From b5fac1ac9587a495188660c23946b298d065ea6d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 30 Apr 2021 00:24:56 +0000 Subject: [PATCH 0001/2168] [cron] Bump distribution date (2021-04-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 266ed629a8..11e9cb1456 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 "2021-04-29" + #define STRING_DISTRIBUTION_DATE "2021-04-30" #endif /** From 636facf40d668bee1cc4c866dab340d1d35d73c4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Apr 2021 02:04:07 -0500 Subject: [PATCH 0002/2168] Silence warning in gcode_D --- Marlin/src/gcode/gcode_d.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 74277291e5..a8a6bdfc3d 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -216,7 +216,8 @@ } break; case 102: { // D102 Test SD Read - card.openFileRead("test.gco"); + char testfile[] = "test.gco"; + card.openFileRead(testfile); if (!card.isFileOpen()) { SERIAL_ECHOLNPAIR("Failed to open test.gco to read."); return; From cfdfd167794de13de75d99c161f61a0898549717 Mon Sep 17 00:00:00 2001 From: David Date: Fri, 30 Apr 2021 08:51:26 +0200 Subject: [PATCH 0003/2168] Fix Thermal Runaway false-alarm in M303, add HeaterWatch::check (#21743) Co-authored-by: Scott Lahteine --- Marlin/src/module/temperature.cpp | 26 +++++++++++++------------- Marlin/src/module/temperature.h | 2 ++ 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 462af7f61a..69f5e9b58e 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -543,7 +543,7 @@ volatile bool Temperature::raw_temps_ready = false; #define GTV(C,B,H) C_GTV(ischamber, C, B_GTV(isbed, B, H)) const uint16_t watch_temp_period = GTV(WATCH_CHAMBER_TEMP_PERIOD, WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); const uint8_t watch_temp_increase = GTV(WATCH_CHAMBER_TEMP_INCREASE, WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); - const celsius_float_t watch_temp_target = celsius_float_t(target - watch_temp_increase + GTV(TEMP_CHAMBER_HYSTERESIS, TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1); + const celsius_float_t watch_temp_target = celsius_float_t(target - (watch_temp_increase + GTV(TEMP_CHAMBER_HYSTERESIS, TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1)); millis_t temp_change_ms = next_temp_ms + SEC_TO_MS(watch_temp_period); celsius_float_t next_watch_temp = 0.0; bool heated = false; @@ -1253,13 +1253,13 @@ void Temperature::manage_heater() { #if WATCH_HOTENDS // Make sure temperature is increasing - if (watch_hotend[e].next_ms && ELAPSED(ms, watch_hotend[e].next_ms)) { // Time to check this extruder? - if (degHotend(e) < watch_hotend[e].target) { // Failed to increase enough? + if (watch_hotend[e].elapsed(ms)) { // Enabled and time to check? + if (watch_hotend[e].check(degHotend(e))) // Increased enough? + start_watching_hotend(e); // If temp reached, turn off elapsed check + else { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error((heater_id_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } - else // Start again if the target is still far off - start_watching_hotend(e); } #endif @@ -1296,13 +1296,13 @@ void Temperature::manage_heater() { #if WATCH_BED // Make sure temperature is increasing - if (watch_bed.elapsed(ms)) { // Time to check the bed? - if (degBed() < watch_bed.target) { // Failed to increase enough? + if (watch_bed.elapsed(ms)) { // Time to check the bed? + if (watch_bed.check(degBed())) // Increased enough? + start_watching_bed(); // If temp reached, turn off elapsed check + else { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error(H_BED, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } - else // Start again if the target is still far off - start_watching_bed(); } #endif // WATCH_BED @@ -1377,11 +1377,11 @@ void Temperature::manage_heater() { #if WATCH_CHAMBER // Make sure temperature is increasing - if (watch_chamber.elapsed(ms)) { // Time to check the chamber? - if (degChamber() < watch_chamber.target) // Failed to increase enough? - _temp_error(H_CHAMBER, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + if (watch_chamber.elapsed(ms)) { // Time to check the chamber? + if (watch_chamber.check(degChamber())) // Increased enough? Error below. + start_watching_chamber(); // If temp reached, turn off elapsed check. else - start_watching_chamber(); // Start again if the target is still far off + _temp_error(H_CHAMBER, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 2bb773f805..adc10c3ccd 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -233,6 +233,8 @@ struct HeaterWatch { inline bool elapsed(const millis_t &ms) { return next_ms && ELAPSED(ms, next_ms); } inline bool elapsed() { return elapsed(millis()); } + inline bool check(const celsius_t curr) { return curr >= target; } + inline void restart(const celsius_t curr, const celsius_t tgt) { if (tgt) { const celsius_t newtarget = curr + INCREASE; From f58b923fd4df7c59a14e91fcd5977feb50774b5b Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Fri, 30 Apr 2021 01:07:18 -0700 Subject: [PATCH 0004/2168] Fix BTT E3 RRF and SKR V2 (Generic PIO) (#21741) Follow-up to #21655 --- ini/stm32f4.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index d6418f439e..ff99296877 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -181,7 +181,7 @@ build_flags = ${stm_flash_drive.build_flags} [env:BIGTREE_E3_RRF] platform = ${common_stm32.platform} extends = common_stm32 -board = genericSTM32F407VGT6 +board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_BIGTREE_E3_RRF build_flags = ${common_stm32.build_flags} -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 @@ -234,7 +234,7 @@ extra_scripts = ${common.extra_scripts} platform = ${common_stm32.platform} platform_packages = ${stm_flash_drive.platform_packages} extends = common_stm32 -board = genericSTM32F407VGT6 +board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld From e4f60f82a4cbcac1921b6bf444fa803910e2adf3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 30 Apr 2021 03:21:59 -0500 Subject: [PATCH 0005/2168] Heater error status --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 2 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 12 ++++++++---- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 75ff1f52c2..2e5f967c2f 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -535,7 +535,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr if (prefix >= 0) lcd_put_wchar(prefix); - lcd_put_u8str(i16tostr3rj(t1)); + lcd_put_u8str(t1 < 0 ? "err" : i16tostr3rj(t1)); lcd_put_wchar('/'); #if !HEATER_IDLE_HANDLER diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 81e89f7cf5..68b75900ef 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -186,10 +186,14 @@ #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, const uint8_t ty) { - 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]); + if (temp < 0) + lcd_put_u8str(tx - 3 * (INFO_FONT_WIDTH) / 2 + 1, ty, "err"); + else { + 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]); + } } #if DO_DRAW_FLOWMETER From 4e4c3ef8fc68afb66ebc434764ba4079c57baf1c Mon Sep 17 00:00:00 2001 From: lujios <83166168+lujios@users.noreply.github.com> Date: Fri, 30 Apr 2021 11:38:30 +0200 Subject: [PATCH 0006/2168] Fix compile with DISTINCT_E_FACTORS + SLIM_LCD_MENUS (#21733) Co-authored-by: Scott Lahteine --- Marlin/src/lcd/menu/menu_advanced.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 463433685e..044797b749 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -350,16 +350,6 @@ void menu_backlash(); #if DISABLED(SLIM_LCD_MENUS) - #if ENABLED(DISTINCT_E_FACTORS) - inline void _reset_e_acceleration_rate(const uint8_t e) { if (e == active_extruder) planner.reset_acceleration_rates(); } - inline void _planner_refresh_e_positioning(const uint8_t e) { - if (e == active_extruder) - planner.refresh_positioning(); - else - planner.steps_to_mm[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; - } - #endif - // M203 / M205 Velocity options void menu_advanced_velocity() { // M203 Max Feedrate @@ -443,7 +433,10 @@ void menu_backlash(); #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(); }); 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); }); + 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, []{ + if (MenuItemBase::itemIndex == active_extruder) + planner.reset_acceleration_rates(); + }); #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(); }); #endif @@ -530,7 +523,13 @@ void menu_advanced_steps_per_mm() { #if ENABLED(DISTINCT_E_FACTORS) 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); }); + EDIT_ITEM_FAST_N(float51, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ + const uint8_t e = MenuItemBase::itemIndex; + if (e == active_extruder) + planner.refresh_positioning(); + else + planner.steps_to_mm[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; + }); #elif E_STEPPERS EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); #endif From 68c010f82ad7a5c5c3dd15ee985654e0f3bc79b5 Mon Sep 17 00:00:00 2001 From: Nikolay March Date: Fri, 30 Apr 2021 12:45:43 +0300 Subject: [PATCH 0007/2168] Sanity-check for COREnn backlash (#21731) --- Marlin/src/inc/SanityCheck.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 97f9a6373a..24ea6ce808 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3034,8 +3034,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " on a MarkForged system."); #elif IS_CORE constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; - static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], + #ifndef CORE_BACKLASH + static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " with your CORE system."); + #endif #endif #endif From 2f537768bc9481a10b25d9f7c5af3627707c836e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 30 Apr 2021 08:30:31 -0500 Subject: [PATCH 0008/2168] MKS Robin flash address --- buildroot/share/PlatformIO/scripts/mks_robin_mini.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py index 4c52035965..3ff9ccf4a6 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py @@ -2,4 +2,4 @@ # buildroot/share/PlatformIO/scripts/mks_robin_mini.py # import marlin -marlin.prepare_robin("0x08005000", "mks_robin_mini.ld", "Robin_mini.bin") +marlin.prepare_robin("0x08007000", "mks_robin_mini.ld", "Robin_mini.bin") From ff41bf5be823bd9564045c1c522adec2f9984ac7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 1 May 2021 01:04:09 +0000 Subject: [PATCH 0009/2168] [cron] Bump distribution date (2021-05-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 11e9cb1456..74fde2f7ac 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 "2021-04-30" + #define STRING_DISTRIBUTION_DATE "2021-05-01" #endif /** From 8c912d7ece490e9b0598d365248d07d6bfd204ae Mon Sep 17 00:00:00 2001 From: ellensp Date: Sat, 1 May 2021 16:15:16 +1200 Subject: [PATCH 0010/2168] Fix SDCARD_CONNECTION default for BTT SKR (#21755) --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 82 +++++++++++-------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 12 --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 18 ---- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 16 ++++ 4 files changed, 66 insertions(+), 62 deletions(-) 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 8c1396d3fe..05072b6c9e 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -52,6 +52,37 @@ #define E0_DIR_PIN P2_13 #define E0_ENABLE_PIN P2_12 + +/** + * _____ _____ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 NC | 3 4 | NC + * 0.18 | 5 6 3.25 NC | 5 6 0.15 + * 1.23 | 7 8 | 3.26 0.16 | 7 8 | 0.18 + * 0.15 | 9 10| 0.17 2.11 | 9 10| 1.30 + * ----- ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN -1 +#define EXP1_04_PIN -1 +#define EXP1_05_PIN -1 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_16 +#define EXP1_08_PIN P0_18 +#define EXP1_09_PIN P2_11 +#define EXP1_10_PIN P1_30 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN P1_31 +#define EXP2_05_PIN P0_18 +#define EXP2_06_PIN P3_25 +#define EXP2_07_PIN P1_23 +#define EXP2_08_PIN P3_26 +#define EXP2_09_PIN P0_15 +#define EXP2_10_PIN P0_17 + + /** * LCD / Controller * @@ -68,26 +99,23 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_26 + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN P1_31 - #elif HAS_WIRED_LCD - #define BTN_EN1 P3_26 - #define BTN_EN2 P3_25 - #define BTN_ENC P2_11 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN - #define SD_DETECT_PIN P1_31 - #define LCD_SDSS P1_23 - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define LCD_SDSS EXP2_07_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP2_05_PIN + #define LCD_PINS_D4 EXP2_09_PIN #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS P2_06 - #define DOGLCD_A0 P0_16 + #define DOGLCD_A0 EXP1_07_PIN #endif #endif // HAS_WIRED_LCD @@ -106,10 +134,6 @@ #endif #endif -#if SD_CONNECTION_IS(LCD) - #define SD_SS_PIN P1_23 -#endif - // Trinamic driver support #if HAS_TRINAMIC_CONFIG @@ -140,10 +164,10 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. #define TMC_USE_SW_SPI - #define TMC_SW_MOSI P0_18 - #define TMC_SW_MISO P0_17 + #define TMC_SW_MOSI EXP2_05_PIN + #define TMC_SW_MISO EXP2_10_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK P0_15 + #define TMC_SW_SCK EXP2_09_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. //#define TMC_SW_SCK P2_06 @@ -186,14 +210,11 @@ // SDCARD_CONNECTION must not be 'LCD'. Nothing should be connected to EXP1/EXP2. //#define SKR_USE_LCD_PINS_FOR_CS #if ENABLED(SKR_USE_LCD_PINS_FOR_CS) - #if SD_CONNECTION_IS(LCD) - #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_PINS_FOR_CS." - #endif - #define X_CS_PIN P1_23 - #define Y_CS_PIN P3_26 - #define Z_CS_PIN P2_11 - #define E0_CS_PIN P3_25 - #define E1_CS_PIN P1_31 + #define X_CS_PIN EXP2_07_PIN + #define Y_CS_PIN EXP2_08_PIN + #define Z_CS_PIN EXP1_09_PIN + #define E0_CS_PIN EXP2_06_PIN + #define E1_CS_PIN EXP2_04_PIN #endif // Example 2: A REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER @@ -201,19 +222,16 @@ // the pins will be in use. So SDCARD_CONNECTION must not be 'LCD'. //#define SKR_USE_LCD_SD_CARD_PINS_FOR_CS #if ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) - #if SD_CONNECTION_IS(LCD) - #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." - #endif #define X_CS_PIN P0_02 #define Y_CS_PIN P0_03 #define Z_CS_PIN P2_06 // We use SD_DETECT_PIN for E0 #undef SD_DETECT_PIN - #define E0_CS_PIN P1_31 + #define E0_CS_PIN EXP2_04_PIN // We use LCD_SDSS pin for E1 #undef LCD_SDSS #define LCD_SDSS -1 - #define E1_CS_PIN P1_23 + #define E1_CS_PIN EXP2_07_PIN #endif // Example 3: Use the driver enable pins for chip-select. diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 89f0e17832..e671429f84 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -367,18 +367,6 @@ #endif // HAS_WIRED_LCD -// -// SD Support -// - -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD -#endif - -#if SD_CONNECTION_IS(LCD) - #define SD_SS_PIN EXP2_07_PIN -#endif - /** * Special pins * P1_30 (37) (NOT 5V tolerant) 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 94165d3948..f3ecf30fc8 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -31,13 +31,6 @@ #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 #endif -// -// SD Connection -// -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD -#endif - // // Servos // @@ -263,13 +256,6 @@ #define EXP2_09_PIN P0_15 #define EXP2_10_PIN P0_17 -// -// SD Connection -// -#if SD_CONNECTION_IS(LCD) - #define SD_SS_PIN EXP2_07_PIN -#endif - /** * _____ _____ * NC | · · | GND 5V | · · | GND @@ -443,10 +429,6 @@ #define LCD_SDSS EXP2_07_PIN // (16) J3-7 & AUX-4 - #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN EXP2_04_PIN // (49) (NOT 5V tolerant) - #endif - #if ENABLED(FYSETC_MINI_12864) #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_07_PIN diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 98e4f8ee26..eadb91a8b3 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -105,12 +105,28 @@ // // SD Support // +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card +#if SD_CONNECTION_IS(LCD) && ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) + #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_PINS_FOR_CS." +#endif + #if SD_CONNECTION_IS(LCD) #define SD_SCK_PIN P0_15 #define SD_MISO_PIN P0_17 #define SD_MOSI_PIN P0_18 + #define SD_SS_PIN EXP2_07_PIN + #define SD_DETECT_PIN EXP2_04_PIN + #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN #define SD_DETECT_PIN P0_27 From ef9ca61039514efef6e2bf100c4b6b1db8f0316c Mon Sep 17 00:00:00 2001 From: ellensp Date: Sat, 1 May 2021 20:21:18 +1200 Subject: [PATCH 0011/2168] Fix Singlenozzle Standby issues (#21759) Fixes #21758 Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_LCD.h | 10 +++++++++ Marlin/src/lcd/menu/menu_temperature.cpp | 2 +- Marlin/src/lcd/menu/menu_tune.cpp | 2 +- Marlin/src/module/temperature.cpp | 26 +++++++++++++----------- Marlin/src/module/temperature.h | 8 +++++--- Marlin/src/module/tool_change.cpp | 4 +++- 6 files changed, 34 insertions(+), 18 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 429877ce84..a6df825ad9 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -640,6 +640,16 @@ #endif #endif +/** + * Disable unused SINGLENOZZLE sub-options + */ +#if DISABLED(SINGLENOZZLE) + #undef SINGLENOZZLE_STANDBY_TEMP +#endif +#if !BOTH(HAS_FAN, SINGLENOZZLE) + #undef SINGLENOZZLE_STANDBY_FAN +#endif + /** * DISTINCT_E_FACTORS affects how some E factors are accessed */ diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 47643cfb57..33a3d2f445 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -171,7 +171,7 @@ void menu_temperature() { #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) LOOP_S_L_N(e, 1, EXTRUDERS) - EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif // diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index feabae437d..1a972f63f2 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -134,7 +134,7 @@ void menu_tune() { #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) LOOP_S_L_N(e, 1, EXTRUDERS) - EDIT_ITEM_FAST_N(uint16_3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif // diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 69f5e9b58e..53d6c14d5b 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -466,9 +466,9 @@ volatile bool Temperature::raw_temps_ready = false; #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) celsius_t Temperature::singlenozzle_temp[EXTRUDERS]; - #if HAS_FAN - uint8_t Temperature::singlenozzle_fan_speed[EXTRUDERS]; - #endif +#endif +#if ENABLED(SINGLENOZZLE_STANDBY_FAN) + uint8_t Temperature::singlenozzle_fan_speed[EXTRUDERS]; #endif #if ENABLED(PROBING_HEATERS_OFF) @@ -2500,20 +2500,22 @@ void Temperature::disable_all_heaters() { #endif // PROBING_HEATERS_OFF -#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) +#if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) void Temperature::singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool) { - #if HAS_FAN + #if ENABLED(SINGLENOZZLE_STANDBY_FAN) singlenozzle_fan_speed[old_tool] = fan_speed[0]; fan_speed[0] = singlenozzle_fan_speed[new_tool]; #endif - singlenozzle_temp[old_tool] = temp_hotend[0].target; - if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { - setTargetHotend(singlenozzle_temp[new_tool], 0); - TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_STATUS_MESSAGE, set_heating_message(0)); - (void)wait_for_hotend(0, false); // Wait for heating or cooling - } + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + singlenozzle_temp[old_tool] = temp_hotend[0].target; + if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { + setTargetHotend(singlenozzle_temp[new_tool], 0); + TERN_(AUTOTEMP, planner.autotemp_update()); + TERN_(HAS_STATUS_MESSAGE, set_heating_message(0)); + (void)wait_for_hotend(0, false); // Wait for heating or cooling + } + #endif } #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index adc10c3ccd..702a3ea04d 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -372,9 +372,11 @@ class Temperature { static inline bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } static inline bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } - #if ENABLED(SINGLENOZZLE_STANDBY_FAN) - static celsius_t singlenozzle_temp[EXTRUDERS]; - #if HAS_FAN + #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) + static celsius_t singlenozzle_temp[EXTRUDERS]; + #endif + #if ENABLED(SINGLENOZZLE_STANDBY_FAN) static uint8_t singlenozzle_fan_speed[EXTRUDERS]; #endif static void singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool); diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 2e5e59c0af..0c5673b31c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1194,7 +1194,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const bool should_move = safe_to_move && !no_move && IsRunning(); if (should_move) { - TERN_(SINGLENOZZLE_STANDBY_TEMP, thermalManager.singlenozzle_change(old_tool, new_tool)); + #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + thermalManager.singlenozzle_change(old_tool, new_tool); + #endif #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) if (should_swap && !too_cold) { From eddce4182b8e3579ae4e74e0f2954d51678ea023 Mon Sep 17 00:00:00 2001 From: hartmannathan <59230071+hartmannathan@users.noreply.github.com> Date: Sat, 1 May 2021 04:43:32 -0400 Subject: [PATCH 0012/2168] Comment correction (#21729) --- Marlin/src/libs/duration_t.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index bd654b7bad..148aa23211 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -115,7 +115,8 @@ struct duration_t { * @brief Formats the duration as a string * @details String will be formated using a "full" representation of duration * - * @param buffer The array pointed to must be able to accommodate 21 bytes + * @param buffer The array pointed to must be able to accommodate 22 bytes + * (21 for the string, 1 more for the terminating nul) * * Output examples: * 123456789012345678901 (strlen) From 05c25b8cdb99fd67047704f65d69e5b8b1797a07 Mon Sep 17 00:00:00 2001 From: tobuh <32395668+tobuh@users.noreply.github.com> Date: Sat, 1 May 2021 10:46:26 +0200 Subject: [PATCH 0013/2168] Fix Power-Loss Save on Pause (#21749) --- Marlin/src/gcode/feature/pause/M125.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 9391b8661b..e65b48545b 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -78,8 +78,9 @@ void GcodeSuite::M125() { // If possible, show an LCD prompt with the 'P' flag const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P')); + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); + if (pause_print(retract, park_point, 0, show_lcd)) { - TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); From b356b4484948305db9fdd6b049b38ab29cfb7cfa Mon Sep 17 00:00:00 2001 From: Sebastiaan Dammann Date: Sun, 2 May 2021 02:38:31 +0200 Subject: [PATCH 0014/2168] Fix Z raise in filament load M701 (#21762) Fixes #21750 --- Marlin/src/gcode/feature/pause/M701_M702.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 6be63346dc..0a649dadd4 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -97,7 +97,7 @@ void GcodeSuite::M701() { }; // Raise the Z axis (with max limit) - const float park_raise = _MIN(0, park_point.z, (Z_MAX_POS) - current_position.z); + const float park_raise = _MIN(park_point.z, (Z_MAX_POS) - current_position.z); move_z_by(park_raise); // Load filament From 9d43570adae1e6835504fc9f42b1fefada54dcb7 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 2 May 2021 12:42:38 +1200 Subject: [PATCH 0015/2168] Add missing ExtUI method (#21763) Fixes #21761 --- Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp index fb66d1f68e..9055e7b430 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp @@ -100,6 +100,10 @@ namespace ExtUI { void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state) { + // Called when any mesh points are updated + } #endif #if ENABLED(POWER_LOSS_RECOVERY) From 741e3c12803077e60bc4842b74a4bf2365e2b3db Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Sat, 1 May 2021 19:59:45 -0500 Subject: [PATCH 0016/2168] Laser Cutter Air Assist (#21753) --- Marlin/Configuration_adv.h | 14 +++++++++---- Marlin/src/feature/spindle_laser.cpp | 16 ++++++++++++++- Marlin/src/feature/spindle_laser.h | 9 ++++++++ Marlin/src/gcode/control/M10-M11.cpp | 3 --- Marlin/src/gcode/control/M7-M9.cpp | 24 ++++++++++++++++++++++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_spindle_laser.cpp | 5 +++++ buildroot/tests/mega2560 | 8 ++++---- 8 files changed, 68 insertions(+), 12 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 149ac610f5..7d89cf5205 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3166,13 +3166,19 @@ //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 #if ENABLED(AIR_EVACUATION) #define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH - #define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin + //#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin #endif - //#define SPINDLE_SERVO // A servo converting an angle to spindle power + //#define AIR_ASSIST // Air Assist control with G-codes M8-M9 + #if ENABLED(AIR_ASSIST) + #define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin + //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin + #endif + + //#define SPINDLE_SERVO // A servo converting an angle to spindle power #ifdef SPINDLE_SERVO - #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control - #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle + #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control + #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle #endif /** diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 78fa75cac6..100b7c4b26 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -71,6 +71,9 @@ void SpindleLaser::init() { #if ENABLED(AIR_EVACUATION) OUT_WRITE(AIR_EVACUATION_PIN, !AIR_EVACUATION_ACTIVE); // Init Vacuum/Blower OFF #endif + #if ENABLED(AIR_ASSIST) + OUT_WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); // Init Air Assist OFF + #endif } #if ENABLED(SPINDLE_LASER_PWM) @@ -147,6 +150,17 @@ void SpindleLaser::apply_power(const uint8_t opwr) { void SpindleLaser::air_evac_toggle() { TOGGLE(AIR_EVACUATION_PIN); } // Toggle state -#endif +#endif // AIR_EVACUATION + +#if ENABLED(AIR_ASSIST) + + // Enable / disable air assist + void SpindleLaser::air_assist_enable() { WRITE(AIR_ASSIST_PIN, AIR_ASSIST_PIN); } // Turn ON + + void SpindleLaser::air_assist_disable() { WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_PIN); } // Turn OFF + + void SpindleLaser::air_assist_toggle() { TOGGLE(AIR_ASSIST_PIN); } // Toggle state + +#endif // AIR_ASSIST #endif // HAS_CUTTER diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index c3454d0b3c..da228cf8a7 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -221,6 +221,15 @@ public: } #endif + #if ENABLED(AIR_ASSIST) + static void air_assist_enable(); // Turn on air assist + static void air_assist_disable(); // Turn off air assist + static void air_assist_toggle(); // Toggle air assist + static inline bool air_assist_state() { // Get current state + return (READ(AIR_ASSIST_PIN) == AIR_ASSIST_ACTIVE); + } + #endif + static inline void disable() { isReady = false; set_enabled(false); } #if HAS_LCD_MENU diff --git a/Marlin/src/gcode/control/M10-M11.cpp b/Marlin/src/gcode/control/M10-M11.cpp index 26f67e6cb6..d5a69dcfcc 100644 --- a/Marlin/src/gcode/control/M10-M11.cpp +++ b/Marlin/src/gcode/control/M10-M11.cpp @@ -25,14 +25,12 @@ #if ENABLED(AIR_EVACUATION) #include "../gcode.h" -#include "../../module/planner.h" #include "../../feature/spindle_laser.h" /** * M10: Vacuum or Blower On */ void GcodeSuite::M10() { - planner.synchronize(); // Wait for move to arrive (TODO: asynchronous) cutter.air_evac_enable(); // Turn on Vacuum or Blower motor } @@ -40,7 +38,6 @@ void GcodeSuite::M10() { * M11: Vacuum or Blower OFF */ void GcodeSuite::M11() { - planner.synchronize(); // Wait for move to arrive (TODO: asynchronous) cutter.air_evac_disable(); // Turn off Vacuum or Blower motor } diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index a33e43288b..f93123eb35 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -61,3 +61,27 @@ void GcodeSuite::M9() { } #endif // COOLANT_CONTROL + +#if ENABLED(AIR_ASSIST) + +#include "../gcode.h" +#include "../../module/planner.h" +#include "../../feature/spindle_laser.h" + +/** + * M8: Air Assist On + */ +void GcodeSuite::M8() { + planner.synchronize(); + cutter.air_assist_enable(); // Turn on Air Assist pin +} + +/** + * M9: Air Assist Off + */ +void GcodeSuite::M9() { + planner.synchronize(); + cutter.air_assist_disable(); // Turn off Air Assist pin +} + +#endif // AIR_ASSIST diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f217c96749..5030f82f90 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -118,6 +118,7 @@ namespace Language_en { PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Pwr"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index f0e702e2dd..a28c614c91 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -56,6 +56,11 @@ EDIT_ITEM(bool, MSG_CUTTER(EVAC_TOGGLE), &evac_state, cutter.air_evac_toggle); #endif + #if ENABLED(AIR_ASSIST) + bool air_assist_state = cutter.air_assist_state(); + EDIT_ITEM(bool, MSG_CUTTER(ASSIST_TOGGLE), &air_assist_state, cutter.air_assist_toggle); + #endif + #if ENABLED(SPINDLE_CHANGE_DIR) if (!is_enabled) { editable.state = is_rev; diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 4ed199df2f..6701cf573b 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -173,9 +173,9 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 + LASER_FEATURE AIR_EVACUATION AIR_ASSIST LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 -exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" +exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" # # Test Laser features with 44780 LCD @@ -183,9 +183,9 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Cooler | Flowmeter | 12 restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE LASER_COOLANT_FLOW_METER + LASER_FEATURE AIR_EVACUATION AIR_ASSIST LASER_COOLANT_FLOW_METER -exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Cooler | Flowmeter | 44780 LCD " "$3" +exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" # # Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER From a95a21a3532b51b793b53306476177d714896f79 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 May 2021 19:32:21 -0500 Subject: [PATCH 0017/2168] Define 'filelist' for dgus/origin --- .../extui/lib/dgus/origin/DGUSDisplayDef.h | 44 +++++++++---------- .../lib/dgus/origin/DGUSScreenHandler.cpp | 2 + 2 files changed, 24 insertions(+), 22 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h index 5c5a315de6..c1890c7c28 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h @@ -24,29 +24,29 @@ #include "../DGUSDisplayDef.h" enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 10, - DGUSLCD_SCREEN_TEMPERATURE = 20, - DGUSLCD_SCREEN_STATUS = 30, - DGUSLCD_SCREEN_STATUS2 = 32, - DGUSLCD_SCREEN_MANUALMOVE = 40, - DGUSLCD_SCREEN_MANUALEXTRUDE=42, - DGUSLCD_SCREEN_FANANDFEEDRATE = 44, - DGUSLCD_SCREEN_FLOWRATES = 46, - DGUSLCD_SCREEN_SDFILELIST = 50, + DGUSLCD_SCREEN_BOOT = 0, + DGUSLCD_SCREEN_MAIN = 10, + DGUSLCD_SCREEN_TEMPERATURE = 20, + DGUSLCD_SCREEN_STATUS = 30, + DGUSLCD_SCREEN_STATUS2 = 32, + DGUSLCD_SCREEN_MANUALMOVE = 40, + DGUSLCD_SCREEN_MANUALEXTRUDE = 42, + DGUSLCD_SCREEN_FANANDFEEDRATE = 44, + DGUSLCD_SCREEN_FLOWRATES = 46, + DGUSLCD_SCREEN_SDFILELIST = 50, DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_PREHEAT=120, - DGUSLCD_SCREEN_UTILITY=110, - DGUSLCD_SCREEN_FILAMENT_HEATING=146, - DGUSLCD_SCREEN_FILAMENT_LOADING=148, - DGUSLCD_SCREEN_FILAMENT_UNLOADING=158, - DGUSLCD_SCREEN_SDPRINTTUNE = 170, - 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, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_POWER_LOSS = 100, + DGUSLCD_SCREEN_PREHEAT = 120, + DGUSLCD_SCREEN_UTILITY = 110, + DGUSLCD_SCREEN_FILAMENT_HEATING = 146, + DGUSLCD_SCREEN_FILAMENT_LOADING = 148, + DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, + DGUSLCD_SCREEN_SDPRINTTUNE = 170, + 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, + DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUSLDC_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp index 8806623b69..73e2f4f6f0 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp @@ -42,6 +42,8 @@ #if ENABLED(SDSUPPORT) + static ExtUI::FileList filelist; + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; From ffbf7a9141ca886dfc799251ad5405dc0542c2af Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 May 2021 20:06:49 -0500 Subject: [PATCH 0018/2168] Fix undefined abl_points --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 735fad015e..3bd96ef495 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -97,6 +97,14 @@ public: int abl_probe_index; #endif + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + int abl_points; + #elif ENABLED(AUTO_BED_LEVELING_3POINT) + static constexpr int abl_points = 3; + #elif ABL_USES_GRID + static constexpr int abl_points = GRID_MAX_POINTS; + #endif + #if ABL_USES_GRID xy_int8_t meshCount; @@ -113,14 +121,6 @@ public: static constexpr xy_uint8_t grid_points = { GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y }; #endif - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - int abl_points; - #elif ENABLED(AUTO_BED_LEVELING_3POINT) - static constexpr int abl_points = 3; - #else - static constexpr int abl_points = GRID_MAX_POINTS; - #endif - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) float Z_offset; #endif From 95a5d63622e26710686ae0ffca5a9326b0c08556 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 May 2021 20:10:16 -0500 Subject: [PATCH 0019/2168] Air Assist tests --- buildroot/tests/mega2560 | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 6701cf573b..b4a3d2b9ac 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -173,7 +173,7 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE AIR_EVACUATION AIR_ASSIST LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" @@ -183,7 +183,7 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air As restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE AIR_EVACUATION AIR_ASSIST LASER_COOLANT_FLOW_METER + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" From 4d544e35e3ed04ee57c5f0242f86551c4e968d0a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 2 May 2021 01:16:57 +0000 Subject: [PATCH 0020/2168] [cron] Bump distribution date (2021-05-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 74fde2f7ac..2ec701cbe5 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 "2021-05-01" + #define STRING_DISTRIBUTION_DATE "2021-05-02" #endif /** From 46eb12da51b50f4fdbd482866e366faee446f3f3 Mon Sep 17 00:00:00 2001 From: vyacheslav-shubin Date: Sun, 2 May 2021 04:28:49 +0300 Subject: [PATCH 0021/2168] ExtUI event for PID tuning start (#21734) --- Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/module/temperature.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index e6452243fd..5603169626 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -57,7 +57,7 @@ namespace ExtUI { enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 }; enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER, COOLER }; enum fan_t : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 }; - enum result_t : uint8_t { PID_BAD_EXTRUDER_NUM, PID_TEMP_TOO_HIGH, PID_TUNING_TIMEOUT, PID_DONE }; + enum result_t : uint8_t { PID_STARTED, PID_BAD_EXTRUDER_NUM, PID_TEMP_TOO_HIGH, PID_TUNING_TIMEOUT, PID_DONE }; constexpr uint8_t extruderCount = EXTRUDERS; constexpr uint8_t hotendCount = HOTENDS; diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 53d6c14d5b..cc7aa6c8e1 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -551,6 +551,8 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); + TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_STARTED)); + if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); From 257ae51275f7112fce716cf1e8ebf7f108f32d97 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 May 2021 21:14:58 -0500 Subject: [PATCH 0022/2168] Use ststm32@~12.1 --- ini/stm32f1.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 94693d65a4..7283adda4b 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -23,7 +23,7 @@ # HAL/STM32 Base Environment values # [common_stm32] -platform = ststm32@~12.0 +platform = ststm32@~12.1 build_flags = ${common.build_flags} -std=gnu++14 -DUSBCON -DUSBD_USE_CDC @@ -36,7 +36,7 @@ src_filter = ${common.default_src_filter} + + Date: Sun, 2 May 2021 03:06:55 -0400 Subject: [PATCH 0023/2168] Allow disable of POWER_TIMEOUT (#21771) Co-authored-by: Scott Lahteine --- Marlin/src/feature/power.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 2f19dae7a6..fb2f1312e0 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -99,6 +99,10 @@ bool Power::is_power_needed() { return false; } +#ifndef POWER_TIMEOUT + #define POWER_TIMEOUT 0 +#endif + void Power::check() { static millis_t nextPowerCheck = 0; millis_t ms = millis(); @@ -106,7 +110,7 @@ void Power::check() { nextPowerCheck = ms + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT))) + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) power_off(); } } From 78de32e5529fdc140a61fbe9ccca338b4fe0abc0 Mon Sep 17 00:00:00 2001 From: Ken Sanislo Date: Sun, 2 May 2021 00:09:23 -0700 Subject: [PATCH 0024/2168] Allow Creality V4 SERVO0 and PROBE pin overrides (#21770) --- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 733e24cfac..421e339058 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -58,10 +58,12 @@ // // Servos // -#ifndef HAS_PIN_27_BOARD - #define SERVO0_PIN PB0 // BLTouch OUT -#else - #define SERVO0_PIN PC6 +#ifndef SERVO0_PIN + #ifndef HAS_PIN_27_BOARD + #define SERVO0_PIN PB0 // BLTouch OUT + #else + #define SERVO0_PIN PC6 + #endif #endif // @@ -71,7 +73,9 @@ #define Y_STOP_PIN PA6 #define Z_STOP_PIN PA7 -#define Z_MIN_PROBE_PIN PB1 // BLTouch IN +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB1 // BLTouch IN +#endif // // Filament Runout Sensor From fbc7a3775af380514f5d1da6af9c06a6565f787f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 May 2021 03:02:24 -0500 Subject: [PATCH 0025/2168] SOFT_RESET_VIA_SERIAL sanity-check --- Marlin/src/inc/SanityCheck.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 24ea6ce808..bb4ec75681 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2215,8 +2215,11 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif /** - * Software Reset on Kill option + * Software Reset options */ +#if ENABLED(SOFT_RESET_VIA_SERIAL) && DISABLED(EMERGENCY_PARSER) + #error "EMERGENCY_PARSER is required to activate SOFT_RESET_VIA_SERIAL." +#endif #if ENABLED(SOFT_RESET_ON_KILL) && !BUTTON_EXISTS(ENC) #error "An encoder button is required or SOFT_RESET_ON_KILL will reset the printer without notice!" #endif From ae06ee24c52abe373e624315b6fa1dd467d02456 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 2 May 2021 18:06:44 -0300 Subject: [PATCH 0026/2168] Fix bad call to 'diskIODriver' (#21775) --- Marlin/src/HAL/STM32/msc_sd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index 20e1ab3cf9..cbfb837875 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -38,7 +38,7 @@ public: return &card.media_usbFlashDrive; #endif #else - return diskIODriver(); + return card.diskIODriver(); #endif } From 30c299fd26af803da9e5b5bb216e80677b9440fe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 May 2021 15:55:20 -0500 Subject: [PATCH 0027/2168] Fix parser temperature rounding --- Marlin/src/gcode/parser.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 8523630098..b3625ec05e 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -371,7 +371,7 @@ public: case TEMPUNIT_K: f -= 273.15f; case TEMPUNIT_F: f = (f - 32) * 0.5555555556f; } - return LROUND(f + 0.5f); + return LROUND(f); } static inline celsius_t value_celsius_diff() { @@ -382,7 +382,7 @@ public: case TEMPUNIT_K: break; case TEMPUNIT_F: f *= 0.5555555556f; } - return LROUND(f + 0.5f); + return LROUND(f); } #else // !TEMPERATURE_UNITS_SUPPORT From cb5e6bfef64ae4bc05db336a5e53a528bb3b7042 Mon Sep 17 00:00:00 2001 From: Vert <45634861+Vertabreak@users.noreply.github.com> Date: Sun, 2 May 2021 17:38:55 -0400 Subject: [PATCH 0028/2168] UBL Mesh Wizard (#21556) Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 2 + Marlin/src/feature/bedlevel/ubl/ubl.cpp | 45 +++++++++++++++++++++++ Marlin/src/gcode/gcode.cpp | 4 ++ Marlin/src/gcode/gcode.h | 4 ++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_ubl.cpp | 49 ++++++++++++++++++++++++- buildroot/tests/FYSETC_F6 | 2 +- 7 files changed, 105 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 442f502c3e..7b03cfe68b 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1491,6 +1491,8 @@ //#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used // as the Z-Height correction value. + //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 164d267ceb..b7a2c380ce 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -35,6 +35,7 @@ unified_bed_leveling ubl; #include "../../../module/planner.h" #include "../../../module/motion.h" #include "../../../module/probe.h" +#include "../../../module/temperature.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" @@ -254,4 +255,48 @@ bool unified_bed_leveling::sanity_check() { return !!error_flag; } +#if ENABLED(UBL_MESH_WIZARD) + + /** + * M1004: UBL Mesh Wizard - One-click mesh creation with or without a probe + */ + void GcodeSuite::M1004() { + + #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "") + #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R255") + + #if HAS_HOTEND + if (parser.seenval('H')) { // Handle H# parameter to set Hotend temp + const celsius_t hotend_temp = parser.value_int(); // Marlin never sends itself F or K, always C + thermalManager.setTargetHotend(hotend_temp, 0); + thermalManager.wait_for_hotend(false); + } + #endif + + #if HAS_HEATED_BED + if (parser.seenval('B')) { // Handle B# parameter to set Bed temp + const celsius_t bed_temp = parser.value_int(); // Marlin never sends itself F or K, always C + thermalManager.setTargetBed(bed_temp); + thermalManager.wait_for_bed(false); + } + #endif + + process_subcommands_now_P(G28_STR); // Home + process_subcommands_now_P(PSTR(ALIGN_GCODE "\n" // Align multi z axis if available + PROBE_GCODE "\n" // Build mesh with available hardware + "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice + + if (parser.seenval('S')) { + char umw_gcode[32]; + sprintf_P(umw_gcode, PSTR("G29S%i"), parser.value_int()); + queue.inject(umw_gcode); + } + + process_subcommands_now_P(PSTR("G29A\nG29F10\n" // Set UBL Active & Fade 10 + "M140S0\nM104S0\n" // Turn off heaters + "M500")); // Store settings + } + +#endif // UBL_MESH_WIZARD + #endif // AUTO_BED_LEVELING_UBL diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index bf26fe5d89..c0c5201222 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -987,6 +987,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 1002: M1002(); break; // M1002: [INTERNAL] Tool-change and Relative E Move #endif + #if ENABLED(UBL_MESH_WIZARD) + case 1004: M1004(); break; // M1004: UBL Mesh Wizard + #endif + #if ENABLED(MAX7219_GCODE) case 7219: M7219(); break; // M7219: Set LEDs, columns, and rows #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 2904d30366..dc0b89e098 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -1079,6 +1079,10 @@ private: static void M1002(); #endif + #if ENABLED(UBL_MESH_WIZARD) + static void M1004(); + #endif + #if ENABLED(MAX7219_GCODE) static void M7219(); #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 5030f82f90..34b2c0bb5b 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -166,6 +166,7 @@ namespace Language_en { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("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_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Measure"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 1ab44856dc..c73be1ef7f 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -37,7 +37,7 @@ #include "../../feature/bedlevel/bedlevel.h" static int16_t ubl_storage_slot = 0, - custom_hotend_temp = 190, + custom_hotend_temp = 150, side_points = 3, ubl_fillin_amount = 5, ubl_height_amount = 1; @@ -603,6 +603,50 @@ void _menu_ubl_tools() { #endif +#if ENABLED(UBL_MESH_WIZARD) + + /** + * UBL Mesh Wizard - One-click mesh creation with or without a probe + */ + void _lcd_ubl_mesh_wizard() { + char ubl_lcd_gcode[30]; + #if HAS_HEATED_BED && HAS_HOTEND + sprintf_P(ubl_lcd_gcode, PSTR("M1004B%iH%iS%i"), custom_bed_temp, custom_hotend_temp, ubl_storage_slot); + #elif HAS_HOTEND + sprintf_P(ubl_lcd_gcode, PSTR("M1004H%iS%i"), custom_hotend_temp, ubl_storage_slot); + #else + sprintf_P(ubl_lcd_gcode, PSTR("M1004S%i"), ubl_storage_slot); + #endif + queue.inject(ubl_lcd_gcode); + } + + void _menu_ubl_mesh_wizard() { + const int16_t total_slots = settings.calc_num_meshes(); + START_MENU(); + BACK_ITEM(MSG_UBL_LEVEL_BED); + + #if HAS_HOTEND + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, thermalManager.hotend_max_target(0)); + #endif + + #if HAS_HEATED_BED + EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, BED_MAX_TARGET); + #endif + + EDIT_ITEM(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, total_slots); + + ACTION_ITEM(MSG_UBL_MESH_WIZARD, _lcd_ubl_mesh_wizard); + + #if ENABLED(G26_MESH_VALIDATION) + SUBMENU(MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + #endif + + ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); + END_MENU(); + } + +#endif + /** * UBL System submenu * @@ -626,6 +670,9 @@ void _lcd_ubl_level_bed() { #if ENABLED(G26_MESH_VALIDATION) SUBMENU(MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); #endif + #if ENABLED(UBL_MESH_WIZARD) + SUBMENU(MSG_UBL_MESH_WIZARD, _menu_ubl_mesh_wizard); + #endif ACTION_ITEM(MSG_UBL_MESH_EDIT, _ubl_goto_map_screen); SUBMENU(MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); SUBMENU(MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/FYSETC_F6 index 3fe59d59a1..9306686af5 100755 --- a/buildroot/tests/FYSETC_F6 +++ b/buildroot/tests/FYSETC_F6 @@ -24,7 +24,7 @@ opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \ L6470_CHAIN_SCK_PIN 53 L6470_CHAIN_MISO_PIN 49 L6470_CHAIN_MOSI_PIN 40 L6470_CHAIN_SS_PIN 42 \ 'ENABLE_RESET_L64XX_CHIPS(V)' NOOP opt_enable RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS EEPROM_CHITCHAT \ - Z_PROBE_ALLEN_KEY AUTO_BED_LEVELING_UBL \ + Z_PROBE_ALLEN_KEY AUTO_BED_LEVELING_UBL UBL_MESH_WIZARD \ OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY DELTA_CALIBRATION_MENU exec_test $1 $2 "DELTA, RAMPS, L6470, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." "$3" From fb2bfe1cef1daeec13760c29d055b4323e65c25c Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 2 May 2021 19:05:15 -0300 Subject: [PATCH 0029/2168] Fix bad DELTA probe move (#21781) --- Marlin/src/module/motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 584e894ae6..7c0f8f404a 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -426,7 +426,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ #endif if (TERN0(IS_KINEMATIC, is_fast)) - TERN(IS_KINEMATIC, NOOP, prepare_line_to_destination()); + TERN(IS_KINEMATIC, prepare_fast_move_to_destination(), NOOP); else prepare_line_to_destination(); From eaa64967b59a12063c6e6cb78ea63bffacaaa1ad Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 3 May 2021 01:04:25 +0000 Subject: [PATCH 0030/2168] [cron] Bump distribution date (2021-05-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2ec701cbe5..88ab7540ab 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 "2021-05-02" + #define STRING_DISTRIBUTION_DATE "2021-05-03" #endif /** From becdac19ea4559c1e636d55d949a15c50cac7888 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 May 2021 21:32:21 -0500 Subject: [PATCH 0031/2168] Temperature cleanup --- Marlin/src/lcd/tft/touch.cpp | 18 +++--- Marlin/src/module/temperature.cpp | 95 +++++++++++-------------------- Marlin/src/module/temperature.h | 54 +++++++----------- 3 files changed, 61 insertions(+), 106 deletions(-) diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index e8a01e889b..83a7ea78b7 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -184,14 +184,16 @@ void Touch::touch(touch_control_t *control) { int8_t heater; heater = control->data; ui.clear_lcd(); - if (heater >= 0) { // HotEnd - #if HOTENDS == 1 - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE), &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); - #else - MenuItemBase::itemIndex = heater; - MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE_N), &thermalManager.temp_hotend[heater].target, 0, thermalManager.hotend_max_target(heater), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); - #endif - } + #if HAS_HOTEND + if (heater >= 0) { // HotEnd + #if HOTENDS == 1 + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE), &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); + #else + MenuItemBase::itemIndex = heater; + MenuItem_int3::action((const char *)GET_TEXT_F(MSG_NOZZLE_N), &thermalManager.temp_hotend[heater].target, 0, thermalManager.hotend_max_target(heater), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + #endif + } + #endif #if HAS_HEATED_BED else if (heater == H_BED) { MenuItem_int3::action((const char *)GET_TEXT_F(MSG_BED), &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index cc7aa6c8e1..6a04efc302 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -447,11 +447,11 @@ volatile bool Temperature::raw_temps_ready = false; temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0, sensor_heater_1, sensor_heater_2, sensor_heater_3, sensor_heater_4, sensor_heater_5, sensor_heater_6, sensor_heater_7); #endif -#ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED +#if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 uint8_t Temperature::consecutive_low_temperature_error[HOTENDS] = { 0 }; #endif -#ifdef MILLISECONDS_PREHEAT_TIME +#if MILLISECONDS_PREHEAT_TIME > 0 millis_t Temperature::preheat_end_time[HOTENDS] = { 0 }; #endif @@ -472,7 +472,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif #if ENABLED(PROBING_HEATERS_OFF) - bool Temperature::paused; + bool Temperature::paused_for_probing; #endif // public: @@ -1320,10 +1320,10 @@ void Temperature::manage_heater() { #if DISABLED(PIDTEMPBED) if (PENDING(ms, next_bed_check_ms) - && TERN1(PAUSE_CHANGE_REQD, paused == last_pause_state) + && TERN1(PAUSE_CHANGE_REQD, paused_for_probing == last_pause_state) ) break; next_bed_check_ms = ms + BED_CHECK_INTERVAL; - TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused); + TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused_for_probing); #endif TERN_(HEATER_IDLE_HANDLER, heater_idle[IDLE_INDEX_BED].update(ms)); @@ -1958,9 +1958,30 @@ void Temperature::updateTemperaturesFromRawValues() { /** * Initialize the temperature manager + * * The manager is implemented by periodic calls to manage_heater() + * + * - Init (and disable) SPI thermocouples like MAX6675 and MAX31865 + * - Disable RUMBA JTAG to accommodate a thermocouple extension + * - Read-enable thermistors with a read-enable pin + * - Init HEATER and COOLER pins for OUTPUT in OFF state + * - Init the FAN pins as PWM or OUTPUT + * - Init the SPI interface for SPI thermocouples + * - Init ADC according to the HAL + * - Set thermistor pins to analog inputs according to the HAL + * - Start the Temperature ISR timer + * - Init the AUTO FAN pins as PWM or OUTPUT + * - Wait 250ms for temperatures to settle + * - Init temp_range[], used for catching min/maxtemp */ void Temperature::init() { + + TERN_(PROBING_HEATERS_OFF, paused_for_probing = false); + + #if BOTH(PIDTEMP, PID_EXTRUSION_SCALING) + last_e_position = 0; + #endif + // Init (and disable) SPI thermocouples #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX6675_CS) OUT_WRITE(MAX6675_CS_PIN, HIGH); @@ -2017,10 +2038,6 @@ void Temperature::init() { OUT_WRITE(TEMP_1_TR_ENABLE_PIN, ENABLED(TEMP_SENSOR_1_IS_MAX_TC)); #endif - #if BOTH(PIDTEMP, PID_EXTRUSION_SCALING) - last_e_position = 0; - #endif - #if HAS_HEATER_0 #ifdef BOARD_OPENDRAIN_MOSFETS OUT_WRITE_OD(HEATER_0_PIN, HEATER_0_INVERTING); @@ -2276,55 +2293,8 @@ void Temperature::init() { while (analog_to_celsius_cooler(mintemp_raw_COOLER) > COOLER_MINTEMP) mintemp_raw_COOLER += TEMPDIR(COOLER) * (OVERSAMPLENR); while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif - - TERN_(PROBING_HEATERS_OFF, paused = false); } -#if WATCH_HOTENDS - /** - * Start Heating Sanity Check for hotends that are below - * their target temperature by a configurable margin. - * This is called when the temperature is set. (M104, M109) - */ - void Temperature::start_watching_hotend(const uint8_t E_NAME) { - const uint8_t ee = HOTEND_INDEX; - watch_hotend[ee].restart(degHotend(ee), degTargetHotend(ee)); - } -#endif - -#if WATCH_BED - /** - * Start Heating Sanity Check for hotends that are below - * their target temperature by a configurable margin. - * This is called when the temperature is set. (M140, M190) - */ - void Temperature::start_watching_bed() { - watch_bed.restart(degBed(), degTargetBed()); - } -#endif - -#if WATCH_CHAMBER - /** - * Start Heating Sanity Check for chamber that is below - * its target temperature by a configurable margin. - * This is called when the temperature is set. (M141, M191) - */ - void Temperature::start_watching_chamber() { - watch_chamber.restart(degChamber(), degTargetChamber()); - } -#endif - -#if WATCH_COOLER - /** - * Start Cooling Sanity Check for cooler that is above - * its target temperature by a configurable margin. - * This is called when the temperature is set. (M143, M193) - */ - void Temperature::start_watching_cooler() { - watch_cooler.restart(degCooler(), degTargetCooler()); - } -#endif - #if HAS_THERMAL_PROTECTION Temperature::tr_state_machine_t Temperature::tr_state_machine[NR_HEATER_RUNAWAY]; // = { { TRInactive, 0 } }; @@ -2487,8 +2457,8 @@ void Temperature::disable_all_heaters() { #if ENABLED(PROBING_HEATERS_OFF) void Temperature::pause(const bool p) { - if (p != paused) { - paused = p; + if (p != paused_for_probing) { + paused_for_probing = p; if (p) { HOTEND_LOOP() heater_idle[e].expire(); // Timeout immediately TERN_(HAS_HEATED_BED, heater_idle[IDLE_INDEX_BED].expire()); // Timeout immediately @@ -2773,17 +2743,16 @@ void Temperature::readings_ready() { const int8_t tdir = temp_dir[e]; if (tdir) { const int16_t rawtemp = temp_hotend[e].raw * tdir; // normal direction, +rawtemp, else -rawtemp - const bool heater_on = (temp_hotend[e].target > 0 - || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount) > 0 - ); if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); + + const bool heater_on = (temp_hotend[e].target > 0 || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount > 0)); if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) #endif min_temp_error((heater_id_t)e); } - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 else consecutive_low_temperature_error[e] = 0; #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 702a3ea04d..148e9eec54 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -462,11 +462,11 @@ class Temperature { static int16_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 static uint8_t consecutive_low_temperature_error[HOTENDS]; #endif - #ifdef MILLISECONDS_PREHEAT_TIME + #if MILLISECONDS_PREHEAT_TIME > 0 static millis_t preheat_end_time[HOTENDS]; #endif @@ -475,7 +475,7 @@ class Temperature { #endif #if ENABLED(PROBING_HEATERS_OFF) - static bool paused; + static bool paused_for_probing; #endif public: @@ -610,7 +610,7 @@ class Temperature { /** * Preheating hotends */ - #ifdef MILLISECONDS_PREHEAT_TIME + #if MILLISECONDS_PREHEAT_TIME > 0 static inline bool is_preheating(const uint8_t E_NAME) { return preheat_end_time[HOTEND_INDEX] && PENDING(millis(), preheat_end_time[HOTEND_INDEX]); } @@ -653,17 +653,11 @@ class Temperature { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].target); } - #if WATCH_HOTENDS - static void start_watching_hotend(const uint8_t e=0); - #else - static inline void start_watching_hotend(const uint8_t=0) {} - #endif - #if HAS_HOTEND static void setTargetHotend(const celsius_t celsius, const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; - #ifdef MILLISECONDS_PREHEAT_TIME + #if MILLISECONDS_PREHEAT_TIME > 0 if (celsius == 0) reset_preheat_time(ee); else if (temp_hotend[ee].target == 0) @@ -702,6 +696,14 @@ class Temperature { return ABS(wholeDegHotend(e) - temp) < (TEMP_HYSTERESIS); } + // Start watching a Hotend to make sure it's really heating up + static inline void start_watching_hotend(const uint8_t E_NAME) { + UNUSED(HOTEND_INDEX); + #if WATCH_HOTENDS + watch_hotend[HOTEND_INDEX].restart(degHotend(HOTEND_INDEX), degTargetHotend(HOTEND_INDEX)); + #endif + } + #endif // HAS_HOTEND #if HAS_HEATED_BED @@ -715,11 +717,8 @@ class Temperature { static inline bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } static inline bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } - #if WATCH_BED - static void start_watching_bed(); - #else - static inline void start_watching_bed() {} - #endif + // Start watching the Bed to make sure it's really heating up + static inline void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } static void setTargetBed(const celsius_t celsius) { TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); @@ -752,12 +751,6 @@ class Temperature { static bool wait_for_probe(const celsius_t target_temp, bool no_wait_for_cooling=true); #endif - #if WATCH_PROBE - static void start_watching_probe(); - #else - static inline void start_watching_probe() {} - #endif - #if HAS_TEMP_CHAMBER #if ENABLED(SHOW_TEMP_ADC_VALUES) static inline int16_t rawChamberTemp() { return temp_chamber.raw; } @@ -772,17 +765,13 @@ class Temperature { #endif #endif - #if WATCH_CHAMBER - static void start_watching_chamber(); - #else - static inline void start_watching_chamber() {} - #endif - #if HAS_HEATED_CHAMBER static void setTargetChamber(const celsius_t celsius) { temp_chamber.target = _MIN(celsius, CHAMBER_MAX_TARGET); start_watching_chamber(); } + // Start watching the Chamber to make sure it's really heating up + static inline void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } #endif #if HAS_TEMP_COOLER @@ -799,17 +788,13 @@ class Temperature { #endif #endif - #if WATCH_COOLER - static void start_watching_cooler(); - #else - static inline void start_watching_cooler() {} - #endif - #if HAS_COOLER static inline void setTargetCooler(const celsius_t celsius) { temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET); start_watching_cooler(); } + // Start watching the Cooler to make sure it's really cooling down + static inline void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } #endif /** @@ -860,7 +845,6 @@ class Temperature { #if ENABLED(PROBING_HEATERS_OFF) static void pause(const bool p); - static inline bool is_paused() { return paused; } #endif #if HEATER_IDLE_HANDLER From 9dd884a324e82c74e8e78c987d490a297bafbdc0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 May 2021 21:32:42 -0500 Subject: [PATCH 0032/2168] Drop early_safe_delay --- Marlin/src/core/utility.cpp | 12 ------------ Marlin/src/core/utility.h | 5 ----- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 8 ++++---- 3 files changed, 4 insertions(+), 21 deletions(-) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 385a572029..3d7897f95a 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -35,18 +35,6 @@ void safe_delay(millis_t ms) { thermalManager.manage_heater(); // This keeps us safe if too many small safe_delay() calls are made } -#if ENABLED(MARLIN_DEV_MODE) - void early_safe_delay(millis_t ms) { - while (ms > 50) { - ms -= 50; - delay(50); - watchdog_refresh(); - } - delay(ms); - watchdog_refresh(); - } -#endif - // A delay to provide brittle hosts time to receive bytes #if ENABLED(SERIAL_OVERRUN_PROTECTION) diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 0e1c109be1..d774b007b6 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -26,11 +26,6 @@ #include "../core/millis_t.h" void safe_delay(millis_t ms); // Delay ensuring that temperatures are updated and the watchdog is kept alive. -#if ENABLED(MARLIN_DEV_MODE) - void early_safe_delay(millis_t ms); // Delay ensuring that the watchdog is kept alive. Can be used before the Temperature ISR starts. -#else - inline void early_safe_delay(millis_t ms) { safe_delay(ms); } -#endif #if ENABLED(SERIAL_OVERRUN_PROTECTION) void serial_delay(const millis_t ms); diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 1fdc291642..1a07b7ab75 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -160,14 +160,14 @@ bool MarlinUI::detected() { return true; } #endif u8g.firstPage(); do { draw_custom_bootscreen(f); } while (u8g.nextPage()); - if (frame_time) early_safe_delay(frame_time); + if (frame_time) safe_delay(frame_time); } #ifndef CUSTOM_BOOTSCREEN_TIMEOUT #define CUSTOM_BOOTSCREEN_TIMEOUT 2500 #endif #if CUSTOM_BOOTSCREEN_TIMEOUT - early_safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); + safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); #endif } #endif // SHOW_CUSTOM_BOOTSCREEN @@ -226,7 +226,7 @@ bool MarlinUI::detected() { return true; } constexpr millis_t frame_time = MARLIN_BOOTSCREEN_FRAME_TIME; LOOP_L_N(f, COUNT(marlin_bootscreen_animation)) { draw_bootscreen_bmp((uint8_t*)pgm_read_ptr(&marlin_bootscreen_animation[f])); - if (frame_time) early_safe_delay(frame_time); + if (frame_time) safe_delay(frame_time); } #endif } @@ -235,7 +235,7 @@ bool MarlinUI::detected() { return true; } void MarlinUI::show_marlin_bootscreen() { for (uint8_t q = bootscreen_pages; q--;) { draw_marlin_bootscreen(q == 0); - if (q) early_safe_delay((BOOTSCREEN_TIMEOUT) / bootscreen_pages); + if (q) safe_delay((BOOTSCREEN_TIMEOUT) / bootscreen_pages); } } From dc187690109b9f66673bb6675c098af0644d40e1 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 2 May 2021 23:37:54 -0300 Subject: [PATCH 0033/2168] Prevent watchdog reset in setup() (#21776) Cause `manage_heaters` to only reset the watchdog and return until `setup()` is completed. Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_adv.h | 5 ----- Marlin/src/module/temperature.cpp | 18 ++---------------- Marlin/src/module/temperature.h | 4 ---- 3 files changed, 2 insertions(+), 25 deletions(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 735e6464d9..19ab98fed3 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -370,11 +370,6 @@ #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 - // Full Touch Screen needs 'tft/xpt2046' #if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI) #define HAS_TFT_XPT2046 1 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 6a04efc302..2f1a54e91d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -420,10 +420,6 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, // private: -#if EARLY_WATCHDOG - bool Temperature::inited = false; -#endif - volatile bool Temperature::raw_temps_ready = false; #if ENABLED(PID_EXTRUSION_SCALING) @@ -1205,11 +1201,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { * - Update the heated bed PID output value */ void Temperature::manage_heater() { - - #if EARLY_WATCHDOG - // If thermal manager is still not running, make sure to at least reset the watchdog! - if (!inited) return watchdog_refresh(); - #endif + if (marlin_state == MF_INITIALIZING) return watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! #if ENABLED(EMERGENCY_PARSER) if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); @@ -2015,12 +2007,6 @@ void Temperature::init() { TERN_(TEMP_SENSOR_1_IS_MAX6675, max6675_1.begin()); #endif - #if EARLY_WATCHDOG - // Flag that the thermalManager should be running - if (inited) return; - inited = true; - #endif - #if MB(RUMBA) // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector #define _AD(N) (TEMP_SENSOR_##N##_IS_AD595 || TEMP_SENSOR_##N##_IS_AD8495) @@ -2209,7 +2195,7 @@ void Temperature::init() { #endif // Wait for temperature measurement to settle - delay(250); + //delay(250); #if HAS_HOTEND diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 148e9eec54..96ff8b5895 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -419,10 +419,6 @@ class Temperature { private: - #if ENABLED(EARLY_WATCHDOG) - static bool inited; // If temperature controller is running - #endif - static volatile bool raw_temps_ready; #if ENABLED(WATCH_HOTENDS) From 65b1139d93b3080c2eb4f56373bf35fe2945976a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 4 May 2021 00:59:46 +0000 Subject: [PATCH 0034/2168] [cron] Bump distribution date (2021-05-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 88ab7540ab..5f169f5b05 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 "2021-05-03" + #define STRING_DISTRIBUTION_DATE "2021-05-04" #endif /** From 01825d883eac8859547ae92f2b3c01b48b121bec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 May 2021 20:09:21 -0500 Subject: [PATCH 0035/2168] Apply SBI/CBI/TEST in HAL --- Marlin/src/HAL/LPC1768/main.cpp | 2 +- Marlin/src/HAL/STM32/HAL_MinSerial.cpp | 4 ++-- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 25 +++++++++++------------- Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp | 2 +- 4 files changed, 15 insertions(+), 18 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 08fb1a1ed5..ef0dc42c78 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -117,7 +117,7 @@ void HAL_init() { PinCfg.Pinmode = 2; // no pull-up/pull-down PINSEL_ConfigPin(&PinCfg); // now set CLKOUT_EN bit - LPC_SC->CLKOUTCFG |= (1<<8); + SBI(LPC_SC->CLKOUTCFG, 8); #endif USB_Init(); // USB Initialization diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp index 823bb6e8f5..7268eed591 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -71,8 +71,8 @@ static void TXBegin() { volatile uint32_t ICER[32]; }; - NVICMin * nvicBase = (NVICMin*)0xE000E100; - nvicBase->ICER[nvicIndex / 32] |= _BV32(nvicIndex % 32); + NVICMin *nvicBase = (NVICMin*)0xE000E100; + SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F); // We NEED memory barriers to ensure Interrupts are actually disabled! // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 6039593f46..c1a56101ad 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -45,7 +45,6 @@ #define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000) #define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200) - void SDRAM_Initialization_Sequence(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command) { __IO uint32_t tmpmrd =0; @@ -192,7 +191,7 @@ void LTDC_Config() { hltdc_F.Instance = LTDC; -/* Layer0 Configuration ------------------------------------------------------*/ + /* Layer0 Configuration ------------------------------------------------------*/ /* Windowing configuration */ pLayerCfg.WindowX0 = 0; @@ -289,22 +288,21 @@ void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint uint16_t offline = TFT_WIDTH - (ex - sx); uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx]; - DMA2D->CR &= ~(1 << 0); + CBI(DMA2D->CR, 0); DMA2D->CR = 3 << 16; DMA2D->OPFCCR = 0X02; DMA2D->OOR = offline; DMA2D->OMAR = addr; DMA2D->NLR = (ey - sy) | ((ex - sx) << 16); DMA2D->OCOLR = color; - DMA2D->CR |= 1<<0; + SBI(DMA2D->CR, 0); uint32_t timeout = 0; - while((DMA2D->ISR & (1<<1)) == 0) - { + while (!TEST(DMA2D->ISR, 1)) { timeout++; - if(timeout>0X1FFFFF)break; + if (timeout > 0x1FFFFF) break; } - DMA2D->IFCR |= 1<<1; + SBI(DMA2D->IFCR, 1); } void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) { @@ -314,7 +312,7 @@ void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uin uint16_t offline = TFT_WIDTH - (ex - sx); uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx]; - DMA2D->CR &= ~(1 << 0); + CBI(DMA2D->CR, 0) DMA2D->CR = 0 << 16; DMA2D->FGPFCCR = 0X02; DMA2D->FGOR = 0; @@ -322,15 +320,14 @@ void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uin DMA2D->FGMAR = (uint32_t)colors; DMA2D->OMAR = addr; DMA2D->NLR = (ey - sy) | ((ex - sx) << 16); - DMA2D->CR |= 1<<0; + SBI(DMA2D->CR, 0); uint32_t timeout = 0; - while((DMA2D->ISR & (1<<1)) == 0) - { + while (!TEST(DMA2D->ISR, 1)) { timeout++; - if(timeout>0X1FFFFF)break; + if (timeout > 0x1FFFFF) break; } - DMA2D->IFCR |= 1<<1; + SBI(DMA2D->IFCR, 1); } void TFT_LTDC::WriteData(uint16_t data) { diff --git a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp index 2cb75bb1e9..0fc3d014d4 100644 --- a/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp @@ -55,7 +55,7 @@ static void TXBegin() { nvic_irq_disable(dev->irq_num); // Use this if removing libmaple - //NVIC_BASE->ICER[1] |= _BV(irq - 32); + //SBI(NVIC_BASE->ICER[1], irq - 32); // We NEED memory barriers to ensure Interrupts are actually disabled! // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) From dfc906930c9b31ddd4d70e9c0ccf15e369abd188 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 May 2021 20:55:05 -0500 Subject: [PATCH 0036/2168] Pause and PLR refinements - Move `pause_print` argument `unload_length` after `show_lcd` so it's next to `DXC_ARGS`. - Tweak the position and conditions of PLR save in `resume_print`. - Add `Nozzle::park_mode_0_height` accessor to get the raised Z height. - Remove extraneous `recovery.save` from `dwin.cpp`. - Move PLR `info.volumetric...` to `flag`. - Remove some G-code spaces in PLR code - Document `pause.h` function declarations. --- Marlin/src/feature/pause.cpp | 25 +++++++------ Marlin/src/feature/pause.h | 44 ++++++++++++++++++----- Marlin/src/feature/powerloss.cpp | 48 ++++++++++++++----------- Marlin/src/feature/powerloss.h | 6 ++-- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 2 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 3 -- Marlin/src/libs/nozzle.cpp | 24 ++++++++----- Marlin/src/libs/nozzle.h | 1 + 9 files changed, 99 insertions(+), 56 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 867502712c..93b4a2aa81 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -316,7 +316,7 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, ); #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) - constexpr float mix_multiplier = 1.0; + constexpr float mix_multiplier = 1.0f; #endif if (!ensure_safe_temperature(false, mode)) { @@ -371,7 +371,7 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, */ uint8_t did_pause_print = 0; -bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const_float_t unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { +bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const_float_t unload_length/*=0*/ DXC_ARGS) { DEBUG_SECTION(pp, "pause_print", true); DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); @@ -394,7 +394,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const_float // Pause the print job and timer #if ENABLED(SDSUPPORT) - if (IS_SD_PRINTING()) { + const bool was_sd_printing = IS_SD_PRINTING(); + if (was_sd_printing) { card.pauseSDPrint(); ++did_pause_print; // Indicate SD pause also } @@ -418,7 +419,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const_float unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); } - // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) + // Park the nozzle by doing a Minimum Z Raise followed by an XY Move if (!axes_should_home()) nozzle.park(0, park_point); @@ -630,9 +631,6 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ // Set extruder to saved position planner.set_e_position_mm((destination.e = current_position.e = resume_position.e)); - // Write PLR now to update the z axis value - TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); - ui.pause_show_message(PAUSE_MESSAGE_STATUS); #ifdef ACTION_ON_RESUMED @@ -645,8 +643,16 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR)); + // Resume the print job timer if it was running + if (print_job_timer.isPaused()) print_job_timer.start(); + #if ENABLED(SDSUPPORT) - if (did_pause_print) { card.startFileprint(); --did_pause_print; } + if (did_pause_print) { + --did_pause_print; + card.startFileprint(); + // Write PLR now to update the z axis value + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); + } #endif #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN @@ -655,9 +661,6 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HAS_FILAMENT_SENSOR, runout.reset()); - // Resume the print job timer if it was running - if (print_job_timer.isPaused()) print_job_timer.start(); - TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); TERN_(HAS_LCD_MENU, ui.return_to_status()); } diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index facd8d8dee..d2c45e44a5 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -85,19 +85,47 @@ extern uint8_t did_pause_print; #define DXC_SAY #endif -bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const_float_t unload_length=0, const bool show_lcd=false DXC_PARAMS); +// Pause the print. If unload_length is set, do a Filament Unload +bool pause_print( + const_float_t retract, // (mm) Retraction length + const xyz_pos_t &park_point, // Parking XY Position and Z Raise + const bool show_lcd=false, // Set LCD status messages? + const_float_t unload_length=0 // (mm) Filament Change Unload Length - 0 to skip + DXC_PARAMS // Dual-X-Carriage extruder index +); -void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); +void wait_for_confirmation( + const bool is_reload=false, // Reload Filament? (otherwise Resume Print) + const int8_t max_beep_count=0 // Beep alert for attention + DXC_PARAMS // Dual-X-Carriage extruder index +); -void resume_print(const_float_t slow_load_length=0, const_float_t fast_load_length=0, const_float_t extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, - const int8_t max_beep_count=0, const celsius_t targetTemp=0 DXC_PARAMS); +void resume_print( + const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move + const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move + const_float_t extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length + const int8_t max_beep_count=0, // Beep alert for attention + const celsius_t targetTemp=0 // (°C) A target temperature for the hotend + DXC_PARAMS // Dual-X-Carriage extruder index +); -bool load_filament(const_float_t slow_load_length=0, const_float_t fast_load_length=0, const_float_t extrude_length=0, const int8_t max_beep_count=0, - const bool show_lcd=false, const bool pause_for_user=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT DXC_PARAMS); +bool load_filament( + const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move + const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move + const_float_t extrude_length=0, // (mm) Purge length + const int8_t max_beep_count=0, // Beep alert for attention + const bool show_lcd=false, // Set LCD status messages? + const bool pause_for_user=false, // Pause for user before returning? + const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply + DXC_PARAMS // Dual-X-Carriage extruder index +); -bool unload_filament(const_float_t unload_length, const bool show_lcd=false, const PauseMode mode=PAUSE_MODE_PAUSE_PRINT +bool unload_filament( + const_float_t unload_length, // (mm) Filament Unload Length - 0 to skip + const bool show_lcd=false, // Set LCD status messages? + const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) - , const_float_t mix_multiplier=1.0 + , const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) #endif ); diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index dd4c78726a..10488af709 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -149,6 +149,8 @@ void PrintJobRecovery::prepare() { */ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) { + // We don't check IS_SD_PRINTING here so a save may occur during a pause + #if SAVE_INFO_INTERVAL_MS > 0 static millis_t next_save_ms; // = 0 millis_t ms = millis(); @@ -192,7 +194,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ #endif #if DISABLED(NO_VOLUMETRICS) - info.volumetric_enabled = parser.volumetric_enabled; + info.flag.volumetric_enabled = parser.volumetric_enabled; #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) info.filament_size[e] = planner.filament_size[e]; #else @@ -366,13 +368,16 @@ void PrintJobRecovery::resume() { } #endif - // Reset E, raise Z, home XY... + // + // Home the axes that can safely be homed, and + // establish the current position as best we can + // #if Z_HOME_DIR > 0 - // If Z homing goes to max, just reset E and home all + // If Z homing goes to max... gcode.process_subcommands_now_P(PSTR( - "G92.9 E0\n" - "G28R0" + "G92.9 E0\n" // Reset E to 0 + "G28R0" // Home all axes (no raise) )); #else // "G92.9 E0 ..." @@ -391,19 +396,20 @@ void PrintJobRecovery::resume() { #endif - #ifdef POWER_LOSS_ZHOME_POS - // If defined move to a safe Z homing position that avoids the print + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) + // Move to a safe XY position where Z can home while avoiding the print. + // If Z_SAFE_HOMING is enabled, its position must also be outside the print area! constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS; - sprintf_P(cmd, PSTR("G1 X%s Y%s F1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); + sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); gcode.process_subcommands_now(cmd); #endif - // Ensure that all axes are marked as homed + // Mark all axes as having been homed (no effect on current_position) set_all_homed(); #if ENABLED(POWER_LOSS_RECOVER_ZHOME) - // Now move to ZsavedPos + POWER_LOSS_ZRAISE - sprintf_P(cmd, PSTR("G1 F500 Z%s"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1)); + // Z was homed. Now move Z back up to the saved Z height, plus the POWER_LOSS_ZRAISE. + sprintf_P(cmd, PSTR("G1Z%sF500"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1)); gcode.process_subcommands_now(cmd); #endif @@ -411,16 +417,16 @@ void PrintJobRecovery::resume() { #if DISABLED(NO_VOLUMETRICS) #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) { - sprintf_P(cmd, PSTR("M200 T%i D%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); + sprintf_P(cmd, PSTR("M200T%iD%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); gcode.process_subcommands_now(cmd); } - if (!info.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200 T%i D0"), info.active_extruder); + if (!info.flag.volumetric_enabled) { + sprintf_P(cmd, PSTR("M200T%iD0"), info.active_extruder); gcode.process_subcommands_now(cmd); } #else - if (info.volumetric_enabled) { - sprintf_P(cmd, PSTR("M200 D%s"), dtostrf(info.filament_size[0], 1, 3, str_1)); + if (info.flag.volumetric_enabled) { + sprintf_P(cmd, PSTR("M200D%s"), dtostrf(info.filament_size[0], 1, 3, str_1)); gcode.process_subcommands_now(cmd); } #endif @@ -437,13 +443,13 @@ void PrintJobRecovery::resume() { FANS_LOOP(i) { const int f = info.fan_speed[i]; if (f) { - sprintf_P(cmd, PSTR("M106 P%i S%i"), i, f); + sprintf_P(cmd, PSTR("M106P%iS%i"), i, f); gcode.process_subcommands_now(cmd); } } #endif - // Restore retract and hop state + // Restore retract and hop state from an active `G10` command #if ENABLED(FWRETRACT) LOOP_L_N(e, EXTRUDERS) { if (info.retract[e] != 0.0) { @@ -458,7 +464,7 @@ void PrintJobRecovery::resume() { // Restore leveling state before 'G92 Z' to ensure // the Z stepper count corresponds to the native Z. if (info.fade || info.flag.leveling) { - sprintf_P(cmd, PSTR("M420 S%i Z%s"), int(info.flag.leveling), dtostrf(info.fade, 1, 1, str_1)); + sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); gcode.process_subcommands_now(cmd); } #endif @@ -468,11 +474,11 @@ void PrintJobRecovery::resume() { #endif // Un-retract if there was a retract at outage - #if POWER_LOSS_RETRACT_LEN + #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_RETRACT_LEN) " F3000")); #endif - // Additional purge if configured + // Additional purge on resume if configured #if POWER_LOSS_PURGE_LEN sprintf_P(cmd, PSTR("G1 E%d F3000"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); gcode.process_subcommands_now(cmd); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index ad34de6e53..0777466cc1 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -70,7 +70,6 @@ typedef struct { #endif #if DISABLED(NO_VOLUMETRICS) - bool volumetric_enabled; float filament_size[EXTRUDERS]; #endif @@ -116,7 +115,10 @@ typedef struct { bool dryrun:1; // M111 S8 bool allow_cold_extrusion:1; // M302 P1 #if ENABLED(HAS_LEVELING) - bool leveling:1; + bool leveling:1; // M420 S + #endif + #if DISABLED(NO_VOLUMETRICS) + bool volumetric_enabled:1; // M200 S D #endif } flag; diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index e65b48545b..dcd3e99f7a 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -80,7 +80,7 @@ void GcodeSuite::M125() { TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); - if (pause_print(retract, park_point, 0, show_lcd)) { + if (pause_print(retract, park_point, show_lcd, 0)) { if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 1033025fe3..6cab3ad352 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -149,7 +149,7 @@ void GcodeSuite::M600() { #endif ); - if (pause_print(retract, park_point, unload_length, true DXC_PASS)) { + if (pause_print(retract, park_point, true, unload_length DXC_PASS)) { #if ENABLED(MMU2_MENUS) mmu2_M600(); resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS); diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 9fdf401b57..dc729263db 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -2298,9 +2298,6 @@ void HMI_PauseOrStop() { if (HMI_flag.select_flag) { HMI_flag.pause_action = true; ICON_Continue(); - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.enabled) recovery.save(true); - #endif queue.inject_P(PSTR("M25")); } else { diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 6918d2fd80..e277216ab4 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -225,6 +225,18 @@ Nozzle nozzle; #if ENABLED(NOZZLE_PARK_FEATURE) + float Nozzle::park_mode_0_height(const_float_t park_z) { + // Apply a minimum raise, if specified. Use park.z as a minimum height instead. + return _MAX(park_z, // Minimum height over 0 based on input + _MIN(Z_MAX_POS, // Maximum height is fixed + #ifdef NOZZLE_PARK_Z_RAISE_MIN + NOZZLE_PARK_Z_RAISE_MIN + // Minimum raise... + #endif + current_position.z // ...over current position + ) + ); + } + void Nozzle::park(const uint8_t z_action, const xyz_pos_t &park/*=NOZZLE_PARK_POINT*/) { constexpr feedRate_t fr_xy = NOZZLE_PARK_XY_FEEDRATE, fr_z = NOZZLE_PARK_Z_FEEDRATE; @@ -237,15 +249,9 @@ Nozzle nozzle; do_blocking_move_to_z(_MIN(current_position.z + park.z, Z_MAX_POS), fr_z); break; - default: { - // Apply a minimum raise, overriding G27 Z - const float min_raised_z =_MIN(Z_MAX_POS, current_position.z - #ifdef NOZZLE_PARK_Z_RAISE_MIN - + NOZZLE_PARK_Z_RAISE_MIN - #endif - ); - do_blocking_move_to_z(_MAX(park.z, min_raised_z), fr_z); - } break; + default: // Raise by NOZZLE_PARK_Z_RAISE_MIN, use park.z as a minimum height + do_blocking_move_to_z(park_mode_0_height(park.z), fr_z); + break; } do_blocking_move_to_xy( diff --git a/Marlin/src/libs/nozzle.h b/Marlin/src/libs/nozzle.h index d1706f0b31..7bbd0e35c1 100644 --- a/Marlin/src/libs/nozzle.h +++ b/Marlin/src/libs/nozzle.h @@ -83,6 +83,7 @@ class Nozzle { #if ENABLED(NOZZLE_PARK_FEATURE) + static float park_mode_0_height(const_float_t park_z) _Os; static void park(const uint8_t z_action, const xyz_pos_t &park=NOZZLE_PARK_POINT) _Os; #endif From f4f41d01bfe287f9f0addc802b78bdf190f97fbb Mon Sep 17 00:00:00 2001 From: Vert <45634861+Vertabreak@users.noreply.github.com> Date: Mon, 3 May 2021 22:07:57 -0400 Subject: [PATCH 0037/2168] UMW follow-up (#21791) --- Marlin/src/lcd/menu/menu_ubl.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index c73be1ef7f..1171837a57 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -618,6 +618,7 @@ void _menu_ubl_tools() { sprintf_P(ubl_lcd_gcode, PSTR("M1004S%i"), ubl_storage_slot); #endif queue.inject(ubl_lcd_gcode); + ui.return_to_status(); } void _menu_ubl_mesh_wizard() { @@ -626,11 +627,11 @@ void _menu_ubl_tools() { BACK_ITEM(MSG_UBL_LEVEL_BED); #if HAS_HOTEND - EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, EXTRUDE_MINTEMP, thermalManager.hotend_max_target(0)); + EDIT_ITEM(int3, MSG_UBL_HOTEND_TEMP_CUSTOM, &custom_hotend_temp, HEATER_0_MINTEMP + 20, thermalManager.hotend_max_target(0)); #endif #if HAS_HEATED_BED - EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP, BED_MAX_TARGET); + EDIT_ITEM(int3, MSG_UBL_BED_TEMP_CUSTOM, &custom_bed_temp, BED_MINTEMP + 20, BED_MAX_TARGET); #endif EDIT_ITEM(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, total_slots); From 9405a5e443b78153bf5e2562ed4aaa0be950970b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 4 May 2021 01:47:42 -0500 Subject: [PATCH 0038/2168] Fix flush_and_request_resend --- Marlin/src/gcode/queue.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index a79909917e..39ec338bbf 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -270,6 +270,7 @@ void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) { SERIAL_FLUSH(); SERIAL_ECHOPGM(STR_RESEND); SERIAL_ECHOLN(serial_state[serial_ind.index].last_N + 1); + SERIAL_ECHOLNPGM(STR_OK); } static bool serial_data_available(serial_index_t index) { From f3f82f56bfda2e50a9810be033f0b55a93d40de7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 5 May 2021 00:57:34 +0000 Subject: [PATCH 0039/2168] [cron] Bump distribution date (2021-05-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5f169f5b05..73edf3914a 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 "2021-05-04" + #define STRING_DISTRIBUTION_DATE "2021-05-05" #endif /** From fccfcfbe5fc222bc53dd52f7a9effa8e305fafbf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 May 2021 06:32:54 -0500 Subject: [PATCH 0040/2168] Cleanup, hex formatting, includes --- Marlin/src/HAL/AVR/MarlinSerial.cpp | 8 +- Marlin/src/HAL/DUE/fastio.h | 2 +- Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp | 1 + Marlin/src/HAL/LPC1768/MarlinSerial.h | 4 +- Marlin/src/HAL/STM32/timers.h | 3 - Marlin/src/HAL/STM32F1/timers.h | 6 +- Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 3 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 3 +- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 3 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 3 +- Marlin/src/HAL/shared/Marduino.h | 4 + Marlin/src/core/serial.h | 9 +- Marlin/src/core/serial_hook.h | 4 +- Marlin/src/gcode/control/M7-M9.cpp | 4 +- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/inc/MarlinConfigPre.h | 2 +- .../extui/lib/dgus/mks/DGUSScreenHandler.cpp | 7 +- .../unicode/cyrillic_char_set_bitmap_31.h | 4552 ++++++++--------- .../lcd/tft/images/btn_rounded_42x39x4.cpp | 76 +- Marlin/src/libs/softspi.h | 6 +- docs/Serial.md | 2 +- 21 files changed, 2354 insertions(+), 2352 deletions(-) diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 7cd4446987..8f82b7b418 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -582,7 +582,8 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); template class MarlinSerial< MarlinSerialCfg >; MSerialT2 customizedSerial2(MSerialT2::HasEmergencyParser); -#endif + +#endif // SERIAL_PORT_2 #ifdef MMU2_SERIAL_PORT @@ -596,7 +597,8 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); template class MarlinSerial< MMU2SerialCfg >; MSerialT3 mmuSerial(MSerialT3::HasEmergencyParser); -#endif + +#endif // MMU2_SERIAL_PORT #ifdef LCD_SERIAL_PORT @@ -622,7 +624,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); } #endif -#endif +#endif // LCD_SERIAL_PORT #endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H) diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index f375cb6b29..a609210d81 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -33,7 +33,7 @@ * For ARDUINO_ARCH_SAM * Note the code here was specifically crafted by disassembling what GCC produces * out of it, so GCC is able to optimize it out as much as possible to the least - * amount of instructions. Be very carefull if you modify them, as "clean code" + * amount of instructions. Be very careful if you modify them, as "clean code" * leads to less efficient compiled code!! */ diff --git a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp index ab9af1fe00..57065c49ac 100644 --- a/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp @@ -21,6 +21,7 @@ */ #ifdef TARGET_LPC1768 +#include "../../inc/MarlinConfig.h" #include "HAL.h" #if ENABLED(POSTMORTEM_DEBUGGING) diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 489bd8cc6c..808d19f8c5 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -60,8 +60,8 @@ extern MSerialT MSerial1; extern MSerialT MSerial2; extern MSerialT MSerial3; -// Consequently, we can't use a RuntimeSerial either. The workaround would be to use a RuntimeSerial> type here -// Right now, let's ignore this until it's actually required. +// Consequently, we can't use a RuntimeSerial either. The workaround would be to use +// a RuntimeSerial> type here. Ignore for now until it's actually required. #if ENABLED(SERIAL_RUNTIME_HOOK) #error "SERIAL_RUNTIME_HOOK is not yet supported for LPC176x." #endif diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 4649824303..7a35e43210 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -21,15 +21,12 @@ */ #pragma once -#include #include "../../inc/MarlinConfig.h" // ------------------------ // Defines // ------------------------ -#define FORCE_INLINE __attribute__((always_inline)) inline - // STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits // avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX // is written to the register. STM32F4 timers do not manifest this issue, diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 3e2e7775f1..63ddfb9e60 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -25,9 +25,10 @@ * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) */ -#include +#include "../../inc/MarlinConfig.h" +#include "HAL.h" + #include -#include "../../core/boards.h" // ------------------------ // Defines @@ -37,7 +38,6 @@ * TODO: Check and confirm what timer we will use for each Temps and stepper driving. * We should probable drive temps with PWM. */ -#define FORCE_INLINE __attribute__((always_inline)) inline typedef uint16_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFF diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 21330eaac1..b6f01e6c0e 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -21,11 +21,12 @@ */ #ifdef __MK20DX256__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 5b22668fce..28bca65af5 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -26,11 +26,12 @@ #if defined(__MK64FX512__) || defined(__MK66FX1M0__) +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index a986c293a9..ccc8c2659c 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -26,10 +26,11 @@ #ifdef __IMXRT1062__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include "../shared/Delay.h" #include "timers.h" - #include #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index e4335ff74f..7e202d724e 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -26,11 +26,12 @@ #ifdef __IMXRT1062__ +#include "../../inc/MarlinConfig.h" #include "HAL.h" + #include #include #include "spi_pins.h" -#include "../../core/macros.h" static SPISettings spiConfig; diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h index d0ee6ecc9d..56be8d7211 100644 --- a/Marlin/src/HAL/shared/Marduino.h +++ b/Marlin/src/HAL/shared/Marduino.h @@ -82,4 +82,8 @@ #define UNUSED(x) ((void)(x)) #endif +#ifndef FORCE_INLINE + #define FORCE_INLINE inline __attribute__((always_inline)) +#endif + #include "progmem.h" diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index b503c0f429..842a2b02c5 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -62,11 +62,11 @@ extern uint8_t marlin_debug_flags; // // Serial redirection // -// Step 1: Find what's the first serial leaf +// Step 1: Find out what the first serial leaf is #if BOTH(HAS_MULTI_SERIAL, SERIAL_CATCHALL) - #define _SERIAL_LEAF_1 MYSERIAL + #define _SERIAL_LEAF_1 MYSERIAL #else - #define _SERIAL_LEAF_1 MYSERIAL1 + #define _SERIAL_LEAF_1 MYSERIAL1 #endif // Hook Meatpack if it's enabled on the first leaf @@ -78,7 +78,8 @@ extern uint8_t marlin_debug_flags; #define SERIAL_LEAF_1 _SERIAL_LEAF_1 #endif -// Step 2: For multiserial, handle the second serial port as well +// Step 2: For multiserial wrap all serial ports in a single +// interface with the ability to output to multiple serial ports. #if HAS_MULTI_SERIAL #define _PORT_REDIRECT(n,p) REMEMBER(n,multiSerial.portMask,p) #define _PORT_RESTORE(n,p) RESTORE(n) diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 512ebdec97..45cdcd35ed 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -67,7 +67,7 @@ struct BaseSerial : public SerialBase< BaseSerial >, public SerialT { SerialFeature features(serial_index_t index) const { return CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } - // We have 2 implementation of the same method in both base class, let's say which one we want + // Two implementations of the same method exist in both base classes so indicate the right one using SerialT::available; using SerialT::read; using SerialT::begin; @@ -134,7 +134,7 @@ struct ForwardSerial : public SerialBase< ForwardSerial > { ForwardSerial(const bool e, SerialT & out) : BaseClassT(e), out(out) {} }; -// A class that's can be hooked and unhooked at runtime, useful to capturing the output of the serial interface +// A class that can be hooked and unhooked at runtime, useful to capture the output of the serial interface template struct RuntimeSerial : public SerialBase< RuntimeSerial >, public SerialT { typedef SerialBase< RuntimeSerial > BaseClassT; diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index f93123eb35..ae112fc372 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -72,7 +72,7 @@ void GcodeSuite::M9() { * M8: Air Assist On */ void GcodeSuite::M8() { - planner.synchronize(); + planner.synchronize(); cutter.air_assist_enable(); // Turn on Air Assist pin } @@ -80,7 +80,7 @@ void GcodeSuite::M8() { * M9: Air Assist Off */ void GcodeSuite::M9() { - planner.synchronize(); + planner.synchronize(); cutter.air_assist_disable(); // Turn off Air Assist pin } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index c0c5201222..241def0f77 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -1064,7 +1064,7 @@ void GcodeSuite::process_subcommands_now_P(PGM_P pgcode) { strncpy_P(cmd, pgcode, len); // Copy the command to the stack cmd[len] = '\0'; // End with a nul parser.parse(cmd); // Parse the command - process_parsed_command(true); // Process it + process_parsed_command(true); // Process it (no "ok") if (!delim) break; // Last command? pgcode = delim + 1; // Get the next command } @@ -1077,7 +1077,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 - process_parsed_command(true); // Process it + process_parsed_command(true); // Process it (no "ok") if (!delim) break; // Last command? *delim = '\n'; // Put back the newline gcode = delim + 1; // Get the next command diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h index dfa0adba1b..c090b7e37b 100644 --- a/Marlin/src/inc/MarlinConfigPre.h +++ b/Marlin/src/inc/MarlinConfigPre.h @@ -34,8 +34,8 @@ #include "../HAL/platforms.h" #endif -#include "../core/boards.h" #include "../core/macros.h" +#include "../core/boards.h" #include "../../Configuration.h" #ifdef CUSTOM_VERSION_FILE diff --git a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp index 8833423b37..2abec905cb 100644 --- a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp @@ -26,19 +26,16 @@ #include "../DGUSScreenHandler.h" +#include "../../../../../inc/MarlinConfig.h" + #include "../../../../../MarlinCore.h" -#include "../../../../../gcode/queue.h" -#include "../../../../../libs/duration_t.h" #include "../../../../../module/settings.h" #include "../../../../../module/temperature.h" #include "../../../../../module/motion.h" #include "../../../../../module/planner.h" #include "../../../../../module/printcounter.h" -#include "../../../../../sd/cardreader.h" #include "../../../../../gcode/gcode.h" -#include "../../../../../pins/pins.h" -#include "../../../../../libs/nozzle.h" #if ENABLED(HAS_STEALTHCHOP) #include "../../../../../module/stepper/trinamic.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h index 00bfe3706b..30b1f84399 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h @@ -109,2421 +109,2421 @@ const uint8_t cyrillic_font_widths[] PROGMEM = { const unsigned char cyrillic_font[] PROGMEM = { /* 0 */ - 0xb9, 0x00, 0x01, 0x2f, 0x02, 0xff, 0x01, 0x30, 0x10, 0x00, 0x01, 0x7f, - 0x02, 0xff, 0x01, 0x90, 0x10, 0x00, 0x01, 0xdf, 0x02, 0xff, 0x01, 0xe0, - 0x0f, 0x00, 0x01, 0x03, 0x03, 0xff, 0x01, 0xf4, 0x0f, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xfb, 0x01, 0xff, 0x01, 0xfa, 0x0f, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf1, 0x02, 0xff, 0x0f, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x50, 0x0e, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0x40, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xb0, 0x0d, 0x00, - 0x01, 0x01, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xf1, 0x0d, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf8, 0x01, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf7, 0x0d, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x01, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xfc, 0x0d, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0xef, 0x01, 0xff, - 0x01, 0x20, 0x0c, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x60, 0x02, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0x80, 0x0c, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0x10, 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xd0, 0x0b, 0x00, - 0x01, 0x03, 0x01, 0xff, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x01, 0xf3, 0x0b, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf5, 0x03, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf9, 0x0b, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x01, 0xe0, 0x03, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0xb4, 0x04, 0x44, 0x02, 0xff, 0x01, 0x40, - 0x0a, 0x00, 0x01, 0xaf, 0x08, 0xff, 0x01, 0xa0, 0x0a, 0x00, 0x09, 0xff, - 0x01, 0xf0, 0x09, 0x00, 0x01, 0x06, 0x02, 0xff, 0x05, 0xee, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xf5, 0x09, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf5, - 0x05, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfb, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x90, 0x06, 0x00, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0x70, 0x08, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x40, - 0x06, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xfe, 0x07, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf2, - 0x07, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf8, 0x07, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf8, 0x07, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf2, - 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xfd, 0x07, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x30, - 0x06, 0x00, 0x01, 0x8d, 0x01, 0xdd, 0x01, 0x60, 0x08, 0x00, 0x01, 0xad, - 0x01, 0xdd, 0x01, 0x70, 0xce, 0x00, + 0xB9, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x01, 0x30, 0x10, 0x00, 0x01, 0x7F, + 0x02, 0xFF, 0x01, 0x90, 0x10, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0xE0, + 0x0F, 0x00, 0x01, 0x03, 0x03, 0xFF, 0x01, 0xF4, 0x0F, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0xFF, 0x01, 0xFA, 0x0F, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF1, 0x02, 0xFF, 0x0F, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x50, 0x0E, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x40, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x0D, 0x00, + 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFC, 0x0D, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x20, 0x0C, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x10, 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF3, 0x0B, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF9, 0x0B, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xE0, 0x03, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xB4, 0x04, 0x44, 0x02, 0xFF, 0x01, 0x40, + 0x0A, 0x00, 0x01, 0xAF, 0x08, 0xFF, 0x01, 0xA0, 0x0A, 0x00, 0x09, 0xFF, + 0x01, 0xF0, 0x09, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x05, 0xEE, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF5, + 0x05, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x40, + 0x06, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xFE, 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFD, 0x07, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x30, + 0x06, 0x00, 0x01, 0x8D, 0x01, 0xDD, 0x01, 0x60, 0x08, 0x00, 0x01, 0xAD, + 0x01, 0xDD, 0x01, 0x70, 0xCE, 0x00, /* 1 */ - 0xb5, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf4, 0x09, 0x00, 0x01, 0x1f, - 0x09, 0xff, 0x01, 0xf4, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf4, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd5, 0x07, 0x55, 0x01, 0x51, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xfe, - 0x04, 0xee, 0x01, 0xdb, 0x01, 0x84, 0x0b, 0x00, 0x01, 0x1f, 0x08, 0xff, - 0x01, 0xe7, 0x0a, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xd2, 0x09, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd6, 0x04, 0x66, 0x01, 0x68, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0xfd, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x05, 0x00, 0x01, 0x04, 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf5, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf7, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf9, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf7, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf4, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xe0, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0x80, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe7, 0x04, 0x77, 0x01, 0x89, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0xfe, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, - 0x01, 0xe2, 0x09, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xfb, 0x01, 0x10, - 0x09, 0x00, 0x01, 0x1d, 0x06, 0xdd, 0x01, 0xdc, 0x01, 0xb7, 0x01, 0x20, - 0xd1, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, + 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD5, 0x07, 0x55, 0x01, 0x51, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFE, + 0x04, 0xEE, 0x01, 0xDB, 0x01, 0x84, 0x0B, 0x00, 0x01, 0x1F, 0x08, 0xFF, + 0x01, 0xE7, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xD2, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x68, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x05, 0x00, 0x01, 0x04, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF9, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF4, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xE0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x80, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE7, 0x04, 0x77, 0x01, 0x89, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFE, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0xE2, 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFB, 0x01, 0x10, + 0x09, 0x00, 0x01, 0x1D, 0x06, 0xDD, 0x01, 0xDC, 0x01, 0xB7, 0x01, 0x20, + 0xD1, 0x00, /* 2 */ - 0xb5, 0x00, 0x01, 0x1f, 0x06, 0xff, 0x01, 0xec, 0x01, 0x94, 0x0b, 0x00, - 0x01, 0x1f, 0x08, 0xff, 0x01, 0xc3, 0x0a, 0x00, 0x01, 0x1f, 0x09, 0xff, - 0x01, 0x40, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd6, 0x03, 0x66, - 0x01, 0x67, 0x01, 0x9d, 0x02, 0xff, 0x01, 0xe1, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x4e, 0x01, 0xff, 0x01, 0xf9, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x04, - 0x02, 0xff, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x06, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x30, 0x08, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0x20, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, - 0x01, 0xcf, 0x01, 0xff, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfa, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x1d, 0x01, 0xff, 0x01, 0xf2, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd2, 0x03, 0x22, 0x01, 0x23, - 0x01, 0x59, 0x02, 0xff, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1f, 0x08, 0xff, - 0x01, 0xd3, 0x0a, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xb3, 0x0a, 0x00, - 0x01, 0x1f, 0x09, 0xff, 0x01, 0xa0, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xd4, 0x04, 0x44, 0x01, 0x45, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xfd, - 0x01, 0x10, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, - 0x01, 0x01, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf6, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf9, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf7, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf5, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x05, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xe7, 0x04, 0x77, 0x01, 0x79, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x10, 0x08, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xe3, 0x09, 0x00, - 0x01, 0x1f, 0x08, 0xff, 0x01, 0xfa, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1d, - 0x07, 0xdd, 0x01, 0xb7, 0x01, 0x20, 0xd1, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x06, 0xFF, 0x01, 0xEC, 0x01, 0x94, 0x0B, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xC3, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0x40, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x03, 0x66, + 0x01, 0x67, 0x01, 0x9D, 0x02, 0xFF, 0x01, 0xE1, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x4E, 0x01, 0xFF, 0x01, 0xF9, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xF2, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x22, 0x01, 0x23, + 0x01, 0x59, 0x02, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, + 0x01, 0xD3, 0x0A, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xB3, 0x0A, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD4, 0x04, 0x44, 0x01, 0x45, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF9, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF7, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x05, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xE7, 0x04, 0x77, 0x01, 0x79, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xE3, 0x09, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFA, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1D, + 0x07, 0xDD, 0x01, 0xB7, 0x01, 0x20, 0xD1, 0x00, /* 3 */ - 0xb5, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf4, 0x09, 0x00, 0x01, 0x1f, - 0x09, 0xff, 0x01, 0xf4, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf4, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd5, 0x07, 0x55, 0x01, 0x51, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xb0, 0xd8, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, + 0x09, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD5, 0x07, 0x55, 0x01, 0x51, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xB0, 0xD8, 0x00, /* 4 */ - 0xb8, 0x00, 0x01, 0x08, 0x09, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, - 0x09, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfa, 0x05, 0x66, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf4, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf2, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xa0, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x70, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0x30, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x08, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xfe, 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x08, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf1, - 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x05, 0x00, 0x01, 0x02, - 0x01, 0x22, 0x01, 0x28, 0x02, 0xff, 0x01, 0xc7, 0x06, 0x77, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0x52, 0x01, 0x22, 0x04, 0x00, 0x01, 0x0f, 0x0f, 0xff, - 0x04, 0x00, 0x01, 0x0f, 0x0f, 0xff, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xed, 0x0b, 0xdd, 0x01, 0xef, 0x01, 0xff, 0x04, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x04, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, - 0x01, 0x5f, 0x01, 0xff, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x50, - 0x0b, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x04, 0x00, 0x01, 0x06, 0x01, 0x66, - 0x01, 0x20, 0x0b, 0x00, 0x01, 0x26, 0x01, 0x66, 0x54, 0x00, + 0xB8, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFA, 0x05, 0x66, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xA0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x30, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFE, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF1, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x05, 0x00, 0x01, 0x02, + 0x01, 0x22, 0x01, 0x28, 0x02, 0xFF, 0x01, 0xC7, 0x06, 0x77, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x52, 0x01, 0x22, 0x04, 0x00, 0x01, 0x0F, 0x0F, 0xFF, + 0x04, 0x00, 0x01, 0x0F, 0x0F, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xED, 0x0B, 0xDD, 0x01, 0xEF, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x04, 0x00, 0x01, 0x06, 0x01, 0x66, + 0x01, 0x20, 0x0B, 0x00, 0x01, 0x26, 0x01, 0x66, 0x54, 0x00, /* 5 */ - 0xb5, 0x00, 0x01, 0x1f, 0x0a, 0xff, 0x09, 0x00, 0x01, 0x1f, 0x0a, 0xff, - 0x09, 0x00, 0x01, 0x1f, 0x0a, 0xff, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xd6, 0x07, 0x66, 0x01, 0x65, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc1, 0x07, 0x11, 0x01, 0x10, 0x09, 0x00, - 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf5, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, - 0x01, 0xf5, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf5, 0x09, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd4, 0x07, 0x44, 0x01, 0x41, 0x09, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe7, 0x08, 0x77, 0x01, 0x50, 0x08, 0x00, - 0x01, 0x1f, 0x0a, 0xff, 0x01, 0xb0, 0x08, 0x00, 0x01, 0x1f, 0x0a, 0xff, - 0x01, 0xb0, 0x08, 0x00, 0x01, 0x1e, 0x0a, 0xee, 0x01, 0xa0, 0xcf, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD6, 0x07, 0x66, 0x01, 0x65, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC1, 0x07, 0x11, 0x01, 0x10, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD4, 0x07, 0x44, 0x01, 0x41, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE7, 0x08, 0x77, 0x01, 0x50, 0x08, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1E, 0x0A, 0xEE, 0x01, 0xA0, 0xCF, 0x00, /* 6 */ - 0xb5, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xf3, 0x04, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xe1, - 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0a, 0x02, 0xff, - 0x01, 0x30, 0x03, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, 0x01, 0xb0, - 0x03, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0xf5, 0x05, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf8, - 0x03, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, - 0x02, 0xff, 0x01, 0x80, 0x05, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0x50, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x1e, - 0x01, 0xff, 0x01, 0xfb, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xf2, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfd, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x07, 0x00, 0x01, 0x01, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xb0, 0x01, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf4, 0x09, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xf7, 0x01, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x02, 0x02, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x05, 0x02, 0xff, - 0x01, 0x40, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x1d, 0x01, 0xff, - 0x01, 0xfa, 0x0b, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xe2, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x90, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xc0, 0x0b, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfc, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x98, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x0c, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xf3, 0x0d, 0x00, - 0x01, 0x2e, 0x05, 0xff, 0x01, 0x60, 0x0d, 0x00, 0x01, 0x07, 0x04, 0xff, - 0x01, 0xfc, 0x0e, 0x00, 0x01, 0x2e, 0x05, 0xff, 0x01, 0x60, 0x0c, 0x00, - 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, 0x01, 0xef, 0x01, 0xff, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xf4, 0x0c, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfd, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0x9a, 0x02, 0xff, 0x01, 0x30, 0x0b, 0x00, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0xe2, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0xe2, 0x0a, 0x00, 0x01, 0x09, 0x02, 0xff, - 0x01, 0x30, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x10, 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf4, - 0x01, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x01, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xc0, 0x08, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0x50, - 0x01, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xfb, 0x08, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xf7, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x04, - 0x02, 0xff, 0x01, 0x90, 0x06, 0x00, 0x01, 0x03, 0x02, 0xff, 0x01, 0x80, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xf7, 0x06, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xfa, - 0x03, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x08, - 0x02, 0xff, 0x01, 0x50, 0x04, 0x00, 0x01, 0x01, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xb0, 0x03, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, - 0x01, 0xaf, 0x01, 0xff, 0x01, 0xf4, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xfc, 0x04, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, - 0x01, 0x0b, 0x02, 0xff, 0x01, 0x20, 0x03, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0xd1, 0x04, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0xe1, 0x02, 0x00, 0x01, 0x08, 0x01, 0xff, - 0x01, 0xfe, 0x01, 0x20, 0x04, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x90, - 0x04, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xfd, 0x01, 0x10, 0x01, 0x00, - 0x01, 0x5d, 0x01, 0xdd, 0x01, 0xd3, 0x05, 0x00, 0x01, 0x3d, 0x01, 0xdd, - 0x01, 0x80, 0x04, 0x00, 0x01, 0x03, 0x02, 0xdd, 0x01, 0x90, 0xc9, 0x00, + 0xB5, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xE1, + 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0A, 0x02, 0xFF, + 0x01, 0x30, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xB0, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, + 0x02, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x50, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x1E, + 0x01, 0xFF, 0x01, 0xFB, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF2, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFD, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x07, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF4, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF7, 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x02, 0x02, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x05, 0x02, 0xFF, + 0x01, 0x40, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x1D, 0x01, 0xFF, + 0x01, 0xFA, 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xE2, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x98, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF3, 0x0D, 0x00, + 0x01, 0x2E, 0x05, 0xFF, 0x01, 0x60, 0x0D, 0x00, 0x01, 0x07, 0x04, 0xFF, + 0x01, 0xFC, 0x0E, 0x00, 0x01, 0x2E, 0x05, 0xFF, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF4, 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x9A, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xE2, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xE2, 0x0A, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0x30, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x50, + 0x01, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xFB, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0x80, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF7, 0x06, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xB0, 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xF4, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xFC, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0x0B, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xD1, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xE1, 0x02, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x20, 0x04, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x01, 0x00, + 0x01, 0x5D, 0x01, 0xDD, 0x01, 0xD3, 0x05, 0x00, 0x01, 0x3D, 0x01, 0xDD, + 0x01, 0x80, 0x04, 0x00, 0x01, 0x03, 0x02, 0xDD, 0x01, 0x90, 0xC9, 0x00, /* 7 */ - 0xa5, 0x00, 0x01, 0x45, 0x01, 0x67, 0x01, 0x65, 0x01, 0x20, 0x0e, 0x00, - 0x01, 0x06, 0x01, 0xcf, 0x03, 0xff, 0x01, 0xfe, 0x01, 0x92, 0x0c, 0x00, - 0x01, 0x04, 0x01, 0xef, 0x06, 0xff, 0x01, 0x90, 0x0b, 0x00, 0x01, 0x6f, - 0x02, 0xff, 0x01, 0xfd, 0x01, 0xcb, 0x01, 0xcf, 0x02, 0xff, 0x01, 0xfc, - 0x0a, 0x00, 0x01, 0x04, 0x02, 0xff, 0x01, 0xd6, 0x01, 0x10, 0x02, 0x00, - 0x01, 0x39, 0x02, 0xff, 0x01, 0xa0, 0x09, 0x00, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xf9, 0x05, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xf3, 0x09, 0x00, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf9, 0x09, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xfe, 0x09, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x07, 0x00, - 0x01, 0xdf, 0x01, 0xff, 0x09, 0x00, 0x01, 0xac, 0x01, 0xcb, 0x07, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, 0x10, 0x00, 0x01, 0x04, 0x02, 0xff, - 0x11, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xfc, 0x10, 0x00, 0x01, 0x01, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0xf5, 0x10, 0x00, 0x01, 0x5d, 0x02, 0xff, - 0x01, 0xa0, 0x0d, 0x00, 0x02, 0x99, 0x01, 0xbe, 0x02, 0xff, 0x01, 0xf8, - 0x0e, 0x00, 0x05, 0xff, 0x01, 0x40, 0x0e, 0x00, 0x05, 0xff, 0x01, 0xf9, - 0x0e, 0x00, 0x02, 0xbb, 0x01, 0xcd, 0x03, 0xff, 0x01, 0xd1, 0x10, 0x00, - 0x01, 0x16, 0x01, 0xef, 0x01, 0xff, 0x01, 0xfc, 0x11, 0x00, 0x01, 0x0a, - 0x02, 0xff, 0x01, 0x60, 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x07, 0x01, 0x99, 0x01, 0x80, 0x07, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xf0, 0x07, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf0, - 0x07, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf1, 0x07, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf2, 0x07, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, - 0x07, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x07, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xe0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x20, - 0x06, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0xd2, 0x05, 0x00, 0x01, 0x03, 0x02, 0xff, 0x01, 0x30, - 0x08, 0x00, 0x01, 0x1e, 0x02, 0xff, 0x01, 0x81, 0x03, 0x00, 0x01, 0x01, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xfa, 0x09, 0x00, 0x01, 0x03, 0x01, 0xef, - 0x02, 0xff, 0x01, 0xda, 0x01, 0x98, 0x01, 0x9a, 0x01, 0xdf, 0x02, 0xff, - 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x2d, 0x07, 0xff, 0x01, 0xfa, 0x0c, 0x00, - 0x01, 0x6d, 0x05, 0xff, 0x01, 0xfb, 0x01, 0x30, 0x0d, 0x00, 0x01, 0x27, - 0x01, 0x9b, 0x01, 0xcd, 0x01, 0xba, 0x01, 0x95, 0x01, 0x10, 0xbe, 0x00, + 0xA5, 0x00, 0x01, 0x45, 0x01, 0x67, 0x01, 0x65, 0x01, 0x20, 0x0E, 0x00, + 0x01, 0x06, 0x01, 0xCF, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0x92, 0x0C, 0x00, + 0x01, 0x04, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0x6F, + 0x02, 0xFF, 0x01, 0xFD, 0x01, 0xCB, 0x01, 0xCF, 0x02, 0xFF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0xD6, 0x01, 0x10, 0x02, 0x00, + 0x01, 0x39, 0x02, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xF9, 0x05, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x09, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF9, 0x09, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xFE, 0x09, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x07, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x09, 0x00, 0x01, 0xAC, 0x01, 0xCB, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x10, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x11, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFC, 0x10, 0x00, 0x01, 0x01, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF5, 0x10, 0x00, 0x01, 0x5D, 0x02, 0xFF, + 0x01, 0xA0, 0x0D, 0x00, 0x02, 0x99, 0x01, 0xBE, 0x02, 0xFF, 0x01, 0xF8, + 0x0E, 0x00, 0x05, 0xFF, 0x01, 0x40, 0x0E, 0x00, 0x05, 0xFF, 0x01, 0xF9, + 0x0E, 0x00, 0x02, 0xBB, 0x01, 0xCD, 0x03, 0xFF, 0x01, 0xD1, 0x10, 0x00, + 0x01, 0x16, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFC, 0x11, 0x00, 0x01, 0x0A, + 0x02, 0xFF, 0x01, 0x60, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x07, 0x01, 0x99, 0x01, 0x80, 0x07, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF0, 0x07, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, + 0x07, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x07, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF2, 0x07, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x07, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xE0, 0x07, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x20, + 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xD2, 0x05, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x1E, 0x02, 0xFF, 0x01, 0x81, 0x03, 0x00, 0x01, 0x01, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x03, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xDA, 0x01, 0x98, 0x01, 0x9A, 0x01, 0xDF, 0x02, 0xFF, + 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x2D, 0x07, 0xFF, 0x01, 0xFA, 0x0C, 0x00, + 0x01, 0x6D, 0x05, 0xFF, 0x01, 0xFB, 0x01, 0x30, 0x0D, 0x00, 0x01, 0x27, + 0x01, 0x9B, 0x01, 0xCD, 0x01, 0xBA, 0x01, 0x95, 0x01, 0x10, 0xBE, 0x00, /* 8 */ - 0xb5, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x07, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x06, 0x00, 0x01, 0x07, 0x02, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x06, 0x00, 0x01, 0x2f, 0x02, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x06, 0x00, 0x01, 0xcf, - 0x02, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x05, 0x00, 0x01, 0x06, 0x03, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x05, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xfa, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x1e, 0x01, 0xff, - 0x01, 0xe1, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x60, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xfb, 0x01, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x03, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf2, 0x01, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x03, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x70, 0x01, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfd, 0x02, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x02, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf3, 0x02, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x02, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x80, 0x02, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfd, 0x03, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x01, 0x01, 0xef, 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, 0x04, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0xb0, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x10, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x99, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x03, 0xff, 0x01, 0x20, - 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x02, 0xff, 0x01, 0xf7, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x02, 0xff, 0x01, 0xd0, 0x06, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x02, 0xff, 0x01, 0x30, - 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xe8, 0x07, 0x00, 0x01, 0x0e, 0x01, 0xee, 0x01, 0xa0, - 0xce, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x07, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x06, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x06, 0x03, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x1E, 0x01, 0xFF, + 0x01, 0xE1, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFD, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x10, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x99, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x02, 0xFF, 0x01, 0xF7, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0x30, + 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xE8, 0x07, 0x00, 0x01, 0x0E, 0x01, 0xEE, 0x01, 0xA0, + 0xCE, 0x00, /* 9 */ - 0x2c, 0x00, 0x01, 0x7f, 0x01, 0xf1, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xe0, - 0x0d, 0x00, 0x01, 0x5f, 0x01, 0xf8, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xb0, 0x0d, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xb6, 0x01, 0x45, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0x50, 0x0d, 0x00, 0x01, 0x05, 0x04, 0xff, - 0x01, 0xfb, 0x0f, 0x00, 0x01, 0x5e, 0x03, 0xff, 0x01, 0x90, 0x10, 0x00, - 0x01, 0x46, 0x01, 0x87, 0x01, 0x51, 0x20, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x07, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x06, 0x00, 0x01, 0x07, 0x02, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x06, 0x00, - 0x01, 0x2f, 0x02, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x06, 0x00, 0x01, 0xbf, 0x02, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0x06, 0x03, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xef, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xfa, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x04, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xe1, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0x60, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, - 0x01, 0xff, 0x01, 0xfb, 0x01, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0d, - 0x01, 0xff, 0x01, 0xf2, 0x01, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x70, 0x01, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xfd, 0x02, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf3, 0x02, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0x80, 0x02, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xfd, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x01, 0x01, 0xef, - 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x0a, 0x01, 0xff, - 0x01, 0xf5, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xb0, - 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, 0x04, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x99, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xc0, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x03, 0xff, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x02, 0xff, 0x01, 0xf7, 0x06, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x02, 0xff, - 0x01, 0xd0, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x1f, 0x02, 0xff, 0x01, 0x30, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xe8, 0x07, 0x00, - 0x01, 0x0e, 0x01, 0xee, 0x01, 0xa0, 0xce, 0x00, + 0x2C, 0x00, 0x01, 0x7F, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xE0, + 0x0D, 0x00, 0x01, 0x5F, 0x01, 0xF8, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xB0, 0x0D, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB6, 0x01, 0x45, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x05, 0x04, 0xFF, + 0x01, 0xFB, 0x0F, 0x00, 0x01, 0x5E, 0x03, 0xFF, 0x01, 0x90, 0x10, 0x00, + 0x01, 0x46, 0x01, 0x87, 0x01, 0x51, 0x20, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x07, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, 0x01, 0x07, 0x02, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x06, 0x00, + 0x01, 0x2F, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x06, 0x00, 0x01, 0xBF, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x06, 0x03, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xE1, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x70, 0x01, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF3, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFD, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF5, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x04, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x99, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xC0, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xF7, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x1F, 0x02, 0xFF, 0x01, 0x30, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xE8, 0x07, 0x00, + 0x01, 0x0E, 0x01, 0xEE, 0x01, 0xA0, 0xCE, 0x00, /* 10 */ - 0xb5, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x1d, - 0x01, 0xff, 0x01, 0xfa, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x04, 0x00, 0x01, 0x01, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xa0, 0x09, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x04, 0x00, 0x01, 0x1d, 0x01, 0xff, - 0x01, 0xf9, 0x0a, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x03, 0x00, - 0x01, 0x01, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x90, 0x0a, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x2d, 0x01, 0xff, 0x01, 0xf9, - 0x0b, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, 0x0b, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x02, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x80, 0x0c, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x01, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xf8, 0x0d, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x01, 0x02, 0x01, 0xef, 0x01, 0xff, 0x01, 0x80, - 0x0d, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x01, 0x2e, 0x01, 0xff, - 0x01, 0xf7, 0x0e, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc3, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x70, 0x0e, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xee, - 0x01, 0xff, 0x01, 0xf7, 0x0f, 0x00, 0x01, 0x1f, 0x03, 0xff, 0x01, 0x70, - 0x0f, 0x00, 0x01, 0x1f, 0x03, 0xff, 0x01, 0x20, 0x0f, 0x00, 0x01, 0x1f, - 0x03, 0xff, 0x01, 0xe2, 0x0f, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xdd, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x0e, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc1, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xe2, 0x0e, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x01, 0x1d, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, - 0x0d, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x01, 0x01, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xe2, 0x0d, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x01, 0x00, 0x01, 0x1d, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x0c, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xe2, 0x0c, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x02, 0x00, 0x01, 0x1d, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x0b, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x01, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xe2, 0x0b, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x03, 0x00, 0x01, 0x1d, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x30, 0x0a, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x02, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xe3, 0x0a, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x04, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x30, 0x09, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x04, 0x00, 0x01, 0x02, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xe3, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x2e, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x30, 0x08, 0x00, - 0x01, 0x1e, 0x01, 0xee, 0x01, 0xb0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xde, - 0x01, 0xee, 0x01, 0xd2, 0xcf, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1D, + 0x01, 0xFF, 0x01, 0xFA, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x04, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xA0, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x1D, 0x01, 0xFF, + 0x01, 0xF9, 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, + 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x90, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF9, + 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x02, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x01, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, + 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x2E, 0x01, 0xFF, + 0x01, 0xF7, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC3, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xEE, + 0x01, 0xFF, 0x01, 0xF7, 0x0F, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x70, + 0x0F, 0x00, 0x01, 0x1F, 0x03, 0xFF, 0x01, 0x20, 0x0F, 0x00, 0x01, 0x1F, + 0x03, 0xFF, 0x01, 0xE2, 0x0F, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xDD, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0E, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC1, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xE2, 0x0E, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, + 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0D, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x01, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0C, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0C, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x02, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0B, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xE2, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x03, 0x00, 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x0A, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xE3, 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x04, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x09, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xE3, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x2E, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x30, 0x08, 0x00, + 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xDE, + 0x01, 0xEE, 0x01, 0xD2, 0xCF, 0x00, /* 11 */ - 0xb6, 0x00, 0x01, 0x08, 0x09, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, - 0x09, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfa, 0x05, 0x66, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf4, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xf4, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf1, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xe0, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x60, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x20, - 0x05, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x08, 0x00, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xfe, 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x08, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf9, 0x06, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x30, 0x08, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf2, - 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x07, 0x00, 0x01, 0x1a, - 0x02, 0xff, 0x01, 0xa0, 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, - 0x07, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x06, 0x00, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x07, 0x00, 0x01, 0x2f, 0x01, 0xff, - 0x01, 0xf4, 0x07, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x07, 0x00, - 0x01, 0x2f, 0x01, 0xfb, 0x01, 0x20, 0x07, 0x00, 0x01, 0xae, 0x01, 0xee, - 0x01, 0x30, 0x07, 0x00, 0x01, 0x03, 0x01, 0x10, 0xc6, 0x00, + 0xB6, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x09, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x09, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFA, 0x05, 0x66, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF4, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, + 0x05, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFE, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF9, 0x06, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x30, 0x08, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF2, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x1A, + 0x02, 0xFF, 0x01, 0xA0, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, + 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x06, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x2F, 0x01, 0xFF, + 0x01, 0xF4, 0x07, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x07, 0x00, + 0x01, 0x2F, 0x01, 0xFB, 0x01, 0x20, 0x07, 0x00, 0x01, 0xAE, 0x01, 0xEE, + 0x01, 0x30, 0x07, 0x00, 0x01, 0x03, 0x01, 0x10, 0xC6, 0x00, /* 12 */ - 0xb5, 0x00, 0x01, 0x1e, 0x02, 0xee, 0x01, 0x70, 0x08, 0x00, 0x02, 0xee, - 0x01, 0xe7, 0x05, 0x00, 0x01, 0x1f, 0x02, 0xff, 0x01, 0xc0, 0x07, 0x00, - 0x01, 0x05, 0x02, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x02, 0xff, - 0x01, 0xf2, 0x07, 0x00, 0x01, 0x0b, 0x02, 0xff, 0x01, 0xf8, 0x05, 0x00, - 0x01, 0x1f, 0x02, 0xff, 0x01, 0xf7, 0x07, 0x00, 0x01, 0x1f, 0x02, 0xff, - 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x02, 0xff, 0x01, 0xfd, 0x07, 0x00, - 0x01, 0x6f, 0x02, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xcf, 0x01, 0xff, 0x01, 0x30, 0x06, 0x00, 0x01, 0xbf, 0x01, 0xfc, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x9d, - 0x01, 0xff, 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xf7, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x98, - 0x01, 0xff, 0x01, 0xe0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xe2, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x92, - 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0x92, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0xdf, 0x01, 0xf9, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x42, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x7f, 0x01, 0xfe, 0x05, 0x00, 0x01, 0x6f, 0x01, 0xfe, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0x40, 0x04, 0x00, 0x01, 0xcf, 0x01, 0xf9, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x0c, 0x01, 0xff, 0x01, 0x90, 0x03, 0x00, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xf3, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x07, 0x01, 0xff, 0x01, 0xe0, - 0x03, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xe0, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0x80, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x01, 0x00, 0x01, 0xcf, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x30, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6f, 0x01, 0xff, - 0x03, 0x00, 0x01, 0x7f, 0x01, 0xfd, 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0x50, 0x02, 0x00, 0x01, 0xcf, 0x01, 0xf8, - 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xa0, - 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x01, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xd0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0xff, - 0x01, 0xf6, 0x01, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0x80, 0x01, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0x90, 0x02, 0x00, 0x01, 0xaf, 0x01, 0xfb, 0x01, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x20, 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x01, 0x10, 0x01, 0x7f, 0x01, 0xfd, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x02, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x60, 0x01, 0xdf, 0x01, 0xf7, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xc2, - 0x01, 0xff, 0x01, 0xf2, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, 0x01, 0x04, - 0x01, 0xff, 0x01, 0xfa, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x03, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0x70, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x03, 0x00, 0x01, 0x9f, 0x02, 0xff, 0x01, 0x20, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x03, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xfc, 0x03, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x05, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0x80, - 0x03, 0x00, 0x01, 0x0d, 0x01, 0xee, 0x01, 0xe6, 0x03, 0x00, 0x01, 0x02, - 0x01, 0xee, 0x01, 0xe7, 0xcc, 0x00, + 0xB5, 0x00, 0x01, 0x1E, 0x02, 0xEE, 0x01, 0x70, 0x08, 0x00, 0x02, 0xEE, + 0x01, 0xE7, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xC0, 0x07, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xF2, 0x07, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xF7, 0x07, 0x00, 0x01, 0x1F, 0x02, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x02, 0xFF, 0x01, 0xFD, 0x07, 0x00, + 0x01, 0x6F, 0x02, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x30, 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x9D, + 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x98, + 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xE2, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x92, + 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0x92, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0xDF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x42, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x7F, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFE, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x40, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xF9, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0x90, 0x03, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xE0, + 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0x80, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x01, 0x00, 0x01, 0xCF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x30, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFD, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xF8, + 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xA0, + 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xD0, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0x90, 0x02, 0x00, 0x01, 0xAF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0x10, 0x01, 0x7F, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0xDF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xC2, + 0x01, 0xFF, 0x01, 0xF2, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xFA, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x70, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x9F, 0x02, 0xFF, 0x01, 0x20, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x05, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0x80, + 0x03, 0x00, 0x01, 0x0D, 0x01, 0xEE, 0x01, 0xE6, 0x03, 0x00, 0x01, 0x02, + 0x01, 0xEE, 0x01, 0xE7, 0xCC, 0x00, /* 13 */ - 0xb5, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x0b, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x0b, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x0b, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd4, - 0x07, 0x44, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xb0, 0x07, 0x00, 0x01, 0x8e, 0x01, 0xee, 0x01, 0x40, - 0xce, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD4, + 0x07, 0x44, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xB0, 0x07, 0x00, 0x01, 0x8E, 0x01, 0xEE, 0x01, 0x40, + 0xCE, 0x00, /* 14 */ - 0xa6, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x64, 0x01, 0x31, 0x0e, 0x00, - 0x01, 0x02, 0x01, 0x8d, 0x04, 0xff, 0x01, 0xc7, 0x01, 0x10, 0x0b, 0x00, - 0x01, 0x01, 0x01, 0x9f, 0x06, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x3e, - 0x08, 0xff, 0x01, 0xd2, 0x09, 0x00, 0x01, 0x04, 0x02, 0xff, 0x01, 0xfc, - 0x01, 0x72, 0x01, 0x00, 0x01, 0x01, 0x01, 0x38, 0x01, 0xdf, 0x02, 0xff, - 0x01, 0x30, 0x08, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x50, - 0x04, 0x00, 0x01, 0x07, 0x02, 0xff, 0x01, 0xe2, 0x07, 0x00, 0x01, 0x01, - 0x01, 0xef, 0x01, 0xff, 0x01, 0xd1, 0x06, 0x00, 0x01, 0x2e, 0x01, 0xff, - 0x01, 0xfd, 0x07, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, - 0x06, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x60, 0x06, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xf4, 0x08, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xe0, - 0x06, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf5, 0x06, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x30, - 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xfb, 0x05, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xfd, 0x0a, 0x00, 0x02, 0xff, 0x05, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x30, - 0x04, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf5, 0x0a, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x04, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf4, - 0x0a, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x70, 0x04, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf2, 0x0a, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x80, - 0x04, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf2, 0x0a, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf3, - 0x0a, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf4, 0x0a, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x60, - 0x04, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf7, 0x0a, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfb, - 0x0a, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x10, 0x05, 0x00, 0x02, 0xff, - 0x01, 0x10, 0x08, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfd, 0x06, 0x00, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0x70, 0x08, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf8, 0x06, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xe1, 0x08, 0x00, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf1, 0x06, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xfa, 0x08, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xa0, 0x06, 0x00, - 0x01, 0x04, 0x02, 0xff, 0x01, 0x80, 0x06, 0x00, 0x01, 0x0a, 0x01, 0xff, - 0x01, 0xfe, 0x01, 0x10, 0x07, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0x01, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xf5, 0x08, 0x00, - 0x01, 0x0b, 0x02, 0xff, 0x01, 0xe6, 0x01, 0x10, 0x02, 0x00, 0x01, 0x02, - 0x01, 0x8f, 0x02, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0xaf, 0x02, 0xff, - 0x01, 0xfc, 0x01, 0xa8, 0x01, 0x8a, 0x01, 0xdf, 0x02, 0xff, 0x01, 0xf6, - 0x0a, 0x00, 0x01, 0x06, 0x01, 0xef, 0x06, 0xff, 0x01, 0xfd, 0x01, 0x40, - 0x0b, 0x00, 0x01, 0x18, 0x01, 0xef, 0x04, 0xff, 0x01, 0xfd, 0x01, 0x60, - 0x0d, 0x00, 0x01, 0x03, 0x01, 0x7a, 0x01, 0xcd, 0x01, 0xdc, 0x01, 0xa7, - 0x01, 0x30, 0xbd, 0x00, + 0xA6, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x64, 0x01, 0x31, 0x0E, 0x00, + 0x01, 0x02, 0x01, 0x8D, 0x04, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0B, 0x00, + 0x01, 0x01, 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x3E, + 0x08, 0xFF, 0x01, 0xD2, 0x09, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0xFC, + 0x01, 0x72, 0x01, 0x00, 0x01, 0x01, 0x01, 0x38, 0x01, 0xDF, 0x02, 0xFF, + 0x01, 0x30, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x04, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0xE2, 0x07, 0x00, 0x01, 0x01, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xD1, 0x06, 0x00, 0x01, 0x2E, 0x01, 0xFF, + 0x01, 0xFD, 0x07, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x06, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF4, 0x08, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, + 0x06, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF5, 0x06, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x30, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x02, 0xFF, 0x05, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x30, + 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, + 0x0A, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x80, + 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, + 0x0A, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, + 0x04, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, + 0x0A, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x10, 0x05, 0x00, 0x02, 0xFF, + 0x01, 0x10, 0x08, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x06, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF8, 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xE1, 0x08, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xFA, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xA0, 0x06, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0x80, 0x06, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x07, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0x01, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF5, 0x08, 0x00, + 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xE6, 0x01, 0x10, 0x02, 0x00, 0x01, 0x02, + 0x01, 0x8F, 0x02, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0xAF, 0x02, 0xFF, + 0x01, 0xFC, 0x01, 0xA8, 0x01, 0x8A, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0xF6, + 0x0A, 0x00, 0x01, 0x06, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFD, 0x01, 0x40, + 0x0B, 0x00, 0x01, 0x18, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x60, + 0x0D, 0x00, 0x01, 0x03, 0x01, 0x7A, 0x01, 0xCD, 0x01, 0xDC, 0x01, 0xA7, + 0x01, 0x30, 0xBD, 0x00, /* 15 */ - 0xb5, 0x00, 0x01, 0x1f, 0x0b, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x0b, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x0b, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe6, 0x07, 0x66, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9e, 0x01, 0xee, 0x01, 0x40, - 0xce, 0x00, + 0xB5, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x0B, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x0B, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x07, 0x66, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9E, 0x01, 0xEE, 0x01, 0x40, + 0xCE, 0x00, /* 16 */ - 0xb5, 0x00, 0x01, 0x1e, 0x06, 0xee, 0x01, 0xec, 0x01, 0x95, 0x0b, 0x00, - 0x01, 0x1f, 0x08, 0xff, 0x01, 0xe5, 0x0a, 0x00, 0x01, 0x1f, 0x09, 0xff, - 0x01, 0x80, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd6, 0x03, 0x66, - 0x01, 0x67, 0x01, 0x9d, 0x02, 0xff, 0x01, 0xf5, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x4e, 0x01, 0xff, 0x01, 0xfe, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x03, - 0x02, 0xff, 0x01, 0x50, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xb0, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xc0, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xa0, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x70, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x1b, 0x02, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc1, 0x03, 0x11, 0x01, 0x12, 0x01, 0x48, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xf9, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xc0, - 0x09, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xfb, 0x01, 0x10, 0x09, 0x00, - 0x01, 0x1f, 0x07, 0xff, 0x01, 0xfb, 0x01, 0x40, 0x0a, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd4, 0x04, 0x44, 0x01, 0x32, 0x0c, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xb0, 0xd8, 0x00, + 0xB5, 0x00, 0x01, 0x1E, 0x06, 0xEE, 0x01, 0xEC, 0x01, 0x95, 0x0B, 0x00, + 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xE5, 0x0A, 0x00, 0x01, 0x1F, 0x09, 0xFF, + 0x01, 0x80, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x03, 0x66, + 0x01, 0x67, 0x01, 0x9D, 0x02, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x4E, 0x01, 0xFF, 0x01, 0xFE, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x03, + 0x02, 0xFF, 0x01, 0x50, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x90, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xA0, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1B, 0x02, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x11, 0x01, 0x12, 0x01, 0x48, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF9, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xC0, + 0x09, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x09, 0x00, + 0x01, 0x1F, 0x07, 0xFF, 0x01, 0xFB, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD4, 0x04, 0x44, 0x01, 0x32, 0x0C, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0xD8, 0x00, /* 17 */ - 0xa6, 0x00, 0x01, 0x35, 0x01, 0x66, 0x01, 0x54, 0x01, 0x10, 0x0e, 0x00, - 0x01, 0x06, 0x01, 0xcf, 0x03, 0xff, 0x01, 0xfd, 0x01, 0x71, 0x0c, 0x00, - 0x01, 0x05, 0x01, 0xef, 0x06, 0xff, 0x01, 0x60, 0x0b, 0x00, 0x01, 0xaf, - 0x07, 0xff, 0x01, 0xf8, 0x0a, 0x00, 0x01, 0x0a, 0x02, 0xff, 0x01, 0xd7, - 0x01, 0x20, 0x01, 0x00, 0x01, 0x03, 0x01, 0x9f, 0x02, 0xff, 0x01, 0x70, - 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x01, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0xf2, 0x08, 0x00, 0x01, 0x02, 0x02, 0xff, - 0x01, 0x60, 0x05, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfa, 0x08, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0x02, 0x02, 0xff, - 0x01, 0x10, 0x07, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, - 0x01, 0xaf, 0x01, 0xff, 0x01, 0x60, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, - 0x01, 0x60, 0x07, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, 0x07, 0x00, 0x01, 0x05, 0x01, 0x55, - 0x01, 0x40, 0x06, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfb, 0x11, 0x00, - 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, - 0x01, 0xf5, 0x11, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf3, 0x11, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf2, 0x11, 0x00, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xf2, 0x11, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf3, 0x11, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf4, 0x11, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf6, 0x11, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xfa, 0x08, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf6, 0x06, 0x00, 0x01, 0x01, 0x01, 0xff, - 0x01, 0xfe, 0x08, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf3, 0x07, 0x00, - 0x01, 0xcf, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xf0, 0x07, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xb0, 0x07, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x01, 0xb0, 0x07, 0x00, 0x01, 0x1e, 0x01, 0xff, - 0x01, 0xf5, 0x07, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0x60, 0x07, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x05, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x08, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xe3, 0x05, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf7, 0x09, 0x00, - 0x01, 0x3f, 0x02, 0xff, 0x01, 0x92, 0x03, 0x00, 0x01, 0x29, 0x02, 0xff, - 0x01, 0xc0, 0x09, 0x00, 0x01, 0x04, 0x03, 0xff, 0x01, 0xda, 0x01, 0x88, - 0x01, 0x9c, 0x02, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x0a, 0x00, 0x01, 0x3d, - 0x07, 0xff, 0x01, 0xc1, 0x0c, 0x00, 0x01, 0x7e, 0x05, 0xff, 0x01, 0xd6, - 0x0e, 0x00, 0x01, 0x37, 0x01, 0xac, 0x01, 0xdd, 0x01, 0xca, 0x01, 0x73, - 0xbe, 0x00, + 0xA6, 0x00, 0x01, 0x35, 0x01, 0x66, 0x01, 0x54, 0x01, 0x10, 0x0E, 0x00, + 0x01, 0x06, 0x01, 0xCF, 0x03, 0xFF, 0x01, 0xFD, 0x01, 0x71, 0x0C, 0x00, + 0x01, 0x05, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0xAF, + 0x07, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0x0A, 0x02, 0xFF, 0x01, 0xD7, + 0x01, 0x20, 0x01, 0x00, 0x01, 0x03, 0x01, 0x9F, 0x02, 0xFF, 0x01, 0x70, + 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF2, 0x08, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x60, 0x05, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFA, 0x08, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x10, 0x07, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x60, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0x60, 0x07, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x07, 0x00, 0x01, 0x05, 0x01, 0x55, + 0x01, 0x40, 0x06, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, 0x11, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF5, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, 0x11, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, 0x11, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, 0x11, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF6, 0x11, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xFA, 0x08, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF6, 0x06, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFE, 0x08, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF3, 0x07, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xF0, 0x07, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xB0, 0x07, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xB0, 0x07, 0x00, 0x01, 0x1E, 0x01, 0xFF, + 0x01, 0xF5, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x60, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x05, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x08, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xE3, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF7, 0x09, 0x00, + 0x01, 0x3F, 0x02, 0xFF, 0x01, 0x92, 0x03, 0x00, 0x01, 0x29, 0x02, 0xFF, + 0x01, 0xC0, 0x09, 0x00, 0x01, 0x04, 0x03, 0xFF, 0x01, 0xDA, 0x01, 0x88, + 0x01, 0x9C, 0x02, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, 0x01, 0x3D, + 0x07, 0xFF, 0x01, 0xC1, 0x0C, 0x00, 0x01, 0x7E, 0x05, 0xFF, 0x01, 0xD6, + 0x0E, 0x00, 0x01, 0x37, 0x01, 0xAC, 0x01, 0xDD, 0x01, 0xCA, 0x01, 0x73, + 0xBE, 0x00, /* 18 */ - 0xb4, 0x00, 0x01, 0x2f, 0x0b, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x2f, - 0x0b, 0xff, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x2f, 0x0b, 0xff, 0x01, 0xa0, - 0x07, 0x00, 0x01, 0x16, 0x04, 0x66, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xd6, - 0x04, 0x66, 0x01, 0x40, 0x0c, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x2e, 0x01, 0xee, 0x01, 0xa0, 0xd4, 0x00, + 0xB4, 0x00, 0x01, 0x2F, 0x0B, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x2F, + 0x0B, 0xFF, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x2F, 0x0B, 0xFF, 0x01, 0xA0, + 0x07, 0x00, 0x01, 0x16, 0x04, 0x66, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xD6, + 0x04, 0x66, 0x01, 0x40, 0x0C, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x2E, 0x01, 0xEE, 0x01, 0xA0, 0xD4, 0x00, /* 19 */ - 0xb4, 0x00, 0x01, 0x8e, 0x01, 0xee, 0x01, 0xe2, 0x07, 0x00, 0x01, 0xde, - 0x01, 0xee, 0x01, 0xa0, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xfa, - 0x06, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0x30, 0x07, 0x00, 0x01, 0x08, - 0x02, 0xff, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xfa, - 0x08, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xf2, 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf2, - 0x05, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xa0, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0x20, - 0x09, 0x00, 0x01, 0x08, 0x02, 0xff, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0d, - 0x01, 0xff, 0x01, 0xfa, 0x0a, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, - 0x01, 0x90, 0x03, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf2, 0x03, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0x90, 0x0b, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x05, 0x02, 0xff, 0x01, 0x20, 0x0b, 0x00, 0x01, 0x07, 0x02, 0xff, - 0x01, 0x20, 0x01, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf9, 0x0d, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, 0x01, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x01, 0xf1, 0x0d, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xf2, 0x01, 0x00, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0x80, 0x0d, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x01, 0xf9, 0x01, 0x05, 0x02, 0xff, 0x01, 0x10, 0x0d, 0x00, 0x01, 0x07, - 0x02, 0xff, 0x01, 0x2d, 0x01, 0xff, 0x01, 0xf8, 0x0f, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xf1, 0x0f, 0x00, 0x01, 0x7f, - 0x03, 0xff, 0x01, 0x80, 0x0f, 0x00, 0x01, 0x0e, 0x02, 0xff, 0x01, 0xfe, - 0x01, 0x10, 0x0f, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0xf7, 0x11, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0xe0, 0x10, 0x00, 0x01, 0x01, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x70, 0x10, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfe, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf6, 0x11, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0xe0, 0x10, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x60, - 0x10, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfe, 0x11, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xf6, 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xd0, - 0x10, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0x50, 0x10, 0x00, 0x01, 0x0c, - 0x01, 0xee, 0x01, 0xec, 0xd7, 0x00, + 0xB4, 0x00, 0x01, 0x8E, 0x01, 0xEE, 0x01, 0xE2, 0x07, 0x00, 0x01, 0xDE, + 0x01, 0xEE, 0x01, 0xA0, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFA, + 0x06, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x30, 0x07, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0x20, 0x05, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFA, + 0x08, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF2, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x20, + 0x09, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xFA, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x90, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x90, 0x0B, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x20, 0x0B, 0x00, 0x01, 0x07, 0x02, 0xFF, + 0x01, 0x20, 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF9, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, 0x01, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x0D, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF9, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x10, 0x0D, 0x00, 0x01, 0x07, + 0x02, 0xFF, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF8, 0x0F, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF1, 0x0F, 0x00, 0x01, 0x7F, + 0x03, 0xFF, 0x01, 0x80, 0x0F, 0x00, 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0F, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0xF7, 0x11, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, 0x10, 0x00, 0x01, 0x01, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x70, 0x10, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFE, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xE0, 0x10, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x60, + 0x10, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFE, 0x11, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xD0, + 0x10, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x50, 0x10, 0x00, 0x01, 0x0C, + 0x01, 0xEE, 0x01, 0xEC, 0xD7, 0x00, /* 20 */ - 0xbb, 0x00, 0x01, 0x0b, 0x01, 0xee, 0x01, 0xe2, 0x11, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf2, 0x11, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf2, - 0x10, 0x00, 0x01, 0x01, 0x01, 0x2d, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x10, - 0x0d, 0x00, 0x01, 0x48, 0x01, 0xce, 0x05, 0xff, 0x01, 0xfd, 0x01, 0x96, - 0x01, 0x10, 0x09, 0x00, 0x01, 0x7d, 0x09, 0xff, 0x01, 0xfa, 0x01, 0x20, - 0x07, 0x00, 0x01, 0x2d, 0x0b, 0xff, 0x01, 0xf6, 0x06, 0x00, 0x01, 0x03, - 0x01, 0xef, 0x02, 0xff, 0x01, 0xfb, 0x01, 0x75, 0x01, 0x4d, 0x01, 0xff, - 0x01, 0xf6, 0x01, 0x56, 0x01, 0x9d, 0x03, 0xff, 0x01, 0x80, 0x05, 0x00, - 0x01, 0x1e, 0x02, 0xff, 0x01, 0xe6, 0x02, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x02, 0x00, 0x01, 0x3b, 0x02, 0xff, 0x01, 0xf5, 0x05, 0x00, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xfb, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf2, 0x03, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xfe, - 0x05, 0x00, 0x02, 0xff, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x03, 0x00, 0x01, 0x07, 0x02, 0xff, 0x01, 0x50, 0x03, 0x00, - 0x01, 0x05, 0x02, 0xff, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xb0, 0x03, 0x00, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xfc, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xe0, 0x03, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf0, 0x03, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf0, 0x03, 0x00, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xfc, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xe0, 0x03, 0x00, - 0x01, 0x05, 0x02, 0xff, 0x01, 0x30, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xb0, 0x04, 0x00, - 0x02, 0xff, 0x01, 0xd1, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf2, - 0x03, 0x00, 0x01, 0x08, 0x02, 0xff, 0x01, 0x60, 0x04, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0xfc, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf2, 0x03, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xfe, 0x05, 0x00, - 0x01, 0x1e, 0x02, 0xff, 0x01, 0xf7, 0x01, 0x10, 0x01, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf2, 0x02, 0x00, 0x01, 0x4c, 0x02, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0x04, 0x03, 0xff, 0x01, 0xfb, 0x01, 0x86, 0x01, 0x5d, - 0x01, 0xff, 0x01, 0xf6, 0x01, 0x67, 0x01, 0xae, 0x03, 0xff, 0x01, 0xa0, - 0x06, 0x00, 0x01, 0x4e, 0x0b, 0xff, 0x01, 0xf8, 0x07, 0x00, 0x01, 0x01, - 0x01, 0x8e, 0x09, 0xff, 0x01, 0xfb, 0x01, 0x30, 0x09, 0x00, 0x01, 0x48, - 0x01, 0xbe, 0x05, 0xff, 0x01, 0xed, 0x01, 0xa6, 0x01, 0x10, 0x0d, 0x00, - 0x01, 0x1c, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x10, 0x10, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf2, 0x11, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf2, - 0x11, 0x00, 0x01, 0x0b, 0x01, 0xee, 0x01, 0xe2, 0xd2, 0x00, + 0xBB, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xE2, 0x11, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x10, 0x00, 0x01, 0x01, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x10, + 0x0D, 0x00, 0x01, 0x48, 0x01, 0xCE, 0x05, 0xFF, 0x01, 0xFD, 0x01, 0x96, + 0x01, 0x10, 0x09, 0x00, 0x01, 0x7D, 0x09, 0xFF, 0x01, 0xFA, 0x01, 0x20, + 0x07, 0x00, 0x01, 0x2D, 0x0B, 0xFF, 0x01, 0xF6, 0x06, 0x00, 0x01, 0x03, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x75, 0x01, 0x4D, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x56, 0x01, 0x9D, 0x03, 0xFF, 0x01, 0x80, 0x05, 0x00, + 0x01, 0x1E, 0x02, 0xFF, 0x01, 0xE6, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x02, 0x00, 0x01, 0x3B, 0x02, 0xFF, 0x01, 0xF5, 0x05, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xFE, + 0x05, 0x00, 0x02, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x50, 0x03, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, 0x03, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE0, 0x03, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x30, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, + 0x02, 0xFF, 0x01, 0xD1, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x03, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x60, 0x04, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x10, 0x02, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFE, 0x05, 0x00, + 0x01, 0x1E, 0x02, 0xFF, 0x01, 0xF7, 0x01, 0x10, 0x01, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x02, 0x00, 0x01, 0x4C, 0x02, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0x04, 0x03, 0xFF, 0x01, 0xFB, 0x01, 0x86, 0x01, 0x5D, + 0x01, 0xFF, 0x01, 0xF6, 0x01, 0x67, 0x01, 0xAE, 0x03, 0xFF, 0x01, 0xA0, + 0x06, 0x00, 0x01, 0x4E, 0x0B, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x01, + 0x01, 0x8E, 0x09, 0xFF, 0x01, 0xFB, 0x01, 0x30, 0x09, 0x00, 0x01, 0x48, + 0x01, 0xBE, 0x05, 0xFF, 0x01, 0xED, 0x01, 0xA6, 0x01, 0x10, 0x0D, 0x00, + 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x10, 0x10, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF2, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x11, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xE2, 0xD2, 0x00, /* 21 */ - 0xb4, 0x00, 0x01, 0x0b, 0x01, 0xee, 0x01, 0xec, 0x07, 0x00, 0x01, 0x2e, - 0x01, 0xee, 0x01, 0xe7, 0x07, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x80, - 0x06, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xc0, 0x08, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0x20, - 0x08, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfd, 0x05, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xf6, 0x09, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, - 0x01, 0x80, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xb0, 0x0a, 0x00, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf3, 0x03, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xfe, 0x01, 0x10, 0x0a, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xfd, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf5, 0x0b, 0x00, 0x01, 0x01, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x80, 0x02, 0x00, 0x01, 0xbf, 0x01, 0xff, - 0x01, 0x90, 0x0c, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xfd, 0x0d, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xf3, 0x0e, 0x00, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0x80, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x70, - 0x0e, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf9, 0x01, 0xff, 0x01, 0xfc, - 0x0f, 0x00, 0x01, 0x08, 0x03, 0xff, 0x01, 0xf2, 0x10, 0x00, 0x01, 0xcf, - 0x02, 0xff, 0x01, 0x50, 0x10, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xfc, - 0x11, 0x00, 0x01, 0xaf, 0x02, 0xff, 0x01, 0x30, 0x0f, 0x00, 0x01, 0x05, - 0x03, 0xff, 0x01, 0xd0, 0x0f, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xfd, - 0x01, 0xff, 0x01, 0xf9, 0x0f, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x91, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x50, 0x0d, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xe1, 0x0d, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x00, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xfb, 0x0d, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x80, 0x01, 0x00, - 0x01, 0x01, 0x02, 0xff, 0x01, 0x60, 0x0b, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xfd, 0x03, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0xf3, 0x03, 0x00, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xfc, 0x0a, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, 0x01, 0x80, - 0x03, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xfd, 0x05, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf4, - 0x09, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, 0x07, 0x00, 0x01, 0x02, 0x02, 0xff, - 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0xa0, 0x07, 0x00, - 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfd, 0x07, 0x00, 0x01, 0x6f, 0x01, 0xff, - 0x01, 0xf5, 0x07, 0x00, 0x01, 0x6e, 0x01, 0xee, 0x01, 0xe3, 0x07, 0x00, - 0x01, 0x0b, 0x01, 0xee, 0x01, 0xed, 0x01, 0x10, 0xce, 0x00, + 0xB4, 0x00, 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xEC, 0x07, 0x00, 0x01, 0x2E, + 0x01, 0xEE, 0x01, 0xE7, 0x07, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x80, + 0x06, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x20, + 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFD, 0x05, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xF6, 0x09, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x80, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xB0, 0x0A, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFD, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0x01, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0x90, 0x0C, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFD, 0x0D, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xF3, 0x0E, 0x00, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, + 0x0E, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0xFF, 0x01, 0xFC, + 0x0F, 0x00, 0x01, 0x08, 0x03, 0xFF, 0x01, 0xF2, 0x10, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0x50, 0x10, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFC, + 0x11, 0x00, 0x01, 0xAF, 0x02, 0xFF, 0x01, 0x30, 0x0F, 0x00, 0x01, 0x05, + 0x03, 0xFF, 0x01, 0xD0, 0x0F, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0xFF, 0x01, 0xF9, 0x0F, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x91, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE1, 0x0D, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFB, 0x0D, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, + 0x01, 0x01, 0x02, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFD, 0x03, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFC, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x80, + 0x03, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFD, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF4, + 0x09, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, 0x07, 0x00, 0x01, 0x02, 0x02, 0xFF, + 0x01, 0x80, 0x05, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0xA0, 0x07, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFD, 0x07, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xF5, 0x07, 0x00, 0x01, 0x6E, 0x01, 0xEE, 0x01, 0xE3, 0x07, 0x00, + 0x01, 0x0B, 0x01, 0xEE, 0x01, 0xED, 0x01, 0x10, 0xCE, 0x00, /* 22 */ - 0xb5, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xc0, 0x07, 0x00, 0x01, 0x9e, - 0x01, 0xee, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, - 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x07, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xe6, 0x07, 0x66, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x51, - 0x01, 0x10, 0x06, 0x00, 0x01, 0x1f, 0x0c, 0xff, 0x01, 0xf1, 0x06, 0x00, - 0x01, 0x1f, 0x0c, 0xff, 0x01, 0xf1, 0x06, 0x00, 0x01, 0x1f, 0x0c, 0xff, - 0x01, 0xf1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf1, 0x11, 0x00, - 0x01, 0x03, 0x01, 0xff, 0x01, 0xf1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xff, - 0x01, 0xf1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf1, 0x11, 0x00, - 0x01, 0x03, 0x01, 0xff, 0x01, 0xf1, 0x11, 0x00, 0x01, 0x01, 0x01, 0x77, + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x07, 0x00, 0x01, 0x9E, + 0x01, 0xEE, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, + 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x07, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE6, 0x07, 0x66, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x51, + 0x01, 0x10, 0x06, 0x00, 0x01, 0x1F, 0x0C, 0xFF, 0x01, 0xF1, 0x06, 0x00, + 0x01, 0x1F, 0x0C, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0x1F, 0x0C, 0xFF, + 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xF1, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF1, 0x11, 0x00, 0x01, 0x01, 0x01, 0x77, 0x01, 0x70, 0x55, 0x00, /* 23 */ - 0xb4, 0x00, 0x01, 0x04, 0x01, 0xee, 0x01, 0xe8, 0x06, 0x00, 0x01, 0xbe, - 0x01, 0xee, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, - 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, - 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, - 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf8, - 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x08, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfa, - 0x06, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x40, 0x05, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x09, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xfd, 0x01, 0xba, 0x04, 0xaa, - 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0b, 0x09, 0xff, - 0x01, 0x10, 0x0a, 0x00, 0x01, 0x8f, 0x08, 0xff, 0x01, 0x10, 0x0a, 0x00, - 0x01, 0x01, 0x01, 0x69, 0x05, 0xaa, 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, - 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, - 0x11, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x10, 0x11, 0x00, 0x01, 0xbe, - 0x01, 0xee, 0x01, 0x10, 0xd0, 0x00, + 0xB4, 0x00, 0x01, 0x04, 0x01, 0xEE, 0x01, 0xE8, 0x06, 0x00, 0x01, 0xBE, + 0x01, 0xEE, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF8, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x08, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, + 0x06, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x40, 0x05, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x09, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0xBA, 0x04, 0xAA, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0B, 0x09, 0xFF, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0x8F, 0x08, 0xFF, 0x01, 0x10, 0x0A, 0x00, + 0x01, 0x01, 0x01, 0x69, 0x05, 0xAA, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, + 0x11, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x10, 0x11, 0x00, 0x01, 0xBE, + 0x01, 0xEE, 0x01, 0x10, 0xD0, 0x00, /* 24 */ - 0xb5, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe6, 0x03, 0x66, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0xe6, 0x03, 0x66, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x0d, 0xff, 0x01, 0xd0, 0x05, 0x00, 0x01, 0x1f, - 0x0d, 0xff, 0x01, 0xd0, 0x05, 0x00, 0x01, 0x1f, 0x0d, 0xff, 0x01, 0xc0, - 0xcc, 0x00, + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x0D, 0xFF, 0x01, 0xD0, 0x05, 0x00, 0x01, 0x1F, + 0x0D, 0xFF, 0x01, 0xD0, 0x05, 0x00, 0x01, 0x1F, 0x0D, 0xFF, 0x01, 0xC0, + 0xCC, 0x00, /* 25 */ - 0xb5, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x1e, - 0x01, 0xee, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe6, 0x03, 0x66, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0xe6, 0x03, 0x66, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd1, - 0x01, 0x10, 0x04, 0x00, 0x01, 0x1f, 0x0e, 0xff, 0x01, 0xfa, 0x04, 0x00, - 0x01, 0x1f, 0x0e, 0xff, 0x01, 0xfa, 0x04, 0x00, 0x01, 0x1f, 0x0e, 0xff, - 0x01, 0xfa, 0x12, 0x00, 0x01, 0xbf, 0x01, 0xfa, 0x12, 0x00, 0x01, 0xbf, - 0x01, 0xfa, 0x12, 0x00, 0x01, 0xbf, 0x01, 0xfa, 0x12, 0x00, 0x01, 0xbf, - 0x01, 0xfa, 0x12, 0x00, 0x01, 0xbf, 0x01, 0xfa, 0x12, 0x00, 0x01, 0x57, + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, + 0x01, 0xEE, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xE6, 0x03, 0x66, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD1, + 0x01, 0x10, 0x04, 0x00, 0x01, 0x1F, 0x0E, 0xFF, 0x01, 0xFA, 0x04, 0x00, + 0x01, 0x1F, 0x0E, 0xFF, 0x01, 0xFA, 0x04, 0x00, 0x01, 0x1F, 0x0E, 0xFF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, + 0x01, 0xFA, 0x12, 0x00, 0x01, 0xBF, 0x01, 0xFA, 0x12, 0x00, 0x01, 0x57, 0x01, 0x74, 0x53, 0x00, /* 26 */ - 0xb5, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe8, - 0x03, 0x88, 0x01, 0x76, 0x01, 0x53, 0x0c, 0x00, 0x01, 0x1f, 0x07, 0xff, - 0x01, 0xfb, 0x01, 0x50, 0x0a, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xfd, - 0x01, 0x30, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xfc, 0x03, 0xcc, - 0x01, 0xcd, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf5, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7e, 0x02, 0xff, - 0x01, 0x20, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, - 0x01, 0x02, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xb0, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf6, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf8, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf9, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf8, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x06, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf2, - 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0xc0, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x05, 0x00, 0x01, 0x1a, 0x02, 0xff, 0x01, 0x40, 0x08, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd6, 0x04, 0x66, 0x01, 0x7b, 0x02, 0xff, 0x01, 0xf9, - 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xa0, 0x09, 0x00, 0x01, 0x1f, - 0x08, 0xff, 0x01, 0xe6, 0x0a, 0x00, 0x01, 0x1e, 0x06, 0xee, 0x01, 0xed, - 0x01, 0xa5, 0xd2, 0x00, + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE8, + 0x03, 0x88, 0x01, 0x76, 0x01, 0x53, 0x0C, 0x00, 0x01, 0x1F, 0x07, 0xFF, + 0x01, 0xFB, 0x01, 0x50, 0x0A, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFD, + 0x01, 0x30, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0xCC, + 0x01, 0xCD, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7E, 0x02, 0xFF, + 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF9, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF8, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xC0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x05, 0x00, 0x01, 0x1A, 0x02, 0xFF, 0x01, 0x40, 0x08, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x7B, 0x02, 0xFF, 0x01, 0xF9, + 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x09, 0x00, 0x01, 0x1F, + 0x08, 0xFF, 0x01, 0xE6, 0x0A, 0x00, 0x01, 0x1E, 0x06, 0xEE, 0x01, 0xED, + 0x01, 0xA5, 0xD2, 0x00, /* 27 */ - 0xb5, 0x00, 0x01, 0x1e, 0x01, 0xee, 0x01, 0xb0, 0x0a, 0x00, 0x01, 0x3e, - 0x01, 0xee, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xe8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x52, 0x05, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x07, 0xff, - 0x01, 0xfb, 0x01, 0x50, 0x03, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, - 0x04, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xfd, 0x01, 0x30, 0x02, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xfd, 0x04, 0xdd, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7e, 0x02, 0xff, 0x01, 0x20, - 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xb0, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x3f, 0x01, 0xff, - 0x01, 0xf1, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xf6, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf8, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xff, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf8, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf6, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x01, 0xf2, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x06, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0xc0, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x1a, 0x02, 0xff, - 0x01, 0x40, 0x01, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd6, 0x04, 0x66, 0x01, 0x7a, 0x02, 0xff, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, - 0x01, 0x1f, 0x09, 0xff, 0x01, 0xa0, 0x02, 0x00, 0x01, 0x3f, 0x01, 0xff, - 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1f, 0x08, 0xff, 0x01, 0xe6, 0x03, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x1e, 0x06, 0xee, - 0x01, 0xed, 0x01, 0xa5, 0x04, 0x00, 0x01, 0x3e, 0x01, 0xee, 0x01, 0xa0, - 0xcb, 0x00, + 0xB5, 0x00, 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x0A, 0x00, 0x01, 0x3E, + 0x01, 0xEE, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x52, 0x05, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x07, 0xFF, + 0x01, 0xFB, 0x01, 0x50, 0x03, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, + 0x04, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xFD, 0x01, 0x30, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xFD, 0x04, 0xDD, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x7E, 0x02, 0xFF, 0x01, 0x20, + 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xB0, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF8, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF8, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF6, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xF2, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xC0, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x1A, 0x02, 0xFF, + 0x01, 0x40, 0x01, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD6, 0x04, 0x66, 0x01, 0x7A, 0x02, 0xFF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xA0, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1F, 0x08, 0xFF, 0x01, 0xE6, 0x03, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x1E, 0x06, 0xEE, + 0x01, 0xED, 0x01, 0xA5, 0x04, 0x00, 0x01, 0x3E, 0x01, 0xEE, 0x01, 0xA0, + 0xCB, 0x00, /* 28 */ - 0xb4, 0x00, 0x01, 0x2e, 0x06, 0xee, 0x01, 0x50, 0x0c, 0x00, 0x01, 0x2f, - 0x06, 0xff, 0x01, 0x50, 0x0c, 0x00, 0x01, 0x2f, 0x06, 0xff, 0x01, 0x50, - 0x0c, 0x00, 0x01, 0x17, 0x04, 0x77, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x50, - 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, - 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, - 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0xb8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x41, 0x0c, 0x00, - 0x01, 0x8f, 0x07, 0xff, 0x01, 0xe8, 0x01, 0x20, 0x0a, 0x00, 0x01, 0x8f, - 0x08, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xed, - 0x04, 0xdd, 0x03, 0xff, 0x01, 0xc0, 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, - 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xfb, - 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x05, 0x00, 0x01, 0x07, - 0x02, 0xff, 0x01, 0x40, 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, - 0x06, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x06, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xe0, - 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, - 0x06, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, - 0x06, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xb0, 0x08, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x05, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x50, - 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x05, 0x00, 0x01, 0x4e, - 0x01, 0xff, 0x01, 0xfd, 0x09, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x96, - 0x04, 0x66, 0x01, 0x8d, 0x02, 0xff, 0x01, 0xf3, 0x09, 0x00, 0x01, 0x8f, - 0x08, 0xff, 0x01, 0xfe, 0x01, 0x40, 0x09, 0x00, 0x01, 0x8f, 0x08, 0xff, - 0x01, 0xb2, 0x0a, 0x00, 0x01, 0x7e, 0x06, 0xee, 0x01, 0xec, 0x01, 0x83, - 0xce, 0x00, + 0xB4, 0x00, 0x01, 0x2E, 0x06, 0xEE, 0x01, 0x50, 0x0C, 0x00, 0x01, 0x2F, + 0x06, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0x2F, 0x06, 0xFF, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0x17, 0x04, 0x77, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x11, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0xB8, 0x03, 0x88, 0x01, 0x76, 0x01, 0x41, 0x0C, 0x00, + 0x01, 0x8F, 0x07, 0xFF, 0x01, 0xE8, 0x01, 0x20, 0x0A, 0x00, 0x01, 0x8F, + 0x08, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xED, + 0x04, 0xDD, 0x03, 0xFF, 0x01, 0xC0, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, + 0x01, 0x50, 0x04, 0x00, 0x01, 0x03, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFB, + 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x07, + 0x02, 0xFF, 0x01, 0x40, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xE0, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, + 0x06, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x50, + 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x05, 0x00, 0x01, 0x4E, + 0x01, 0xFF, 0x01, 0xFD, 0x09, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x96, + 0x04, 0x66, 0x01, 0x8D, 0x02, 0xFF, 0x01, 0xF3, 0x09, 0x00, 0x01, 0x8F, + 0x08, 0xFF, 0x01, 0xFE, 0x01, 0x40, 0x09, 0x00, 0x01, 0x8F, 0x08, 0xFF, + 0x01, 0xB2, 0x0A, 0x00, 0x01, 0x7E, 0x06, 0xEE, 0x01, 0xEC, 0x01, 0x83, + 0xCE, 0x00, /* 29 */ - 0xa5, 0x00, 0x01, 0x14, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x0e, 0x00, - 0x01, 0x02, 0x01, 0x8e, 0x03, 0xff, 0x01, 0xfe, 0x01, 0xa4, 0x0d, 0x00, - 0x01, 0x8f, 0x06, 0xff, 0x01, 0xc2, 0x0b, 0x00, 0x01, 0x0c, 0x08, 0xff, - 0x01, 0x50, 0x0a, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xfd, 0x01, 0x73, - 0x01, 0x00, 0x01, 0x01, 0x01, 0x49, 0x02, 0xff, 0x01, 0xf6, 0x09, 0x00, - 0x01, 0x05, 0x02, 0xff, 0x01, 0x80, 0x04, 0x00, 0x01, 0x2c, 0x02, 0xff, - 0x01, 0x30, 0x08, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf8, 0x06, 0x00, - 0x01, 0xaf, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x01, 0xd0, 0x06, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf6, 0x08, 0x00, - 0x01, 0xaf, 0x01, 0xff, 0x01, 0x60, 0x06, 0x00, 0x01, 0x03, 0x01, 0xff, - 0x01, 0xfe, 0x08, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, 0x07, 0x00, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0x40, 0x07, 0x00, 0x01, 0x55, 0x01, 0x54, - 0x08, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, - 0x11, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf4, 0x0a, 0x00, 0x01, 0xbf, - 0x08, 0xff, 0x01, 0xf5, 0x0a, 0x00, 0x01, 0xbf, 0x08, 0xff, 0x01, 0xf6, - 0x0a, 0x00, 0x01, 0xbf, 0x08, 0xff, 0x01, 0xf7, 0x0a, 0x00, 0x01, 0x35, - 0x06, 0x55, 0x01, 0x5a, 0x01, 0xff, 0x01, 0xf6, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf5, 0x11, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf3, - 0x06, 0x00, 0x01, 0x09, 0x01, 0xee, 0x01, 0xe5, 0x08, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf8, - 0x08, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xd0, 0x06, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xfd, 0x08, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x70, - 0x06, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x20, 0x07, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x20, 0x07, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x90, - 0x06, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfb, 0x08, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x01, 0xf3, 0x06, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf3, - 0x08, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x04, 0x00, - 0x01, 0x06, 0x02, 0xff, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x03, 0x02, 0xff, - 0x01, 0xe6, 0x03, 0x00, 0x01, 0x03, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xfd, - 0x0a, 0x00, 0x01, 0x5f, 0x02, 0xff, 0x01, 0xfb, 0x01, 0x87, 0x01, 0x8a, - 0x01, 0xef, 0x02, 0xff, 0x01, 0xd1, 0x0a, 0x00, 0x01, 0x04, 0x01, 0xef, - 0x06, 0xff, 0x01, 0xfb, 0x01, 0x10, 0x0b, 0x00, 0x01, 0x19, 0x05, 0xff, - 0x01, 0xfc, 0x01, 0x50, 0x0d, 0x00, 0x01, 0x15, 0x01, 0x9b, 0x01, 0xde, - 0x01, 0xdc, 0x01, 0xa7, 0x01, 0x20, 0xbe, 0x00, + 0xA5, 0x00, 0x01, 0x14, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x0E, 0x00, + 0x01, 0x02, 0x01, 0x8E, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0xA4, 0x0D, 0x00, + 0x01, 0x8F, 0x06, 0xFF, 0x01, 0xC2, 0x0B, 0x00, 0x01, 0x0C, 0x08, 0xFF, + 0x01, 0x50, 0x0A, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x73, + 0x01, 0x00, 0x01, 0x01, 0x01, 0x49, 0x02, 0xFF, 0x01, 0xF6, 0x09, 0x00, + 0x01, 0x05, 0x02, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x2C, 0x02, 0xFF, + 0x01, 0x30, 0x08, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF8, 0x06, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xD0, 0x06, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF6, 0x08, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xFE, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, 0x07, 0x00, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x07, 0x00, 0x01, 0x55, 0x01, 0x54, + 0x08, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, + 0x11, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0xBF, + 0x08, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xBF, 0x08, 0xFF, 0x01, 0xF6, + 0x0A, 0x00, 0x01, 0xBF, 0x08, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0x35, + 0x06, 0x55, 0x01, 0x5A, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF5, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF3, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xEE, 0x01, 0xE5, 0x08, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF0, 0x06, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF8, + 0x08, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xD0, 0x06, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xFD, 0x08, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, + 0x06, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x20, 0x07, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x90, + 0x06, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFB, 0x08, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xF3, 0x06, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF3, + 0x08, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x04, 0x00, + 0x01, 0x06, 0x02, 0xFF, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x03, 0x02, 0xFF, + 0x01, 0xE6, 0x03, 0x00, 0x01, 0x03, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xFD, + 0x0A, 0x00, 0x01, 0x5F, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x87, 0x01, 0x8A, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xD1, 0x0A, 0x00, 0x01, 0x04, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xFB, 0x01, 0x10, 0x0B, 0x00, 0x01, 0x19, 0x05, 0xFF, + 0x01, 0xFC, 0x01, 0x50, 0x0D, 0x00, 0x01, 0x15, 0x01, 0x9B, 0x01, 0xDE, + 0x01, 0xDC, 0x01, 0xA7, 0x01, 0x20, 0xBE, 0x00, /* 30 */ - 0xab, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x06, 0x00, - 0x01, 0x1e, 0x01, 0xee, 0x01, 0xb0, 0x05, 0x00, 0x01, 0x02, 0x01, 0x8d, - 0x03, 0xff, 0x01, 0xfe, 0x01, 0x93, 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x9f, 0x06, 0xff, 0x01, 0xb2, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x04, 0x00, 0x01, 0x3e, - 0x08, 0xff, 0x01, 0x50, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, - 0x03, 0x00, 0x01, 0x03, 0x02, 0xff, 0x01, 0xfc, 0x01, 0x62, 0x01, 0x00, - 0x01, 0x02, 0x01, 0x6b, 0x02, 0xff, 0x01, 0xf6, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x03, 0x00, 0x01, 0x1e, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x40, 0x04, 0x00, 0x01, 0x3d, 0x02, 0xff, 0x01, 0x30, 0x02, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xff, - 0x01, 0xd1, 0x05, 0x00, 0x01, 0x01, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xd0, - 0x02, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x04, - 0x02, 0xff, 0x01, 0x10, 0x06, 0x00, 0x01, 0x1e, 0x01, 0xff, 0x01, 0xf7, - 0x02, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf6, 0x07, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xfd, - 0x02, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xe0, 0x08, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x40, - 0x01, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0x80, 0x08, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x90, - 0x01, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x01, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x02, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x09, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf0, 0x01, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xff, - 0x01, 0xfc, 0x09, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x00, - 0x01, 0x1f, 0x05, 0xff, 0x01, 0xfb, 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf4, 0x01, 0x00, 0x01, 0x1f, 0x05, 0xff, 0x01, 0xfa, 0x09, 0x00, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xf5, 0x01, 0x00, 0x01, 0x1f, 0x05, 0xff, - 0x01, 0xf9, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf5, 0x01, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe5, 0x01, 0x55, 0x01, 0x57, 0x01, 0xff, - 0x01, 0xfa, 0x09, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xff, - 0x01, 0xfb, 0x09, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf3, 0x01, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0xff, 0x01, 0xfd, - 0x09, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, 0x01, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x10, - 0x08, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xe0, 0x01, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x50, - 0x08, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xa0, 0x01, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xb0, - 0x08, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x50, 0x01, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf2, - 0x07, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xfe, 0x02, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfb, - 0x07, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf6, 0x02, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x01, 0x02, 0xff, 0x01, 0x70, - 0x06, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xd0, 0x02, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf7, - 0x05, 0x00, 0x01, 0x06, 0x02, 0xff, 0x01, 0x30, 0x02, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x09, 0x02, 0xff, 0x01, 0xc4, - 0x03, 0x00, 0x01, 0x03, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xf6, 0x03, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x04, 0x00, 0x01, 0x9f, 0x02, 0xff, - 0x01, 0xea, 0x01, 0x87, 0x01, 0x8a, 0x01, 0xef, 0x02, 0xff, 0x01, 0x50, - 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x04, 0x00, 0x01, 0x06, - 0x07, 0xff, 0x01, 0xd4, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, - 0x05, 0x00, 0x01, 0x19, 0x05, 0xff, 0x01, 0xe7, 0x0e, 0x00, 0x01, 0x04, - 0x01, 0x9b, 0x01, 0xce, 0x01, 0xdc, 0x01, 0x95, 0xb9, 0x00, + 0xAB, 0x00, 0x01, 0x13, 0x01, 0x56, 0x01, 0x54, 0x01, 0x20, 0x06, 0x00, + 0x01, 0x1E, 0x01, 0xEE, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x02, 0x01, 0x8D, + 0x03, 0xFF, 0x01, 0xFE, 0x01, 0x93, 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x04, 0x00, 0x01, 0x01, 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xB2, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x3E, + 0x08, 0xFF, 0x01, 0x50, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, + 0x03, 0x00, 0x01, 0x03, 0x02, 0xFF, 0x01, 0xFC, 0x01, 0x62, 0x01, 0x00, + 0x01, 0x02, 0x01, 0x6B, 0x02, 0xFF, 0x01, 0xF6, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0x1E, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x40, 0x04, 0x00, 0x01, 0x3D, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0xD1, 0x05, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xD0, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x10, 0x06, 0x00, 0x01, 0x1E, 0x01, 0xFF, 0x01, 0xF7, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF6, 0x07, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFD, + 0x02, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xE0, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x40, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x80, 0x08, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x20, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x01, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x02, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x09, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF0, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFC, 0x09, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x1F, 0x05, 0xFF, 0x01, 0xFB, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF4, 0x01, 0x00, 0x01, 0x1F, 0x05, 0xFF, 0x01, 0xFA, 0x09, 0x00, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, 0x01, 0x1F, 0x05, 0xFF, + 0x01, 0xF9, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE5, 0x01, 0x55, 0x01, 0x57, 0x01, 0xFF, + 0x01, 0xFA, 0x09, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFB, 0x09, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0xFF, 0x01, 0xFD, + 0x09, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x10, + 0x08, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, + 0x08, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xB0, + 0x08, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x01, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, + 0x07, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, + 0x07, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x01, 0x02, 0xFF, 0x01, 0x70, + 0x06, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD0, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF7, + 0x05, 0x00, 0x01, 0x06, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x09, 0x02, 0xFF, 0x01, 0xC4, + 0x03, 0x00, 0x01, 0x03, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xF6, 0x03, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x9F, 0x02, 0xFF, + 0x01, 0xEA, 0x01, 0x87, 0x01, 0x8A, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x50, + 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x06, + 0x07, 0xFF, 0x01, 0xD4, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, + 0x05, 0x00, 0x01, 0x19, 0x05, 0xFF, 0x01, 0xE7, 0x0E, 0x00, 0x01, 0x04, + 0x01, 0x9B, 0x01, 0xCE, 0x01, 0xDC, 0x01, 0x95, 0xB9, 0x00, /* 31 */ - 0xb7, 0x00, 0x01, 0x04, 0x01, 0x9c, 0x01, 0xde, 0x06, 0xee, 0x01, 0xc0, - 0x09, 0x00, 0x01, 0x04, 0x01, 0xdf, 0x08, 0xff, 0x01, 0xd0, 0x09, 0x00, - 0x01, 0x6f, 0x09, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x04, 0x02, 0xff, - 0x01, 0xfb, 0x01, 0x87, 0x04, 0x77, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd0, - 0x08, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xfc, 0x01, 0x20, 0x05, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x4f, 0x01, 0xff, - 0x01, 0xe1, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0x60, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xd0, 0x08, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x30, 0x06, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0xcf, 0x01, 0xff, - 0x01, 0x10, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, - 0x01, 0xaf, 0x01, 0xff, 0x01, 0x20, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xd0, 0x08, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x50, 0x06, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xfa, 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xd0, 0x08, 0x00, 0x01, 0x02, 0x01, 0xef, 0x01, 0xff, 0x01, 0xe8, - 0x01, 0x54, 0x04, 0x44, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xd0, 0x09, 0x00, - 0x01, 0x4f, 0x09, 0xff, 0x01, 0xd0, 0x09, 0x00, 0x01, 0x03, 0x01, 0xdf, - 0x08, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0x05, 0x01, 0xae, 0x07, 0xff, - 0x01, 0xd0, 0x0c, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x32, - 0x01, 0x22, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xd0, 0x0c, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0xe2, 0x02, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, - 0x0b, 0x00, 0x01, 0x08, 0x02, 0xff, 0x01, 0x30, 0x02, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xd0, 0x0b, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xf5, - 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0x04, - 0x02, 0xff, 0x01, 0x60, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, - 0x0a, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xd0, 0x09, 0x00, 0x01, 0x02, 0x01, 0xef, 0x01, 0xff, - 0x01, 0x90, 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x09, 0x00, - 0x01, 0x1d, 0x01, 0xff, 0x01, 0xfb, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xd0, 0x09, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x08, 0x00, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x10, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, - 0x08, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xe1, 0x06, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x07, 0x02, 0xff, 0x01, 0x20, - 0x06, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, 0x07, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x01, 0xf4, 0x07, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xd0, - 0xcf, 0x00, + 0xB7, 0x00, 0x01, 0x04, 0x01, 0x9C, 0x01, 0xDE, 0x06, 0xEE, 0x01, 0xC0, + 0x09, 0x00, 0x01, 0x04, 0x01, 0xDF, 0x08, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x6F, 0x09, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x01, 0xFB, 0x01, 0x87, 0x04, 0x77, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x08, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x20, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x4F, 0x01, 0xFF, + 0x01, 0xE1, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x30, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x10, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x20, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x50, 0x06, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFA, 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x08, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE8, + 0x01, 0x54, 0x04, 0x44, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x4F, 0x09, 0xFF, 0x01, 0xD0, 0x09, 0x00, 0x01, 0x03, 0x01, 0xDF, + 0x08, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0x05, 0x01, 0xAE, 0x07, 0xFF, + 0x01, 0xD0, 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x32, + 0x01, 0x22, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xD0, 0x0C, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xE2, 0x02, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x0B, 0x00, 0x01, 0x08, 0x02, 0xFF, 0x01, 0x30, 0x02, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xF5, + 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0x04, + 0x02, 0xFF, 0x01, 0x60, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x0A, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x90, 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x09, 0x00, + 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xD0, 0x09, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0x08, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xE1, 0x06, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x20, + 0x06, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, 0x07, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xF4, 0x07, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xD0, + 0xCF, 0x00, /* 32 */ - 0xff, 0x00, 0x45, 0x00, 0x01, 0x01, 0x01, 0x11, 0x10, 0x00, 0x01, 0x02, - 0x01, 0x8d, 0x02, 0xff, 0x01, 0xfd, 0x01, 0x93, 0x0e, 0x00, 0x01, 0x9f, - 0x05, 0xff, 0x01, 0xb0, 0x0c, 0x00, 0x01, 0x0b, 0x06, 0xff, 0x01, 0xfb, - 0x0c, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf8, 0x01, 0x42, 0x01, 0x12, - 0x01, 0x4a, 0x02, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0xcf, 0x01, 0xff, - 0x01, 0x30, 0x03, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x90, 0x0b, 0x00, - 0x01, 0xff, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xb0, - 0x0a, 0x00, 0x01, 0x02, 0x01, 0xdd, 0x01, 0xd5, 0x04, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xc0, - 0x11, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xc0, 0x0e, 0x00, 0x01, 0x02, - 0x01, 0x57, 0x01, 0xad, 0x02, 0xff, 0x01, 0xc0, 0x0c, 0x00, 0x01, 0x16, - 0x01, 0xad, 0x05, 0xff, 0x01, 0xc0, 0x0b, 0x00, 0x01, 0x09, 0x04, 0xff, - 0x01, 0xfe, 0x01, 0x9d, 0x01, 0xff, 0x01, 0xc0, 0x0b, 0x00, 0x01, 0xcf, - 0x02, 0xff, 0x01, 0xc9, 0x01, 0x64, 0x01, 0x10, 0x01, 0x0b, 0x01, 0xff, - 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x71, - 0x03, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x70, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xc0, - 0x0a, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf2, 0x03, 0x00, 0x01, 0x0a, - 0x02, 0xff, 0x01, 0xc0, 0x0a, 0x00, 0x01, 0x07, 0x02, 0xff, 0x01, 0x83, - 0x01, 0x12, 0x01, 0x48, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf4, 0x0b, 0x00, - 0x01, 0xcf, 0x05, 0xff, 0x01, 0x76, 0x02, 0xff, 0x01, 0xf6, 0x0a, 0x00, - 0x01, 0x1b, 0x04, 0xff, 0x01, 0xc3, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, - 0x01, 0xf6, 0x0b, 0x00, 0x01, 0x39, 0x01, 0xce, 0x01, 0xdc, 0x01, 0x94, - 0x02, 0x00, 0x01, 0x2a, 0x01, 0xde, 0x01, 0xb3, 0xbd, 0x00, + 0xFF, 0x00, 0x45, 0x00, 0x01, 0x01, 0x01, 0x11, 0x10, 0x00, 0x01, 0x02, + 0x01, 0x8D, 0x02, 0xFF, 0x01, 0xFD, 0x01, 0x93, 0x0E, 0x00, 0x01, 0x9F, + 0x05, 0xFF, 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x0B, 0x06, 0xFF, 0x01, 0xFB, + 0x0C, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x42, 0x01, 0x12, + 0x01, 0x4A, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x30, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xB0, + 0x0A, 0x00, 0x01, 0x02, 0x01, 0xDD, 0x01, 0xD5, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xC0, + 0x11, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xC0, 0x0E, 0x00, 0x01, 0x02, + 0x01, 0x57, 0x01, 0xAD, 0x02, 0xFF, 0x01, 0xC0, 0x0C, 0x00, 0x01, 0x16, + 0x01, 0xAD, 0x05, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0x09, 0x04, 0xFF, + 0x01, 0xFE, 0x01, 0x9D, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0xCF, + 0x02, 0xFF, 0x01, 0xC9, 0x01, 0x64, 0x01, 0x10, 0x01, 0x0B, 0x01, 0xFF, + 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x71, + 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xC0, + 0x0A, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0x0A, + 0x02, 0xFF, 0x01, 0xC0, 0x0A, 0x00, 0x01, 0x07, 0x02, 0xFF, 0x01, 0x83, + 0x01, 0x12, 0x01, 0x48, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF4, 0x0B, 0x00, + 0x01, 0xCF, 0x05, 0xFF, 0x01, 0x76, 0x02, 0xFF, 0x01, 0xF6, 0x0A, 0x00, + 0x01, 0x1B, 0x04, 0xFF, 0x01, 0xC3, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0xF6, 0x0B, 0x00, 0x01, 0x39, 0x01, 0xCE, 0x01, 0xDC, 0x01, 0x94, + 0x02, 0x00, 0x01, 0x2A, 0x01, 0xDE, 0x01, 0xB3, 0xBD, 0x00, /* 33 */ - 0x93, 0x00, 0x01, 0x03, 0x01, 0xcc, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xd0, 0x10, 0x00, 0x01, 0x26, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xa0, 0x0d, 0x00, 0x01, 0x02, 0x01, 0x69, 0x01, 0xbe, 0x03, 0xff, - 0x01, 0x40, 0x0c, 0x00, 0x01, 0x02, 0x01, 0xcf, 0x04, 0xff, 0x01, 0xf6, - 0x0d, 0x00, 0x01, 0x3f, 0x03, 0xff, 0x01, 0xfe, 0x01, 0xa6, 0x01, 0x10, - 0x0d, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xfc, 0x01, 0x85, 0x01, 0x10, - 0x0e, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, 0x11, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x40, 0x11, 0x00, 0x01, 0x7f, 0x01, 0xf7, 0x02, 0x00, - 0x01, 0x10, 0x0f, 0x00, 0x01, 0xdf, 0x01, 0xe0, 0x01, 0x3a, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xfb, 0x01, 0x71, 0x0c, 0x00, 0x01, 0x01, 0x01, 0xff, - 0x01, 0x99, 0x04, 0xff, 0x01, 0xfe, 0x01, 0x60, 0x0b, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xdf, 0x05, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x08, - 0x02, 0xff, 0x01, 0xfe, 0x01, 0x72, 0x01, 0x11, 0x01, 0x5b, 0x02, 0xff, - 0x01, 0x50, 0x0a, 0x00, 0x01, 0x0b, 0x02, 0xff, 0x01, 0xc1, 0x03, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x01, 0xe1, 0x0a, 0x00, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf7, - 0x0a, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xf6, 0x04, 0x00, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xfd, 0x0a, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xf1, - 0x05, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x50, - 0x09, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x80, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x05, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x50, - 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf1, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf8, - 0x04, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfd, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf6, - 0x0b, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xe3, 0x03, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0xd0, 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, 0x01, 0xa6, - 0x01, 0x45, 0x01, 0x8e, 0x02, 0xff, 0x01, 0x30, 0x0b, 0x00, 0x01, 0x01, - 0x01, 0xcf, 0x05, 0xff, 0x01, 0xf5, 0x0d, 0x00, 0x01, 0x08, 0x04, 0xff, - 0x01, 0xfc, 0x01, 0x30, 0x0e, 0x00, 0x01, 0x16, 0x01, 0xac, 0x01, 0xed, - 0x01, 0xc8, 0x01, 0x30, 0xc0, 0x00, + 0x93, 0x00, 0x01, 0x03, 0x01, 0xCC, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xD0, 0x10, 0x00, 0x01, 0x26, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xA0, 0x0D, 0x00, 0x01, 0x02, 0x01, 0x69, 0x01, 0xBE, 0x03, 0xFF, + 0x01, 0x40, 0x0C, 0x00, 0x01, 0x02, 0x01, 0xCF, 0x04, 0xFF, 0x01, 0xF6, + 0x0D, 0x00, 0x01, 0x3F, 0x03, 0xFF, 0x01, 0xFE, 0x01, 0xA6, 0x01, 0x10, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x85, 0x01, 0x10, + 0x0E, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x11, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x40, 0x11, 0x00, 0x01, 0x7F, 0x01, 0xF7, 0x02, 0x00, + 0x01, 0x10, 0x0F, 0x00, 0x01, 0xDF, 0x01, 0xE0, 0x01, 0x3A, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x71, 0x0C, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0x99, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xDF, 0x05, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x08, + 0x02, 0xFF, 0x01, 0xFE, 0x01, 0x72, 0x01, 0x11, 0x01, 0x5B, 0x02, 0xFF, + 0x01, 0x50, 0x0A, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x01, 0xC1, 0x03, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE1, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF7, + 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFD, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF6, + 0x0B, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE3, 0x03, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xA6, + 0x01, 0x45, 0x01, 0x8E, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, 0x01, 0x01, + 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF5, 0x0D, 0x00, 0x01, 0x08, 0x04, 0xFF, + 0x01, 0xFC, 0x01, 0x30, 0x0E, 0x00, 0x01, 0x16, 0x01, 0xAC, 0x01, 0xED, + 0x01, 0xC8, 0x01, 0x30, 0xC0, 0x00, /* 34 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x04, 0x77, 0x01, 0x63, 0x0e, 0x00, - 0x01, 0xef, 0x05, 0xff, 0x01, 0xd5, 0x0d, 0x00, 0x01, 0xef, 0x06, 0xff, - 0x01, 0x60, 0x0c, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x02, 0x99, 0x01, 0xac, - 0x02, 0xff, 0x01, 0xf1, 0x0c, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, - 0x01, 0x2d, 0x01, 0xff, 0x01, 0xf5, 0x0c, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x03, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf7, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x0c, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x2d, 0x01, 0xff, 0x01, 0xe0, - 0x0c, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x02, 0x99, 0x01, 0xac, 0x02, 0xff, - 0x01, 0x40, 0x0c, 0x00, 0x01, 0xef, 0x05, 0xff, 0x01, 0xf3, 0x0d, 0x00, - 0x01, 0xef, 0x05, 0xff, 0x01, 0xfe, 0x01, 0x60, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xfc, 0x03, 0x88, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0x30, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x01, 0x70, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0x90, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x04, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0x90, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x04, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x70, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xfa, 0x03, 0x22, 0x01, 0x4b, 0x02, 0xff, 0x01, 0x10, - 0x0b, 0x00, 0x01, 0xef, 0x06, 0xff, 0x01, 0xf8, 0x0c, 0x00, 0x01, 0xef, - 0x06, 0xff, 0x01, 0x80, 0x0c, 0x00, 0x01, 0xef, 0x04, 0xff, 0x01, 0xfd, - 0x01, 0x93, 0xd4, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x04, 0x77, 0x01, 0x63, 0x0E, 0x00, + 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xD5, 0x0D, 0x00, 0x01, 0xEF, 0x06, 0xFF, + 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x02, 0x99, 0x01, 0xAC, + 0x02, 0xFF, 0x01, 0xF1, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, + 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF5, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x03, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF7, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xE0, + 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x02, 0x99, 0x01, 0xAC, 0x02, 0xFF, + 0x01, 0x40, 0x0C, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF3, 0x0D, 0x00, + 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x03, 0x88, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x02, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x30, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x90, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x70, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFA, 0x03, 0x22, 0x01, 0x4B, 0x02, 0xFF, 0x01, 0x10, + 0x0B, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0x80, 0x0C, 0x00, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xFD, + 0x01, 0x93, 0xD4, 0x00, /* 35 */ - 0xff, 0x00, 0x56, 0x00, 0x06, 0x77, 0x01, 0x70, 0x0d, 0x00, 0x01, 0xef, - 0x05, 0xff, 0x01, 0xf0, 0x0d, 0x00, 0x01, 0xef, 0x05, 0xff, 0x01, 0xf0, - 0x0d, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x04, 0x99, 0x01, 0x90, 0x0d, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0xd9, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x06, 0x77, 0x01, 0x70, 0x0D, 0x00, 0x01, 0xEF, + 0x05, 0xFF, 0x01, 0xF0, 0x0D, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF0, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x04, 0x99, 0x01, 0x90, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0xD9, 0x00, /* 36 */ - 0xff, 0x00, 0x58, 0x00, 0x01, 0x57, 0x06, 0x77, 0x01, 0x20, 0x0c, 0x00, - 0x01, 0xcf, 0x06, 0xff, 0x01, 0x50, 0x0c, 0x00, 0x01, 0xdf, 0x06, 0xff, - 0x01, 0x50, 0x0c, 0x00, 0x01, 0xdf, 0x01, 0xfd, 0x03, 0x99, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0x50, 0x0c, 0x00, 0x01, 0xdf, 0x01, 0xfa, 0x03, 0x00, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0c, 0x00, 0x01, 0xef, 0x01, 0xfa, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xfa, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0c, 0x00, - 0x01, 0xef, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, - 0x0c, 0x00, 0x01, 0xff, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, - 0x01, 0x50, 0x0c, 0x00, 0x01, 0xff, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xf8, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf6, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, - 0x0b, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf5, 0x03, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf3, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf0, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, - 0x0b, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x90, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0x30, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x50, - 0x0a, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xfd, 0x04, 0x22, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x50, 0x09, 0x00, 0x01, 0x6a, 0x01, 0xae, 0x08, 0xff, - 0x01, 0xca, 0x01, 0xa0, 0x08, 0x00, 0x01, 0x9f, 0x0a, 0xff, 0x01, 0xf0, - 0x08, 0x00, 0x01, 0x9f, 0x0a, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x9f, - 0x01, 0xf5, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x9f, - 0x01, 0xf5, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x9f, - 0x01, 0xf5, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x9f, - 0x01, 0xf5, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf0, 0x08, 0x00, 0x01, 0x8e, - 0x01, 0xe5, 0x08, 0x00, 0x01, 0xde, 0x01, 0xe0, 0x6c, 0x00, + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x57, 0x06, 0x77, 0x01, 0x20, 0x0C, 0x00, + 0x01, 0xCF, 0x06, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x06, 0xFF, + 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFD, 0x03, 0x99, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xDF, 0x01, 0xFA, 0x03, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFA, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, + 0x01, 0x50, 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF6, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x90, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0x30, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x50, + 0x0A, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFD, 0x04, 0x22, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x6A, 0x01, 0xAE, 0x08, 0xFF, + 0x01, 0xCA, 0x01, 0xA0, 0x08, 0x00, 0x01, 0x9F, 0x0A, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0x9F, 0x0A, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x9F, + 0x01, 0xF5, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0x8E, + 0x01, 0xE5, 0x08, 0x00, 0x01, 0xDE, 0x01, 0xE0, 0x6C, 0x00, /* 37 */ - 0xff, 0x00, 0x58, 0x00, 0x01, 0x28, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xfc, - 0x01, 0x71, 0x0e, 0x00, 0x01, 0x09, 0x05, 0xff, 0x01, 0x60, 0x0c, 0x00, - 0x01, 0x01, 0x01, 0xcf, 0x05, 0xff, 0x01, 0xf8, 0x0c, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x73, 0x01, 0x11, 0x01, 0x5b, 0x02, 0xff, - 0x01, 0x50, 0x0b, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xc1, 0x03, 0x00, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0xe0, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xfe, - 0x01, 0x10, 0x03, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf6, 0x0a, 0x00, - 0x01, 0x05, 0x01, 0xff, 0x01, 0xf5, 0x05, 0x00, 0x01, 0xdf, 0x01, 0xfc, - 0x0a, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xe0, 0x05, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x0a, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xb0, 0x05, 0x00, - 0x01, 0x4f, 0x01, 0xff, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xc6, 0x05, 0x66, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x60, 0x09, 0x00, - 0x01, 0x1f, 0x09, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2f, 0x09, 0xff, - 0x01, 0x80, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xb6, 0x07, 0x66, - 0x01, 0x30, 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x80, 0x11, 0x00, - 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, 0x11, 0x00, 0x01, 0x0a, 0x01, 0xff, - 0x01, 0xf0, 0x05, 0x00, 0x01, 0x48, 0x01, 0x88, 0x0a, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xef, 0x01, 0xfc, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd2, 0x03, 0x00, - 0x01, 0x6f, 0x01, 0xff, 0x01, 0xe1, 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, - 0x01, 0xa6, 0x01, 0x45, 0x01, 0x7c, 0x02, 0xff, 0x01, 0x50, 0x0b, 0x00, - 0x01, 0x01, 0x01, 0xcf, 0x05, 0xff, 0x01, 0xf6, 0x0d, 0x00, 0x01, 0x08, - 0x04, 0xff, 0x01, 0xfd, 0x01, 0x40, 0x0e, 0x00, 0x01, 0x16, 0x01, 0xad, - 0x01, 0xee, 0x01, 0xc9, 0x01, 0x40, 0xc0, 0x00, + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x28, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xFC, + 0x01, 0x71, 0x0E, 0x00, 0x01, 0x09, 0x05, 0xFF, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x73, 0x01, 0x11, 0x01, 0x5B, 0x02, 0xFF, + 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xE0, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF6, 0x0A, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, 0x01, 0xDF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xB0, 0x05, 0x00, + 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xC6, 0x05, 0x66, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x60, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x2F, 0x09, 0xFF, + 0x01, 0x80, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB6, 0x07, 0x66, + 0x01, 0x30, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, + 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0x48, 0x01, 0x88, 0x0A, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFC, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x00, + 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xE1, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, + 0x01, 0xA6, 0x01, 0x45, 0x01, 0x7C, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, + 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x08, + 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x40, 0x0E, 0x00, 0x01, 0x16, 0x01, 0xAD, + 0x01, 0xEE, 0x01, 0xC9, 0x01, 0x40, 0xC0, 0x00, /* 38 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x03, 0x02, 0x77, 0x03, 0x00, 0x01, 0x01, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x03, 0x02, 0x77, 0x03, 0x00, 0x01, 0x01, 0x01, 0x77, 0x01, 0x71, 0x03, 0x00, 0x01, 0x06, 0x01, 0x77, 0x01, 0x73, - 0x06, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xb0, 0x02, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xb0, - 0x06, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfb, 0x02, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x02, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xfb, - 0x08, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xa0, 0x01, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x02, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xc0, - 0x08, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfa, 0x01, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x01, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfc, - 0x0a, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0xa0, 0x01, 0x03, 0x01, 0xff, - 0x01, 0xf4, 0x01, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xc0, 0x0a, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf9, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0xbf, 0x01, 0xff, - 0x01, 0x93, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xc1, - 0x0c, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfb, 0x01, 0xff, 0x01, 0xfb, - 0x01, 0xff, 0x01, 0xfc, 0x01, 0x10, 0x0d, 0x00, 0x01, 0xcf, 0x04, 0xff, - 0x01, 0xd1, 0x0e, 0x00, 0x01, 0x0d, 0x03, 0xff, 0x01, 0xfd, 0x01, 0x10, - 0x0e, 0x00, 0x01, 0x5f, 0x04, 0xff, 0x01, 0x60, 0x0d, 0x00, 0x01, 0x05, - 0x05, 0xff, 0x01, 0xf6, 0x0d, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xe5, - 0x01, 0xff, 0x01, 0xf5, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x60, 0x0b, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x23, 0x01, 0xff, 0x01, 0xf4, - 0x01, 0x1d, 0x01, 0xff, 0x01, 0xf7, 0x0b, 0x00, 0x01, 0x6f, 0x01, 0xff, - 0x01, 0xe2, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x01, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xfd, - 0x01, 0x20, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x00, 0x01, 0x1d, - 0x01, 0xff, 0x01, 0xf7, 0x09, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xd1, - 0x01, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x00, 0x01, 0x01, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0x70, 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x10, 0x01, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, - 0x02, 0x00, 0x01, 0x1c, 0x01, 0xff, 0x01, 0xf8, 0x07, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0xd1, 0x02, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf4, - 0x02, 0x00, 0x01, 0x01, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x80, 0x05, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xfd, 0x01, 0x10, 0x02, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x1c, 0x01, 0xff, 0x01, 0xf8, - 0x05, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd1, 0x03, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x01, 0x01, 0xcf, 0x01, 0xff, - 0x01, 0x80, 0xcc, 0x00, + 0x06, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, + 0x06, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFB, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFB, + 0x08, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, + 0x08, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFA, 0x01, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, + 0x0A, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xA0, 0x01, 0x03, 0x01, 0xFF, + 0x01, 0xF4, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0A, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x01, 0x93, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xC1, + 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0xFF, 0x01, 0xFB, + 0x01, 0xFF, 0x01, 0xFC, 0x01, 0x10, 0x0D, 0x00, 0x01, 0xCF, 0x04, 0xFF, + 0x01, 0xD1, 0x0E, 0x00, 0x01, 0x0D, 0x03, 0xFF, 0x01, 0xFD, 0x01, 0x10, + 0x0E, 0x00, 0x01, 0x5F, 0x04, 0xFF, 0x01, 0x60, 0x0D, 0x00, 0x01, 0x05, + 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xE5, + 0x01, 0xFF, 0x01, 0xF5, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x23, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x1D, 0x01, 0xFF, 0x01, 0xF7, 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xE2, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x01, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x20, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x1D, + 0x01, 0xFF, 0x01, 0xF7, 0x09, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD1, + 0x01, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x01, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x10, 0x01, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x02, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF8, 0x07, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xD1, 0x02, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF4, + 0x02, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xFD, 0x01, 0x10, 0x02, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF8, + 0x05, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD1, 0x03, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0x80, 0xCC, 0x00, /* 39 */ - 0xff, 0x00, 0x45, 0x00, 0x01, 0x01, 0x11, 0x00, 0x01, 0x17, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0xa5, 0x0e, 0x00, 0x01, 0x06, 0x05, 0xff, - 0x01, 0xd3, 0x0d, 0x00, 0x01, 0x5f, 0x06, 0xff, 0x01, 0x30, 0x0c, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0xc5, 0x01, 0x21, 0x01, 0x26, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0xd0, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xfb, - 0x03, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, 0x0b, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf3, 0x03, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xf9, - 0x0b, 0x00, 0x01, 0x05, 0x01, 0x88, 0x01, 0x80, 0x04, 0x00, 0x01, 0xff, - 0x01, 0xfa, 0x11, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf9, 0x11, 0x00, - 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf4, 0x0e, 0x00, 0x01, 0x01, 0x01, 0x33, - 0x01, 0x36, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xb0, 0x0e, 0x00, 0x01, 0x09, - 0x03, 0xff, 0x01, 0xfa, 0x01, 0x10, 0x0e, 0x00, 0x01, 0x09, 0x03, 0xff, - 0x01, 0xfa, 0x01, 0x10, 0x0e, 0x00, 0x01, 0x08, 0x01, 0xee, 0x03, 0xff, - 0x01, 0xe3, 0x10, 0x00, 0x01, 0x01, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xfd, - 0x11, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x40, 0x0a, 0x00, 0x01, 0x06, - 0x01, 0x66, 0x01, 0x30, 0x04, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x70, - 0x0a, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xb0, 0x04, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x80, 0x0a, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xf1, - 0x04, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x60, 0x0a, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xfb, 0x03, 0x00, 0x01, 0x04, 0x02, 0xff, 0x01, 0x10, - 0x0a, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0xe8, 0x01, 0x53, 0x01, 0x46, - 0x01, 0xbf, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, 0x01, 0x7f, 0x06, 0xff, - 0x01, 0xb0, 0x0c, 0x00, 0x01, 0x06, 0x01, 0xef, 0x04, 0xff, 0x01, 0xf7, - 0x0e, 0x00, 0x01, 0x05, 0x01, 0x9c, 0x01, 0xde, 0x01, 0xdc, 0x01, 0x95, - 0xc1, 0x00, + 0xFF, 0x00, 0x45, 0x00, 0x01, 0x01, 0x11, 0x00, 0x01, 0x17, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0xA5, 0x0E, 0x00, 0x01, 0x06, 0x05, 0xFF, + 0x01, 0xD3, 0x0D, 0x00, 0x01, 0x5F, 0x06, 0xFF, 0x01, 0x30, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xC5, 0x01, 0x21, 0x01, 0x26, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, + 0x03, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, + 0x0B, 0x00, 0x01, 0x05, 0x01, 0x88, 0x01, 0x80, 0x04, 0x00, 0x01, 0xFF, + 0x01, 0xFA, 0x11, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF9, 0x11, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF4, 0x0E, 0x00, 0x01, 0x01, 0x01, 0x33, + 0x01, 0x36, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xB0, 0x0E, 0x00, 0x01, 0x09, + 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x09, 0x03, 0xFF, + 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x08, 0x01, 0xEE, 0x03, 0xFF, + 0x01, 0xE3, 0x10, 0x00, 0x01, 0x01, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xFD, + 0x11, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x06, + 0x01, 0x66, 0x01, 0x30, 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x70, + 0x0A, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x80, 0x0A, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xF1, + 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x0A, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFB, 0x03, 0x00, 0x01, 0x04, 0x02, 0xFF, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0xE8, 0x01, 0x53, 0x01, 0x46, + 0x01, 0xBF, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x7F, 0x06, 0xFF, + 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x06, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xF7, + 0x0E, 0x00, 0x01, 0x05, 0x01, 0x9C, 0x01, 0xDE, 0x01, 0xDC, 0x01, 0x95, + 0xC1, 0x00, /* 40 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, - 0x01, 0x77, 0x01, 0x76, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x03, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x0e, 0x02, 0xff, 0x01, 0xfe, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x7f, 0x01, 0xff, - 0x01, 0xcf, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x01, 0x01, 0xff, 0x01, 0xf9, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xe1, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0x70, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0xcf, 0x01, 0xfd, 0x01, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf4, 0x01, 0x00, 0x01, 0x9f, 0x01, 0xfe, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x01, 0xb0, 0x01, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x20, 0x01, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf8, 0x02, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xe0, 0x02, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0x60, 0x02, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0xdf, 0x01, 0xfc, 0x03, 0x00, 0x01, 0x9f, - 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf3, 0x03, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xa0, - 0x03, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x02, 0xff, - 0x01, 0x10, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xff, 0x01, 0xe0, 0x04, 0x00, 0x01, 0x9f, 0x01, 0xfe, - 0xd2, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, + 0x01, 0x77, 0x01, 0x76, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0xCF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE1, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xFD, 0x01, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF4, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x01, 0xB0, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF8, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, 0x01, 0xFC, 0x03, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF3, 0x03, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xA0, + 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0xD2, 0x00, /* 41 */ - 0xca, 0x00, 0x01, 0x2a, 0x01, 0xa2, 0x03, 0x00, 0x01, 0x3a, 0x01, 0xa2, - 0x0d, 0x00, 0x01, 0x2f, 0x01, 0xf9, 0x03, 0x00, 0x01, 0xaf, 0x01, 0xf1, - 0x0d, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0x82, 0x01, 0x00, 0x01, 0x29, - 0x01, 0xff, 0x01, 0xc0, 0x0d, 0x00, 0x01, 0x05, 0x05, 0xff, 0x01, 0x30, - 0x0e, 0x00, 0x01, 0x7f, 0x03, 0xff, 0x01, 0xf6, 0x0f, 0x00, 0x01, 0x02, - 0x01, 0x8b, 0x01, 0xdd, 0x01, 0xb8, 0x01, 0x10, 0x21, 0x00, 0x01, 0x67, - 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, 0x01, 0x77, 0x01, 0x76, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0xfe, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, - 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x05, - 0x02, 0xff, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, - 0x01, 0x0e, 0x02, 0xff, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x03, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xcf, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xf9, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf1, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0x70, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0xcf, 0x01, 0xfd, 0x01, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf4, - 0x01, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x01, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, 0x01, 0x00, 0x01, 0x9f, - 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x20, 0x01, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x02, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xe0, 0x02, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x60, 0x02, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0xdf, - 0x01, 0xfc, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, - 0x02, 0xff, 0x01, 0xf3, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, - 0x01, 0xef, 0x02, 0xff, 0x01, 0xa0, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xfe, - 0x0b, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0x10, 0x03, 0x00, 0x01, 0x9f, - 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xe0, - 0x04, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0xd2, 0x00, + 0xCA, 0x00, 0x01, 0x2A, 0x01, 0xA2, 0x03, 0x00, 0x01, 0x3A, 0x01, 0xA2, + 0x0D, 0x00, 0x01, 0x2F, 0x01, 0xF9, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xF1, + 0x0D, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0x82, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xFF, 0x01, 0xC0, 0x0D, 0x00, 0x01, 0x05, 0x05, 0xFF, 0x01, 0x30, + 0x0E, 0x00, 0x01, 0x7F, 0x03, 0xFF, 0x01, 0xF6, 0x0F, 0x00, 0x01, 0x02, + 0x01, 0x8B, 0x01, 0xDD, 0x01, 0xB8, 0x01, 0x10, 0x21, 0x00, 0x01, 0x67, + 0x01, 0x74, 0x04, 0x00, 0x01, 0x05, 0x01, 0x77, 0x01, 0x76, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x05, + 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, + 0x01, 0x0E, 0x02, 0xFF, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xCF, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF9, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x70, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFD, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x20, 0x01, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xE0, 0x02, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x60, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, + 0x01, 0xFC, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xF3, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xA0, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFE, + 0x0B, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x10, 0x03, 0x00, 0x01, 0x9F, + 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xE0, + 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0xD2, 0x00, /* 42 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x67, - 0x01, 0x77, 0x01, 0x10, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x03, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf6, 0x0c, 0x00, 0x01, 0xef, 0x01, 0xf8, - 0x03, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x60, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf8, 0x02, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf5, 0x0d, 0x00, - 0x01, 0xef, 0x01, 0xf8, 0x02, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x50, - 0x0d, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x00, 0x01, 0x0a, 0x01, 0xff, - 0x01, 0xf5, 0x0e, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0x50, 0x0e, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xf4, 0x0f, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x40, 0x0f, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf4, - 0x10, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0x40, 0x10, 0x00, 0x01, 0xef, - 0x02, 0xff, 0x01, 0xa0, 0x10, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xfa, - 0x10, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xb0, - 0x0f, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xfb, - 0x0f, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0xb0, 0x0e, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x01, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xfb, 0x0e, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x02, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0xc0, 0x0d, 0x00, 0x01, 0xef, 0x01, 0xf8, - 0x02, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfc, 0x0d, 0x00, 0x01, 0xef, - 0x01, 0xf8, 0x03, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xc0, 0x0c, 0x00, - 0x01, 0xef, 0x01, 0xf8, 0x03, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfc, - 0x0c, 0x00, 0x01, 0xef, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x9f, 0x01, 0xff, - 0x01, 0xc1, 0xd2, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x04, 0x00, 0x01, 0x67, + 0x01, 0x77, 0x01, 0x10, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x03, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF8, + 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x60, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF8, 0x02, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF5, 0x0D, 0x00, + 0x01, 0xEF, 0x01, 0xF8, 0x02, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x50, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF5, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x50, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x40, 0x0F, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF4, + 0x10, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x40, 0x10, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0xA0, 0x10, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFA, + 0x10, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xB0, + 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xFB, + 0x0F, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xB0, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x01, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xFB, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x02, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF8, + 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, 0x0D, 0x00, 0x01, 0xEF, + 0x01, 0xF8, 0x03, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xC0, 0x0C, 0x00, + 0x01, 0xEF, 0x01, 0xF8, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0xEF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0xC1, 0xD2, 0x00, /* 43 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x02, 0x06, 0x77, 0x01, 0x75, 0x0c, 0x00, - 0x01, 0x05, 0x06, 0xff, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x05, 0x06, 0xff, - 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xfb, 0x03, 0xaa, - 0x01, 0xef, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf2, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, - 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, - 0x0c, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, 0x01, 0xbf, - 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, - 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, - 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x08, 0x01, 0xff, - 0x01, 0xf0, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf0, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xd0, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, - 0x0c, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xb0, 0x03, 0x00, 0x01, 0xbf, - 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x80, 0x03, 0x00, - 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x3f, 0x01, 0xff, 0x01, 0x40, - 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x9f, 0x01, 0xff, - 0x01, 0x10, 0x03, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0b, 0x00, 0x01, 0x04, - 0x01, 0xff, 0x01, 0xf9, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xfc, 0x0b, 0x00, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xfc, - 0x0b, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x70, 0x04, 0x00, 0x01, 0xbf, - 0x01, 0xfc, 0x0b, 0x00, 0x01, 0x9f, 0x01, 0xf6, 0x05, 0x00, 0x01, 0xbf, - 0x01, 0xfc, 0x0b, 0x00, 0x01, 0x34, 0xc7, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x02, 0x06, 0x77, 0x01, 0x75, 0x0C, 0x00, + 0x01, 0x05, 0x06, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x06, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xFB, 0x03, 0xAA, + 0x01, 0xEF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, + 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xD0, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0C, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x80, 0x03, 0x00, + 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x3F, 0x01, 0xFF, 0x01, 0x40, + 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0x10, 0x03, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x04, + 0x01, 0xFF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFC, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFC, + 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xF6, 0x05, 0x00, 0x01, 0xBF, + 0x01, 0xFC, 0x0B, 0x00, 0x01, 0x34, 0xC7, 0x00, /* 44 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, - 0x01, 0x03, 0x02, 0x77, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xd0, - 0x04, 0x00, 0x01, 0x0b, 0x02, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, - 0x01, 0xf3, 0x04, 0x00, 0x01, 0x2f, 0x02, 0xff, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0xfa, 0x04, 0x00, 0x01, 0x9f, 0x02, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x02, 0xff, 0x01, 0x10, 0x03, 0x00, 0x03, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x02, 0xff, 0x01, 0x80, 0x02, 0x00, 0x01, 0x06, 0x03, 0xff, - 0x0a, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xe0, 0x02, 0x00, 0x01, 0x0d, - 0x03, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0xdf, 0x01, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0xdf, 0x01, 0xfc, 0x02, 0x00, 0x01, 0xaf, - 0x01, 0xfe, 0x01, 0x8f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x01, 0x7f, 0x01, 0xff, 0x01, 0x30, 0x01, 0x01, 0x01, 0xff, 0x01, 0xf8, - 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf2, 0x01, 0x7f, - 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x0a, 0x01, 0xff, - 0x01, 0xf1, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, 0x01, 0x7f, 0x01, 0xff, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x03, 0x01, 0xff, 0x01, 0xf7, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0x40, 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0xcf, 0x01, 0xfd, 0x01, 0xcf, - 0x01, 0xfe, 0x01, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x6f, 0x02, 0xff, 0x01, 0xf7, 0x01, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, - 0x01, 0x0f, 0x02, 0xff, 0x01, 0xf1, 0x01, 0x00, 0x01, 0x7f, 0x01, 0xff, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x09, 0x02, 0xff, - 0x01, 0xa0, 0x01, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x02, 0x02, 0xff, 0x01, 0x40, 0x01, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0xcf, 0x01, 0xfd, 0x02, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x5f, 0x01, 0xf7, 0x02, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x06, 0x01, 0x61, 0x02, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x0a, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x06, 0x00, 0x01, 0x7f, 0x01, 0xff, 0xd1, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, + 0x01, 0x03, 0x02, 0x77, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xD0, + 0x04, 0x00, 0x01, 0x0B, 0x02, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0xF3, 0x04, 0x00, 0x01, 0x2F, 0x02, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0xFA, 0x04, 0x00, 0x01, 0x9F, 0x02, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x10, 0x03, 0x00, 0x03, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x02, 0xFF, 0x01, 0x80, 0x02, 0x00, 0x01, 0x06, 0x03, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xE0, 0x02, 0x00, 0x01, 0x0D, + 0x03, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0xDF, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0xDF, 0x01, 0xFC, 0x02, 0x00, 0x01, 0xAF, + 0x01, 0xFE, 0x01, 0x8F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x30, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xF8, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x7F, + 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x0A, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, 0x01, 0x7F, 0x01, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x40, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0xCF, 0x01, 0xFD, 0x01, 0xCF, + 0x01, 0xFE, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x6F, 0x02, 0xFF, 0x01, 0xF7, 0x01, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, + 0x01, 0x0F, 0x02, 0xFF, 0x01, 0xF1, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0xA0, 0x01, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x02, 0x02, 0xFF, 0x01, 0x40, 0x01, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFD, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x5F, 0x01, 0xF7, 0x02, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x06, 0x01, 0x61, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x0A, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0xD1, 0x00, /* 45 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, - 0x01, 0x73, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x05, 0xaa, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x07, 0xff, 0x01, 0xf8, 0x0b, 0x00, - 0x01, 0xef, 0x07, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xfc, - 0x05, 0x77, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf8, 0xd2, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, + 0x01, 0x73, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x05, 0xAA, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF8, 0x0B, 0x00, + 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFC, + 0x05, 0x77, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0xD2, 0x00, /* 46 */ - 0xff, 0x00, 0x58, 0x00, 0x01, 0x39, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xeb, - 0x01, 0x60, 0x0e, 0x00, 0x01, 0x1b, 0x04, 0xff, 0x01, 0xfe, 0x01, 0x50, - 0x0c, 0x00, 0x01, 0x02, 0x01, 0xef, 0x05, 0xff, 0x01, 0xf8, 0x0c, 0x00, - 0x01, 0x0d, 0x02, 0xff, 0x01, 0x83, 0x01, 0x12, 0x01, 0x5c, 0x02, 0xff, - 0x01, 0x50, 0x0b, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xd1, 0x03, 0x00, - 0x01, 0x7f, 0x01, 0xff, 0x01, 0xe1, 0x0a, 0x00, 0x01, 0x01, 0x01, 0xff, - 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf7, - 0x0a, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xfd, 0x0a, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf1, - 0x05, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x50, - 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, 0x05, 0x00, 0x01, 0x3f, - 0x01, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, - 0x05, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x05, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x50, - 0x09, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf1, 0x05, 0x00, 0x01, 0xaf, - 0x01, 0xff, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf8, - 0x04, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xfd, 0x0b, 0x00, 0x02, 0xff, - 0x01, 0x20, 0x03, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf6, 0x0b, 0x00, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xe3, 0x03, 0x00, 0x01, 0xaf, 0x01, 0xff, - 0x01, 0xd0, 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, 0x01, 0xa5, 0x01, 0x34, - 0x01, 0x7e, 0x02, 0xff, 0x01, 0x30, 0x0b, 0x00, 0x01, 0x01, 0x01, 0xcf, - 0x05, 0xff, 0x01, 0xf5, 0x0d, 0x00, 0x01, 0x19, 0x04, 0xff, 0x01, 0xfc, - 0x01, 0x30, 0x0e, 0x00, 0x01, 0x27, 0x01, 0xbd, 0x01, 0xee, 0x01, 0xc9, - 0x01, 0x40, 0xc0, 0x00, + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x39, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xEB, + 0x01, 0x60, 0x0E, 0x00, 0x01, 0x1B, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x0C, 0x00, 0x01, 0x02, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x0D, 0x02, 0xFF, 0x01, 0x83, 0x01, 0x12, 0x01, 0x5C, 0x02, 0xFF, + 0x01, 0x50, 0x0B, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xD1, 0x03, 0x00, + 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xE1, 0x0A, 0x00, 0x01, 0x01, 0x01, 0xFF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF7, + 0x0A, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xFD, 0x0A, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF1, + 0x05, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x05, 0x00, 0x01, 0x3F, + 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, + 0x05, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x80, 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x05, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, + 0x09, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0xAF, + 0x01, 0xFF, 0x01, 0x10, 0x09, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFD, 0x0B, 0x00, 0x02, 0xFF, + 0x01, 0x20, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xE3, 0x03, 0x00, 0x01, 0xAF, 0x01, 0xFF, + 0x01, 0xD0, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xA5, 0x01, 0x34, + 0x01, 0x7E, 0x02, 0xFF, 0x01, 0x30, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xCF, + 0x05, 0xFF, 0x01, 0xF5, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFC, + 0x01, 0x30, 0x0E, 0x00, 0x01, 0x27, 0x01, 0xBD, 0x01, 0xEE, 0x01, 0xC9, + 0x01, 0x40, 0xC0, 0x00, /* 47 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x07, 0x77, 0x01, 0x73, 0x0b, 0x00, - 0x01, 0xef, 0x07, 0xff, 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x07, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xfd, 0x05, 0xaa, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0xd2, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x07, 0x77, 0x01, 0x73, 0x0B, 0x00, + 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFD, 0x05, 0xAA, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0xD2, 0x00, /* 48 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0xc7, 0x01, 0x10, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf4, 0x01, 0x08, 0x04, 0xff, 0x01, 0xf6, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf4, 0x01, 0xaf, 0x05, 0xff, 0x01, 0x80, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xfc, 0x01, 0xff, 0x01, 0xf9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xf6, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf3, 0x04, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x70, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf2, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfe, 0x05, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf5, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x05, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf7, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfa, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf8, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfa, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x05, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfe, - 0x05, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf5, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf2, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf4, - 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x70, 0x0a, 0x00, 0x01, 0xef, - 0x02, 0xff, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1b, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x10, 0x0a, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xfb, 0x01, 0x64, - 0x01, 0x58, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf5, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0xaf, 0x05, 0xff, 0x01, 0x70, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x08, 0x04, 0xff, 0x01, 0xe4, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xce, 0x01, 0xed, 0x01, 0xa5, - 0x0d, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xde, 0x01, 0xe8, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x80, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1B, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x64, + 0x01, 0x58, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xE4, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xCE, 0x01, 0xED, 0x01, 0xA5, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xDE, 0x01, 0xE8, 0x25, 0x00, /* 49 */ - 0xff, 0x00, 0x58, 0x00, 0x01, 0x38, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xea, - 0x01, 0x50, 0x0e, 0x00, 0x01, 0x19, 0x04, 0xff, 0x01, 0xfd, 0x01, 0x20, - 0x0c, 0x00, 0x01, 0x01, 0x01, 0xcf, 0x05, 0xff, 0x01, 0xf2, 0x0c, 0x00, - 0x01, 0x0c, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x73, 0x01, 0x12, 0x01, 0x6d, - 0x01, 0xff, 0x01, 0xfd, 0x0c, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xc1, - 0x03, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x60, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xb0, - 0x0a, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf6, 0x04, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xf0, 0x0a, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf1, - 0x04, 0x00, 0x01, 0x04, 0x01, 0xbb, 0x01, 0xb1, 0x0a, 0x00, 0x01, 0x0d, - 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x11, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x70, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, - 0x11, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xc0, 0x05, 0x00, 0x01, 0x55, 0x01, 0x52, 0x0a, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf1, 0x04, 0x00, 0x01, 0x04, 0x01, 0xff, - 0x01, 0xf4, 0x0a, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf6, 0x04, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf1, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x10, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xc0, 0x0b, 0x00, - 0x01, 0x8f, 0x01, 0xff, 0x01, 0xd2, 0x02, 0x00, 0x01, 0x01, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x60, 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, 0x01, 0x94, - 0x01, 0x34, 0x01, 0x8e, 0x01, 0xff, 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x01, - 0x01, 0xdf, 0x05, 0xff, 0x01, 0xe1, 0x0d, 0x00, 0x01, 0x19, 0x04, 0xff, - 0x01, 0xfa, 0x01, 0x10, 0x0e, 0x00, 0x01, 0x27, 0x01, 0xcd, 0x01, 0xee, - 0x01, 0xc8, 0x01, 0x20, 0xc0, 0x00, + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x38, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xEA, + 0x01, 0x50, 0x0E, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFD, 0x01, 0x20, + 0x0C, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, 0x01, 0xF2, 0x0C, 0x00, + 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x73, 0x01, 0x12, 0x01, 0x6D, + 0x01, 0xFF, 0x01, 0xFD, 0x0C, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xC1, + 0x03, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xB0, + 0x0A, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF0, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, + 0x04, 0x00, 0x01, 0x04, 0x01, 0xBB, 0x01, 0xB1, 0x0A, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x70, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, + 0x11, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, 0x11, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xC0, 0x05, 0x00, 0x01, 0x55, 0x01, 0x52, 0x0A, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF1, 0x04, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, + 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xD2, 0x02, 0x00, 0x01, 0x01, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0x94, + 0x01, 0x34, 0x01, 0x8E, 0x01, 0xFF, 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x01, + 0x01, 0xDF, 0x05, 0xFF, 0x01, 0xE1, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, + 0x01, 0xFA, 0x01, 0x10, 0x0E, 0x00, 0x01, 0x27, 0x01, 0xCD, 0x01, 0xEE, + 0x01, 0xC8, 0x01, 0x20, 0xC0, 0x00, /* 50 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x47, 0x06, 0x77, 0x01, 0x76, 0x0c, 0x00, - 0x01, 0x9f, 0x06, 0xff, 0x01, 0xfe, 0x0c, 0x00, 0x01, 0x9f, 0x06, 0xff, - 0x01, 0xfe, 0x0c, 0x00, 0x01, 0x6a, 0x02, 0xaa, 0x01, 0xdf, 0x01, 0xff, - 0x02, 0xaa, 0x01, 0xa9, 0x0f, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, 0x01, 0x9f, 0x01, 0xfe, 0x12, 0x00, - 0x01, 0x9f, 0x01, 0xfe, 0xd7, 0x00, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x47, 0x06, 0x77, 0x01, 0x76, 0x0C, 0x00, + 0x01, 0x9F, 0x06, 0xFF, 0x01, 0xFE, 0x0C, 0x00, 0x01, 0x9F, 0x06, 0xFF, + 0x01, 0xFE, 0x0C, 0x00, 0x01, 0x6A, 0x02, 0xAA, 0x01, 0xDF, 0x01, 0xFF, + 0x02, 0xAA, 0x01, 0xA9, 0x0F, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, 0x01, 0x9F, 0x01, 0xFE, 0x12, 0x00, + 0x01, 0x9F, 0x01, 0xFE, 0xD7, 0x00, /* 51 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x67, 0x01, 0x75, 0x05, 0x00, 0x01, 0x05, - 0x01, 0x77, 0x01, 0x70, 0x0a, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x05, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xb0, 0x0a, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x01, 0x50, 0x04, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x50, 0x0a, 0x00, - 0x01, 0x0f, 0x01, 0xff, 0x01, 0xb0, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xff, - 0x0b, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf0, 0x03, 0x00, 0x01, 0x01, - 0x01, 0xff, 0x01, 0xf9, 0x0b, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf5, - 0x03, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf3, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xfb, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xd0, 0x0c, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x70, - 0x0c, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x50, 0x02, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x20, 0x0c, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, - 0x02, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x0d, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf1, 0x01, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf5, 0x0d, 0x00, - 0x01, 0x04, 0x01, 0xff, 0x01, 0xf5, 0x01, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf0, 0x0e, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x01, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0x90, 0x0e, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0x10, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0x40, 0x0e, 0x00, 0x01, 0x3f, 0x01, 0xff, - 0x01, 0x50, 0x01, 0xbf, 0x01, 0xfd, 0x0f, 0x00, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xb1, 0x01, 0xff, 0x01, 0xf8, 0x0f, 0x00, 0x01, 0x08, 0x01, 0xff, - 0x01, 0xf7, 0x01, 0xff, 0x01, 0xf2, 0x0f, 0x00, 0x01, 0x03, 0x03, 0xff, - 0x01, 0xc0, 0x10, 0x00, 0x01, 0xdf, 0x02, 0xff, 0x01, 0x60, 0x10, 0x00, - 0x01, 0x8f, 0x02, 0xff, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xfa, - 0x11, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf4, 0x11, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x80, - 0x11, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x20, 0x11, 0x00, 0x01, 0xef, - 0x01, 0xfc, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf6, 0x0f, 0x00, - 0x01, 0x05, 0x01, 0x76, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xd0, 0x0f, 0x00, - 0x01, 0x09, 0x03, 0xff, 0x01, 0x50, 0x0f, 0x00, 0x01, 0x09, 0x02, 0xff, - 0x01, 0xf7, 0x10, 0x00, 0x01, 0x05, 0x01, 0xce, 0x01, 0xda, 0x01, 0x30, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x67, 0x01, 0x75, 0x05, 0x00, 0x01, 0x05, + 0x01, 0x77, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x05, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x0A, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0x50, 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x50, 0x0A, 0x00, + 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, + 0x0B, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, 0x03, 0x00, 0x01, 0x01, + 0x01, 0xFF, 0x01, 0xF9, 0x0B, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, + 0x03, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF3, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFB, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xD0, 0x0C, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, + 0x0C, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x20, 0x0C, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x02, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x0D, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF1, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x0D, 0x00, + 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF5, 0x01, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x0E, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0x90, 0x0E, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x10, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x40, 0x0E, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0x50, 0x01, 0xBF, 0x01, 0xFD, 0x0F, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xB1, 0x01, 0xFF, 0x01, 0xF8, 0x0F, 0x00, 0x01, 0x08, 0x01, 0xFF, + 0x01, 0xF7, 0x01, 0xFF, 0x01, 0xF2, 0x0F, 0x00, 0x01, 0x03, 0x03, 0xFF, + 0x01, 0xC0, 0x10, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x60, 0x10, 0x00, + 0x01, 0x8F, 0x02, 0xFF, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xFA, + 0x11, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF4, 0x11, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, + 0x11, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x20, 0x11, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF6, 0x0F, 0x00, + 0x01, 0x05, 0x01, 0x76, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xD0, 0x0F, 0x00, + 0x01, 0x09, 0x03, 0xFF, 0x01, 0x50, 0x0F, 0x00, 0x01, 0x09, 0x02, 0xFF, + 0x01, 0xF7, 0x10, 0x00, 0x01, 0x05, 0x01, 0xCE, 0x01, 0xDA, 0x01, 0x30, 0x24, 0x00, /* 52 */ - 0xe3, 0x00, 0x01, 0x05, 0x01, 0x99, 0x01, 0x80, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, - 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, - 0x0c, 0x00, 0x01, 0x01, 0x01, 0x8d, 0x01, 0xff, 0x01, 0xeb, 0x01, 0x40, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x01, 0x02, 0x01, 0x9e, 0x01, 0xff, - 0x01, 0xea, 0x01, 0x50, 0x07, 0x00, 0x01, 0x6f, 0x03, 0xff, 0x01, 0xfa, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x01, 0x5f, 0x03, 0xff, 0x01, 0xfc, - 0x01, 0x20, 0x05, 0x00, 0x01, 0x06, 0x05, 0xff, 0x01, 0x98, 0x01, 0xff, - 0x01, 0xe4, 0x05, 0xff, 0x01, 0xd1, 0x05, 0x00, 0x01, 0x3f, 0x01, 0xff, - 0x01, 0xfc, 0x01, 0x53, 0x01, 0x36, 0x01, 0xcf, 0x01, 0xfc, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0xff, 0x01, 0x83, 0x01, 0x24, 0x01, 0x9f, 0x01, 0xff, - 0x01, 0xfb, 0x05, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x90, 0x02, 0x00, - 0x01, 0x0a, 0x03, 0xff, 0x01, 0xe2, 0x02, 0x00, 0x01, 0x03, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x40, 0x03, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfc, - 0x04, 0x00, 0x01, 0xdf, 0x02, 0xff, 0x01, 0x40, 0x03, 0x00, 0x01, 0x5f, - 0x01, 0xff, 0x01, 0xb0, 0x03, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf4, - 0x04, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xfb, 0x04, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xe0, - 0x04, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xf6, 0x04, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, - 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf7, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0x90, - 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf9, 0x03, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0x80, 0x04, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf0, 0x05, 0x00, 0x01, 0xff, 0x01, 0xfa, - 0x03, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0x70, 0x04, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x05, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x03, 0x00, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf0, 0x05, 0x00, 0x01, 0xff, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf0, - 0x05, 0x00, 0x01, 0xff, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x0f, 0x01, 0xff, - 0x01, 0xb0, 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf3, 0x04, 0x00, - 0x01, 0x03, 0x01, 0xff, 0x01, 0xf7, 0x03, 0x00, 0x01, 0x0c, 0x01, 0xff, - 0x01, 0xf0, 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf7, 0x04, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf4, 0x03, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf5, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xfc, 0x04, 0x00, - 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf1, 0x03, 0x00, 0x01, 0x04, 0x01, 0xff, - 0x01, 0xfc, 0x04, 0x00, 0x01, 0xdf, 0x02, 0xff, 0x01, 0x40, 0x03, 0x00, - 0x01, 0x5f, 0x01, 0xff, 0x01, 0xb0, 0x04, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xa0, 0x02, 0x00, 0x01, 0x0b, 0x03, 0xff, 0x01, 0xe3, 0x02, 0x00, - 0x01, 0x04, 0x02, 0xff, 0x01, 0x40, 0x04, 0x00, 0x01, 0x5f, 0x01, 0xff, - 0x01, 0xfd, 0x01, 0x74, 0x01, 0x47, 0x01, 0xdf, 0x01, 0xfe, 0x03, 0xff, - 0x01, 0x95, 0x01, 0x45, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xfb, 0x05, 0x00, - 0x01, 0x08, 0x05, 0xff, 0x01, 0xb8, 0x01, 0xff, 0x01, 0xe6, 0x05, 0xff, - 0x01, 0xd1, 0x06, 0x00, 0x01, 0x7f, 0x03, 0xff, 0x01, 0xfa, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x01, 0x6f, 0x03, 0xff, 0x01, 0xfa, 0x01, 0x10, - 0x06, 0x00, 0x01, 0x02, 0x01, 0x8c, 0x01, 0xef, 0x01, 0xdb, 0x01, 0x50, - 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x01, 0x02, 0x01, 0x8d, 0x01, 0xee, - 0x01, 0xd9, 0x01, 0x30, 0x0c, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, - 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, - 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, - 0x11, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xe0, 0x1e, 0x00, + 0xE3, 0x00, 0x01, 0x05, 0x01, 0x99, 0x01, 0x80, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x0C, 0x00, 0x01, 0x01, 0x01, 0x8D, 0x01, 0xFF, 0x01, 0xEB, 0x01, 0x40, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0x9E, 0x01, 0xFF, + 0x01, 0xEA, 0x01, 0x50, 0x07, 0x00, 0x01, 0x6F, 0x03, 0xFF, 0x01, 0xFA, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x5F, 0x03, 0xFF, 0x01, 0xFC, + 0x01, 0x20, 0x05, 0x00, 0x01, 0x06, 0x05, 0xFF, 0x01, 0x98, 0x01, 0xFF, + 0x01, 0xE4, 0x05, 0xFF, 0x01, 0xD1, 0x05, 0x00, 0x01, 0x3F, 0x01, 0xFF, + 0x01, 0xFC, 0x01, 0x53, 0x01, 0x36, 0x01, 0xCF, 0x01, 0xFC, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0xFF, 0x01, 0x83, 0x01, 0x24, 0x01, 0x9F, 0x01, 0xFF, + 0x01, 0xFB, 0x05, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x90, 0x02, 0x00, + 0x01, 0x0A, 0x03, 0xFF, 0x01, 0xE2, 0x02, 0x00, 0x01, 0x03, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x40, 0x03, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFC, + 0x04, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x40, 0x03, 0x00, 0x01, 0x5F, + 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xFB, 0x04, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, + 0x04, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF7, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, 0x01, 0xFA, + 0x03, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x70, 0x04, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x03, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0x90, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF0, + 0x05, 0x00, 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x0F, 0x01, 0xFF, + 0x01, 0xB0, 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xF7, 0x03, 0x00, 0x01, 0x0C, 0x01, 0xFF, + 0x01, 0xF0, 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF7, 0x04, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF4, 0x03, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF5, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xFC, 0x04, 0x00, + 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x03, 0x00, 0x01, 0x04, 0x01, 0xFF, + 0x01, 0xFC, 0x04, 0x00, 0x01, 0xDF, 0x02, 0xFF, 0x01, 0x40, 0x03, 0x00, + 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xB0, 0x04, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xA0, 0x02, 0x00, 0x01, 0x0B, 0x03, 0xFF, 0x01, 0xE3, 0x02, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0x40, 0x04, 0x00, 0x01, 0x5F, 0x01, 0xFF, + 0x01, 0xFD, 0x01, 0x74, 0x01, 0x47, 0x01, 0xDF, 0x01, 0xFE, 0x03, 0xFF, + 0x01, 0x95, 0x01, 0x45, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x08, 0x05, 0xFF, 0x01, 0xB8, 0x01, 0xFF, 0x01, 0xE6, 0x05, 0xFF, + 0x01, 0xD1, 0x06, 0x00, 0x01, 0x7F, 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x6F, 0x03, 0xFF, 0x01, 0xFA, 0x01, 0x10, + 0x06, 0x00, 0x01, 0x02, 0x01, 0x8C, 0x01, 0xEF, 0x01, 0xDB, 0x01, 0x50, + 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x02, 0x01, 0x8D, 0x01, 0xEE, + 0x01, 0xD9, 0x01, 0x30, 0x0C, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, + 0x11, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xE0, 0x1E, 0x00, /* 53 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x37, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, - 0x01, 0x17, 0x01, 0x77, 0x01, 0x40, 0x0a, 0x00, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xe1, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x20, 0x0a, 0x00, - 0x01, 0x03, 0x01, 0xff, 0x01, 0xfb, 0x03, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf6, 0x0c, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x50, 0x02, 0x00, - 0x01, 0x2f, 0x01, 0xff, 0x01, 0xb0, 0x0c, 0x00, 0x01, 0x0d, 0x01, 0xff, - 0x01, 0xe1, 0x02, 0x00, 0x01, 0xcf, 0x01, 0xfe, 0x01, 0x10, 0x0c, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xfb, 0x01, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf5, 0x0e, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0x60, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x90, 0x0e, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf2, - 0x01, 0xcf, 0x01, 0xfd, 0x0f, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0xff, 0x01, 0xf3, 0x10, 0x00, 0x01, 0x6f, 0x02, 0xff, 0x01, 0x70, - 0x10, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xfc, 0x11, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xfd, 0x11, 0x00, 0x01, 0x4f, 0x02, 0xff, 0x01, 0x80, - 0x0f, 0x00, 0x01, 0x01, 0x01, 0xef, 0x02, 0xff, 0x01, 0xf3, 0x0f, 0x00, - 0x01, 0x0a, 0x01, 0xff, 0x01, 0xe3, 0x01, 0xef, 0x01, 0xfd, 0x0f, 0x00, - 0x01, 0x6f, 0x01, 0xff, 0x01, 0x50, 0x01, 0x5f, 0x01, 0xff, 0x01, 0x90, - 0x0d, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfb, 0x01, 0x00, 0x01, 0x0a, - 0x01, 0xff, 0x01, 0xf4, 0x0d, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xe1, - 0x01, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xfd, 0x0d, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0x50, 0x02, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x90, - 0x0b, 0x00, 0x01, 0x03, 0x01, 0xff, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf4, 0x0b, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xe1, - 0x03, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xfe, 0x01, 0x10, 0x0a, 0x00, - 0x01, 0x9f, 0x01, 0xff, 0x01, 0x50, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, - 0x01, 0xa0, 0x0a, 0x00, 0x02, 0x11, 0x05, 0x00, 0x01, 0x01, 0x01, 0x11, - 0x01, 0x10, 0xbe, 0x00, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x37, 0x01, 0x77, 0x01, 0x30, 0x04, 0x00, + 0x01, 0x17, 0x01, 0x77, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xE1, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, 0x0A, 0x00, + 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFB, 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF6, 0x0C, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, + 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xB0, 0x0C, 0x00, 0x01, 0x0D, 0x01, 0xFF, + 0x01, 0xE1, 0x02, 0x00, 0x01, 0xCF, 0x01, 0xFE, 0x01, 0x10, 0x0C, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF5, 0x0E, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0x60, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x90, 0x0E, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF2, + 0x01, 0xCF, 0x01, 0xFD, 0x0F, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0xFF, 0x01, 0xF3, 0x10, 0x00, 0x01, 0x6F, 0x02, 0xFF, 0x01, 0x70, + 0x10, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xFC, 0x11, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFD, 0x11, 0x00, 0x01, 0x4F, 0x02, 0xFF, 0x01, 0x80, + 0x0F, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xF3, 0x0F, 0x00, + 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE3, 0x01, 0xEF, 0x01, 0xFD, 0x0F, 0x00, + 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x50, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0x90, + 0x0D, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, 0x01, 0x00, 0x01, 0x0A, + 0x01, 0xFF, 0x01, 0xF4, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xE1, + 0x01, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFD, 0x0D, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0x50, 0x02, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x90, + 0x0B, 0x00, 0x01, 0x03, 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF4, 0x0B, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xE1, + 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x0A, 0x00, + 0x01, 0x9F, 0x01, 0xFF, 0x01, 0x50, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xA0, 0x0A, 0x00, 0x02, 0x11, 0x05, 0x00, 0x01, 0x01, 0x01, 0x11, + 0x01, 0x10, 0xBE, 0x00, /* 54 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, - 0x01, 0x73, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x00, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x05, 0x11, 0x01, 0xff, - 0x01, 0xf7, 0x0b, 0x00, 0x01, 0xef, 0x07, 0xff, 0x01, 0xfc, 0x01, 0x99, - 0x0a, 0x00, 0x01, 0xef, 0x09, 0xff, 0x0a, 0x00, 0x01, 0xef, 0x09, 0xff, - 0x12, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x12, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x12, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x12, 0x00, 0x01, 0x0e, 0x01, 0xff, - 0x12, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x6d, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x74, 0x05, 0x00, 0x01, 0x77, + 0x01, 0x73, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x00, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x05, 0x11, 0x01, 0xFF, + 0x01, 0xF7, 0x0B, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x01, 0xFC, 0x01, 0x99, + 0x0A, 0x00, 0x01, 0xEF, 0x09, 0xFF, 0x0A, 0x00, 0x01, 0xEF, 0x09, 0xFF, + 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x12, 0x00, 0x01, 0x0E, 0x01, 0xFF, + 0x12, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x6D, 0x00, /* 55 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x02, 0x01, 0x77, 0x01, 0x71, 0x04, 0x00, - 0x01, 0x77, 0x01, 0x73, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, - 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, - 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x04, 0x00, - 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf2, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x03, - 0x01, 0xff, 0x01, 0xf6, 0x04, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, - 0x02, 0xff, 0x01, 0x85, 0x03, 0x55, 0x01, 0xff, 0x01, 0xf8, 0x0c, 0x00, - 0x01, 0x6f, 0x06, 0xff, 0x01, 0xf8, 0x0c, 0x00, 0x01, 0x07, 0x06, 0xff, - 0x01, 0xf8, 0x0d, 0x00, 0x01, 0x17, 0x01, 0xbc, 0x03, 0xcc, 0x01, 0xff, - 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x12, 0x00, 0x01, 0x11, 0x01, 0x10, 0xbf, 0x00, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x02, 0x01, 0x77, 0x01, 0x71, 0x04, 0x00, + 0x01, 0x77, 0x01, 0x73, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, + 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x04, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF2, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x03, + 0x01, 0xFF, 0x01, 0xF6, 0x04, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x02, 0xFF, 0x01, 0x85, 0x03, 0x55, 0x01, 0xFF, 0x01, 0xF8, 0x0C, 0x00, + 0x01, 0x6F, 0x06, 0xFF, 0x01, 0xF8, 0x0C, 0x00, 0x01, 0x07, 0x06, 0xFF, + 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x17, 0x01, 0xBC, 0x03, 0xCC, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x12, 0x00, 0x01, 0x11, 0x01, 0x10, 0xBF, 0x00, /* 56 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x64, 0x02, 0x00, 0x01, 0x01, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x64, 0x02, 0x00, 0x01, 0x01, 0x01, 0x66, 0x01, 0x62, 0x02, 0x00, 0x01, 0x02, 0x01, 0x66, 0x01, 0x60, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x11, 0x01, 0x13, - 0x01, 0xff, 0x01, 0xf6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x0a, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x0a, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x0a, 0xff, 0x01, 0xf1, - 0xcf, 0x00, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x11, 0x01, 0x13, + 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x0A, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF1, + 0xCF, 0x00, /* 57 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x63, 0x02, 0x00, 0x01, 0x01, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x66, 0x01, 0x63, 0x02, 0x00, 0x01, 0x01, 0x01, 0x66, 0x01, 0x62, 0x02, 0x00, 0x01, 0x02, 0x01, 0x66, 0x01, 0x60, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, - 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, - 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x02, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xff, - 0x01, 0xf1, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x11, 0x01, 0x13, - 0x01, 0xff, 0x01, 0xf6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xff, 0x01, 0xf1, - 0x08, 0x00, 0x01, 0xef, 0x0a, 0xff, 0x01, 0xf9, 0x01, 0x95, 0x07, 0x00, - 0x01, 0xef, 0x0b, 0xff, 0x01, 0xf9, 0x07, 0x00, 0x01, 0xef, 0x0b, 0xff, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0x5f, 0x01, 0xf9, 0x12, 0x00, 0x01, 0x5f, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0x5f, 0x01, 0xf9, 0x12, 0x00, 0x01, 0x5f, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0x5f, 0x01, 0xf9, 0x6a, 0x00, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, + 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, + 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x02, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF5, 0x02, 0x00, 0x01, 0x06, 0x01, 0xFF, + 0x01, 0xF1, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x11, 0x01, 0x13, + 0x01, 0xFF, 0x01, 0xF6, 0x02, 0x11, 0x01, 0x17, 0x01, 0xFF, 0x01, 0xF1, + 0x08, 0x00, 0x01, 0xEF, 0x0A, 0xFF, 0x01, 0xF9, 0x01, 0x95, 0x07, 0x00, + 0x01, 0xEF, 0x0B, 0xFF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0xEF, 0x0B, 0xFF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0x5F, 0x01, 0xF9, 0x6A, 0x00, /* 58 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x12, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xff, 0x02, 0xee, 0x01, 0xed, - 0x01, 0xc9, 0x01, 0x60, 0x0d, 0x00, 0x01, 0xef, 0x06, 0xff, 0x01, 0x70, - 0x0c, 0x00, 0x01, 0xef, 0x06, 0xff, 0x01, 0xfa, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xfa, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6a, 0x02, 0xff, 0x01, 0x50, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, - 0x01, 0xd0, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x0c, - 0x01, 0xff, 0x01, 0xf1, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, - 0x01, 0x09, 0x01, 0xff, 0x01, 0xf3, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x04, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf4, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x2f, 0x01, 0xff, 0x01, 0xe0, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x11, 0x01, 0x38, 0x02, 0xff, - 0x01, 0x70, 0x0b, 0x00, 0x01, 0xef, 0x06, 0xff, 0x01, 0xfc, 0x0c, 0x00, - 0x01, 0xef, 0x06, 0xff, 0x01, 0xc1, 0x0c, 0x00, 0x01, 0xef, 0x05, 0xff, - 0x01, 0xb5, 0x0d, 0x00, 0x05, 0x11, 0xc2, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x02, 0xEE, 0x01, 0xED, + 0x01, 0xC9, 0x01, 0x60, 0x0D, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x70, + 0x0C, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFA, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6A, 0x02, 0xFF, 0x01, 0x50, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, + 0x01, 0xD0, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0C, + 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, + 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x2F, 0x01, 0xFF, 0x01, 0xE0, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x11, 0x01, 0x38, 0x02, 0xFF, + 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xFC, 0x0C, 0x00, + 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xC1, 0x0C, 0x00, 0x01, 0xEF, 0x05, 0xFF, + 0x01, 0xB5, 0x0D, 0x00, 0x05, 0x11, 0xC2, 0x00, /* 59 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x07, 0x00, 0x01, 0x02, - 0x01, 0x66, 0x01, 0x60, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x07, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x07, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x07, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xff, - 0x02, 0xee, 0x01, 0xed, 0x01, 0xc9, 0x01, 0x60, 0x02, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x06, 0xff, 0x01, 0x70, - 0x01, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, - 0x06, 0xff, 0x01, 0xfa, 0x01, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xfa, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6b, - 0x02, 0xff, 0x01, 0x50, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xd0, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf1, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf3, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf4, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf2, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x04, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xe0, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x03, 0x11, 0x01, 0x37, 0x02, 0xff, 0x01, 0x70, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x06, 0xff, - 0x01, 0xfc, 0x01, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, - 0x01, 0xef, 0x06, 0xff, 0x01, 0xc1, 0x01, 0x00, 0x01, 0x07, 0x01, 0xff, - 0x01, 0xf0, 0x08, 0x00, 0x01, 0xef, 0x05, 0xff, 0x01, 0xb5, 0x02, 0x00, - 0x01, 0x07, 0x01, 0xff, 0x01, 0xf0, 0x08, 0x00, 0x05, 0x11, 0x05, 0x00, - 0x01, 0x11, 0x01, 0x10, 0xbb, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x07, 0x00, 0x01, 0x02, + 0x01, 0x66, 0x01, 0x60, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x07, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFF, + 0x02, 0xEE, 0x01, 0xED, 0x01, 0xC9, 0x01, 0x60, 0x02, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x06, 0xFF, 0x01, 0x70, + 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xFA, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, 0x01, 0x6B, + 0x02, 0xFF, 0x01, 0x50, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xD0, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF1, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF3, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF4, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xE0, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x11, 0x01, 0x37, 0x02, 0xFF, 0x01, 0x70, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x06, 0xFF, + 0x01, 0xFC, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, + 0x01, 0xEF, 0x06, 0xFF, 0x01, 0xC1, 0x01, 0x00, 0x01, 0x07, 0x01, 0xFF, + 0x01, 0xF0, 0x08, 0x00, 0x01, 0xEF, 0x05, 0xFF, 0x01, 0xB5, 0x02, 0x00, + 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF0, 0x08, 0x00, 0x05, 0x11, 0x05, 0x00, + 0x01, 0x11, 0x01, 0x10, 0xBB, 0x00, /* 60 */ - 0xff, 0x00, 0x55, 0x00, 0x01, 0x36, 0x04, 0x66, 0x01, 0x63, 0x0e, 0x00, - 0x01, 0x9f, 0x04, 0xff, 0x01, 0xf8, 0x0e, 0x00, 0x01, 0x9f, 0x04, 0xff, - 0x01, 0xf8, 0x0e, 0x00, 0x01, 0x6a, 0x03, 0xaa, 0x01, 0xff, 0x01, 0xf8, - 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, - 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x12, 0x00, 0x01, 0xff, 0x01, 0xf8, - 0x12, 0x00, 0x02, 0xff, 0x02, 0xee, 0x01, 0xed, 0x01, 0xc9, 0x01, 0x50, - 0x0d, 0x00, 0x06, 0xff, 0x01, 0xfe, 0x01, 0x60, 0x0c, 0x00, 0x07, 0xff, - 0x01, 0xf9, 0x0c, 0x00, 0x01, 0xff, 0x01, 0xfa, 0x02, 0x33, 0x01, 0x34, - 0x01, 0x6b, 0x02, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xf8, - 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0xc0, 0x0b, 0x00, 0x01, 0xff, - 0x01, 0xf8, 0x04, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf1, 0x0b, 0x00, - 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf3, - 0x0b, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf3, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, 0x01, 0x0b, - 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xf8, 0x04, 0x00, - 0x01, 0x3f, 0x01, 0xff, 0x01, 0xe0, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xf9, - 0x03, 0x11, 0x01, 0x38, 0x02, 0xff, 0x01, 0x70, 0x0b, 0x00, 0x07, 0xff, - 0x01, 0xfc, 0x0c, 0x00, 0x07, 0xff, 0x01, 0xb1, 0x0c, 0x00, 0x06, 0xff, - 0x01, 0xb5, 0x0d, 0x00, 0x05, 0x11, 0xbf, 0x00, + 0xFF, 0x00, 0x55, 0x00, 0x01, 0x36, 0x04, 0x66, 0x01, 0x63, 0x0E, 0x00, + 0x01, 0x9F, 0x04, 0xFF, 0x01, 0xF8, 0x0E, 0x00, 0x01, 0x9F, 0x04, 0xFF, + 0x01, 0xF8, 0x0E, 0x00, 0x01, 0x6A, 0x03, 0xAA, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x12, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x12, 0x00, 0x02, 0xFF, 0x02, 0xEE, 0x01, 0xED, 0x01, 0xC9, 0x01, 0x50, + 0x0D, 0x00, 0x06, 0xFF, 0x01, 0xFE, 0x01, 0x60, 0x0C, 0x00, 0x07, 0xFF, + 0x01, 0xF9, 0x0C, 0x00, 0x01, 0xFF, 0x01, 0xFA, 0x02, 0x33, 0x01, 0x34, + 0x01, 0x6B, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, + 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0xC0, 0x0B, 0x00, 0x01, 0xFF, + 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF1, 0x0B, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF3, + 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF3, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, 0x01, 0x0B, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF8, 0x04, 0x00, + 0x01, 0x3F, 0x01, 0xFF, 0x01, 0xE0, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xF9, + 0x03, 0x11, 0x01, 0x38, 0x02, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x07, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x07, 0xFF, 0x01, 0xB1, 0x0C, 0x00, 0x06, 0xFF, + 0x01, 0xB5, 0x0D, 0x00, 0x05, 0x11, 0xBF, 0x00, /* 61 */ - 0xff, 0x00, 0x57, 0x00, 0x01, 0x02, 0x01, 0x8c, 0x01, 0xff, 0x01, 0xfd, - 0x01, 0x94, 0x0f, 0x00, 0x01, 0x9f, 0x04, 0xff, 0x01, 0xb2, 0x0d, 0x00, - 0x01, 0x0c, 0x05, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x0c, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0xf8, 0x01, 0x42, 0x01, 0x36, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0xe1, 0x0b, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, - 0x02, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfa, 0x0b, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf5, 0x04, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x20, - 0x0a, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xe0, 0x04, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0x90, 0x0a, 0x00, 0x01, 0x0a, 0x01, 0xcc, 0x01, 0x80, - 0x04, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xe0, 0x11, 0x00, 0x01, 0x08, - 0x01, 0xff, 0x01, 0xf1, 0x0d, 0x00, 0x01, 0x69, 0x03, 0x99, 0x01, 0x9b, - 0x01, 0xff, 0x01, 0xf4, 0x0d, 0x00, 0x01, 0xaf, 0x05, 0xff, 0x01, 0xf5, - 0x0d, 0x00, 0x01, 0xaf, 0x05, 0xff, 0x01, 0xf6, 0x0d, 0x00, 0x01, 0x58, - 0x03, 0x88, 0x01, 0x8a, 0x01, 0xff, 0x01, 0xf5, 0x11, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf4, 0x0a, 0x00, 0x01, 0x05, 0x01, 0x55, 0x01, 0x10, - 0x04, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf2, 0x0a, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0x80, 0x04, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xe0, - 0x0a, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xd0, 0x04, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xa0, 0x0a, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xf5, - 0x04, 0x00, 0x01, 0xbf, 0x01, 0xff, 0x01, 0x40, 0x0a, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xfe, 0x01, 0x20, 0x02, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xfc, 0x0c, 0x00, 0x01, 0x9f, 0x01, 0xff, 0x01, 0xf9, 0x01, 0x42, - 0x01, 0x37, 0x01, 0xdf, 0x01, 0xff, 0x01, 0xf2, 0x0c, 0x00, 0x01, 0x0b, - 0x06, 0xff, 0x01, 0x40, 0x0d, 0x00, 0x01, 0x8f, 0x04, 0xff, 0x01, 0xc2, - 0x0e, 0x00, 0x01, 0x01, 0x01, 0x8c, 0x01, 0xef, 0x01, 0xed, 0x01, 0x94, - 0xc1, 0x00, + 0xFF, 0x00, 0x57, 0x00, 0x01, 0x02, 0x01, 0x8C, 0x01, 0xFF, 0x01, 0xFD, + 0x01, 0x94, 0x0F, 0x00, 0x01, 0x9F, 0x04, 0xFF, 0x01, 0xB2, 0x0D, 0x00, + 0x01, 0x0C, 0x05, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x0C, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0xF8, 0x01, 0x42, 0x01, 0x36, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0xE1, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, + 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFA, 0x0B, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF5, 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x20, + 0x0A, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0x90, 0x0A, 0x00, 0x01, 0x0A, 0x01, 0xCC, 0x01, 0x80, + 0x04, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xE0, 0x11, 0x00, 0x01, 0x08, + 0x01, 0xFF, 0x01, 0xF1, 0x0D, 0x00, 0x01, 0x69, 0x03, 0x99, 0x01, 0x9B, + 0x01, 0xFF, 0x01, 0xF4, 0x0D, 0x00, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0xF5, + 0x0D, 0x00, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0xF6, 0x0D, 0x00, 0x01, 0x58, + 0x03, 0x88, 0x01, 0x8A, 0x01, 0xFF, 0x01, 0xF5, 0x11, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF4, 0x0A, 0x00, 0x01, 0x05, 0x01, 0x55, 0x01, 0x10, + 0x04, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x80, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, + 0x0A, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xD0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xA0, 0x0A, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xF5, + 0x04, 0x00, 0x01, 0xBF, 0x01, 0xFF, 0x01, 0x40, 0x0A, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x20, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xFC, 0x0C, 0x00, 0x01, 0x9F, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, + 0x01, 0x37, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x0B, + 0x06, 0xFF, 0x01, 0x40, 0x0D, 0x00, 0x01, 0x8F, 0x04, 0xFF, 0x01, 0xC2, + 0x0E, 0x00, 0x01, 0x01, 0x01, 0x8C, 0x01, 0xEF, 0x01, 0xED, 0x01, 0x94, + 0xC1, 0x00, /* 62 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x04, 0x00, 0x01, 0x05, - 0x01, 0xae, 0x01, 0xff, 0x01, 0xed, 0x01, 0x83, 0x09, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x03, 0x00, 0x01, 0x03, 0x01, 0xdf, 0x04, 0xff, 0x01, 0xa1, - 0x08, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x6f, 0x05, 0xff, - 0x01, 0xfe, 0x01, 0x20, 0x07, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0x04, 0x02, 0xff, 0x01, 0xd6, 0x01, 0x32, 0x01, 0x48, 0x02, 0xff, - 0x01, 0xe0, 0x07, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x1c, 0x01, 0xff, 0x01, 0xf9, - 0x07, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x7f, 0x01, 0xff, - 0x01, 0xb0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, 0x01, 0x10, - 0x06, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0x20, 0x04, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x70, 0x06, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x02, 0x01, 0xff, 0x01, 0xfb, - 0x05, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xb0, 0x06, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xe0, 0x06, 0x00, 0x01, 0xef, 0x01, 0xfd, - 0x01, 0x99, 0x01, 0x9c, 0x01, 0xff, 0x01, 0xf3, 0x05, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xf1, 0x06, 0x00, 0x01, 0xef, 0x04, 0xff, 0x01, 0xf2, - 0x05, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf2, 0x06, 0x00, 0x01, 0xef, - 0x04, 0xff, 0x01, 0xf1, 0x05, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf3, - 0x06, 0x00, 0x01, 0xef, 0x01, 0xfc, 0x01, 0x88, 0x01, 0x8c, 0x01, 0xff, - 0x01, 0xf2, 0x05, 0x00, 0x01, 0x07, 0x01, 0xff, 0x01, 0xf2, 0x06, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf3, - 0x05, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xf1, 0x06, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x04, 0x01, 0xff, 0x01, 0xf6, 0x05, 0x00, - 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf0, 0x06, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x01, 0x00, 0x01, 0x01, 0x01, 0xff, 0x01, 0xfb, 0x05, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xb0, 0x06, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, - 0x01, 0xcf, 0x01, 0xff, 0x01, 0x20, 0x04, 0x00, 0x01, 0x7f, 0x01, 0xff, - 0x01, 0x70, 0x06, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xb0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xef, 0x01, 0xff, - 0x01, 0x10, 0x06, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x0e, - 0x01, 0xff, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x2d, 0x01, 0xff, 0x01, 0xf9, - 0x07, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x04, 0x02, 0xff, - 0x01, 0xd7, 0x01, 0x32, 0x01, 0x49, 0x02, 0xff, 0x01, 0xd0, 0x07, 0x00, - 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x6f, 0x05, 0xff, 0x01, 0xfd, - 0x01, 0x20, 0x07, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x03, 0x00, 0x01, 0x03, - 0x01, 0xdf, 0x04, 0xff, 0x01, 0xa1, 0x08, 0x00, 0x01, 0x11, 0x01, 0x10, - 0x04, 0x00, 0x01, 0x05, 0x01, 0xad, 0x01, 0xff, 0x01, 0xec, 0x01, 0x82, - 0xbc, 0x00, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x56, 0x01, 0x63, 0x04, 0x00, 0x01, 0x05, + 0x01, 0xAE, 0x01, 0xFF, 0x01, 0xED, 0x01, 0x83, 0x09, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x03, 0x00, 0x01, 0x03, 0x01, 0xDF, 0x04, 0xFF, 0x01, 0xA1, + 0x08, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x6F, 0x05, 0xFF, + 0x01, 0xFE, 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0x04, 0x02, 0xFF, 0x01, 0xD6, 0x01, 0x32, 0x01, 0x48, 0x02, 0xFF, + 0x01, 0xE0, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x1C, 0x01, 0xFF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0xB0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x10, + 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x20, 0x04, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x06, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x02, 0x01, 0xFF, 0x01, 0xFB, + 0x05, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB0, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xE0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xFD, + 0x01, 0x99, 0x01, 0x9C, 0x01, 0xFF, 0x01, 0xF3, 0x05, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0xEF, 0x04, 0xFF, 0x01, 0xF2, + 0x05, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x06, 0x00, 0x01, 0xEF, + 0x04, 0xFF, 0x01, 0xF1, 0x05, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x06, 0x00, 0x01, 0xEF, 0x01, 0xFC, 0x01, 0x88, 0x01, 0x8C, 0x01, 0xFF, + 0x01, 0xF2, 0x05, 0x00, 0x01, 0x07, 0x01, 0xFF, 0x01, 0xF2, 0x06, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x01, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF3, + 0x05, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xF1, 0x06, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x04, 0x01, 0xFF, 0x01, 0xF6, 0x05, 0x00, + 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x01, 0x00, 0x01, 0x01, 0x01, 0xFF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xB0, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, + 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x20, 0x04, 0x00, 0x01, 0x7F, 0x01, 0xFF, + 0x01, 0x70, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x01, 0x01, 0xEF, 0x01, 0xFF, + 0x01, 0x10, 0x06, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x0E, + 0x01, 0xFF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x2D, 0x01, 0xFF, 0x01, 0xF9, + 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x04, 0x02, 0xFF, + 0x01, 0xD7, 0x01, 0x32, 0x01, 0x49, 0x02, 0xFF, 0x01, 0xD0, 0x07, 0x00, + 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x6F, 0x05, 0xFF, 0x01, 0xFD, + 0x01, 0x20, 0x07, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x03, 0x00, 0x01, 0x03, + 0x01, 0xDF, 0x04, 0xFF, 0x01, 0xA1, 0x08, 0x00, 0x01, 0x11, 0x01, 0x10, + 0x04, 0x00, 0x01, 0x05, 0x01, 0xAD, 0x01, 0xFF, 0x01, 0xEC, 0x01, 0x82, + 0xBC, 0x00, /* 63 */ - 0xff, 0x00, 0x58, 0x00, 0x01, 0x14, 0x05, 0x66, 0x01, 0x60, 0x0c, 0x00, - 0x01, 0x2b, 0x06, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x02, 0x01, 0xef, - 0x06, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, 0x01, 0xeb, - 0x02, 0xaa, 0x01, 0xac, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x4f, - 0x01, 0xff, 0x01, 0xf5, 0x03, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x0b, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0x30, - 0x03, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x9f, - 0x01, 0xff, 0x01, 0x20, 0x03, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x0b, 0x00, 0x01, 0x6f, 0x01, 0xff, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xf8, - 0x01, 0x20, 0x02, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, - 0x01, 0x08, 0x07, 0xff, 0x01, 0xf2, 0x0c, 0x00, 0x01, 0x8f, 0x06, 0xff, - 0x01, 0xf2, 0x0c, 0x00, 0x01, 0x02, 0x01, 0x9d, 0x05, 0xff, 0x01, 0xf2, - 0x0d, 0x00, 0x01, 0x01, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x62, 0x01, 0x27, - 0x01, 0xff, 0x01, 0xf2, 0x0d, 0x00, 0x01, 0x0c, 0x01, 0xff, 0x01, 0xf7, - 0x01, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x0d, 0x00, 0x01, 0xcf, - 0x01, 0xff, 0x01, 0x80, 0x01, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x0c, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf9, 0x02, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x0c, 0x00, 0x01, 0xaf, 0x01, 0xff, 0x01, 0xa0, - 0x02, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x0b, 0x00, 0x01, 0x09, - 0x01, 0xff, 0x01, 0xfa, 0x03, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x0b, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x01, 0xb0, 0x03, 0x00, 0x01, 0x05, - 0x01, 0xff, 0x01, 0xf2, 0x0a, 0x00, 0x01, 0x08, 0x01, 0xff, 0x01, 0xfb, - 0x04, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, 0x0a, 0x00, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0xc0, 0x04, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf2, - 0x0a, 0x00, 0x02, 0x11, 0x06, 0x00, 0x01, 0x11, 0x01, 0x10, 0xbe, 0x00, + 0xFF, 0x00, 0x58, 0x00, 0x01, 0x14, 0x05, 0x66, 0x01, 0x60, 0x0C, 0x00, + 0x01, 0x2B, 0x06, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x02, 0x01, 0xEF, + 0x06, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0xEB, + 0x02, 0xAA, 0x01, 0xAC, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x4F, + 0x01, 0xFF, 0x01, 0xF5, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0x30, + 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x9F, + 0x01, 0xFF, 0x01, 0x20, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x6F, 0x01, 0xFF, 0x01, 0x70, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xF8, + 0x01, 0x20, 0x02, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, + 0x01, 0x08, 0x07, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x8F, 0x06, 0xFF, + 0x01, 0xF2, 0x0C, 0x00, 0x01, 0x02, 0x01, 0x9D, 0x05, 0xFF, 0x01, 0xF2, + 0x0D, 0x00, 0x01, 0x01, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x62, 0x01, 0x27, + 0x01, 0xFF, 0x01, 0xF2, 0x0D, 0x00, 0x01, 0x0C, 0x01, 0xFF, 0x01, 0xF7, + 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0D, 0x00, 0x01, 0xCF, + 0x01, 0xFF, 0x01, 0x80, 0x01, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0C, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF9, 0x02, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0C, 0x00, 0x01, 0xAF, 0x01, 0xFF, 0x01, 0xA0, + 0x02, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0B, 0x00, 0x01, 0x09, + 0x01, 0xFF, 0x01, 0xFA, 0x03, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0B, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x01, 0xB0, 0x03, 0x00, 0x01, 0x05, + 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x08, 0x01, 0xFF, 0x01, 0xFB, + 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, 0x0A, 0x00, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0xC0, 0x04, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x02, 0x11, 0x06, 0x00, 0x01, 0x11, 0x01, 0x10, 0xBE, 0x00, /* 64 */ - 0x2c, 0x00, 0x01, 0xbd, 0x01, 0xdd, 0x01, 0x60, 0x01, 0x05, 0x01, 0xdd, - 0x01, 0xdc, 0x0e, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x70, 0x01, 0x06, - 0x01, 0xff, 0x01, 0xfe, 0x0e, 0x00, 0x01, 0xdf, 0x01, 0xff, 0x01, 0x70, - 0x01, 0x06, 0x01, 0xff, 0x01, 0xfe, 0x0e, 0x00, 0x01, 0xdf, 0x01, 0xff, - 0x01, 0x70, 0x01, 0x06, 0x01, 0xff, 0x01, 0xfe, 0x0e, 0x00, 0x01, 0x67, + 0x2C, 0x00, 0x01, 0xBD, 0x01, 0xDD, 0x01, 0x60, 0x01, 0x05, 0x01, 0xDD, + 0x01, 0xDC, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, 0x01, 0x06, + 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, 0x01, 0x70, + 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0xDF, 0x01, 0xFF, + 0x01, 0x70, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xFE, 0x0E, 0x00, 0x01, 0x67, 0x01, 0x77, 0x01, 0x30, 0x01, 0x02, 0x01, 0x77, 0x01, 0x76, 0x33, 0x00, - 0x01, 0x1c, 0x0a, 0xcc, 0x09, 0x00, 0x01, 0x1f, 0x0a, 0xff, 0x09, 0x00, - 0x01, 0x1f, 0x0a, 0xff, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xe8, - 0x08, 0x88, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xfe, 0x07, 0xee, - 0x01, 0xe4, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf5, 0x09, 0x00, - 0x01, 0x1f, 0x09, 0xff, 0x01, 0xf5, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xe7, 0x07, 0x77, 0x01, 0x72, 0x09, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, - 0x01, 0x1f, 0x01, 0xff, 0x01, 0xc0, 0x11, 0x00, 0x01, 0x1f, 0x01, 0xff, - 0x01, 0xd4, 0x08, 0x44, 0x01, 0x30, 0x08, 0x00, 0x01, 0x1f, 0x0a, 0xff, - 0x01, 0xb0, 0x08, 0x00, 0x01, 0x1f, 0x0a, 0xff, 0x01, 0xb0, 0x08, 0x00, - 0x01, 0x1f, 0x0a, 0xff, 0x01, 0xb0, 0x08, 0x00, 0x01, 0x01, 0x0a, 0x11, - 0xbc, 0x00, + 0x01, 0x1C, 0x0A, 0xCC, 0x09, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xE8, + 0x08, 0x88, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xFE, 0x07, 0xEE, + 0x01, 0xE4, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, + 0x01, 0x1F, 0x09, 0xFF, 0x01, 0xF5, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xE7, 0x07, 0x77, 0x01, 0x72, 0x09, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, + 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xC0, 0x11, 0x00, 0x01, 0x1F, 0x01, 0xFF, + 0x01, 0xD4, 0x08, 0x44, 0x01, 0x30, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, + 0x01, 0xB0, 0x08, 0x00, 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, + 0x01, 0x1F, 0x0A, 0xFF, 0x01, 0xB0, 0x08, 0x00, 0x01, 0x01, 0x0A, 0x11, + 0xBC, 0x00, /* 65 */ - 0xb6, 0x00, 0x01, 0x01, 0x02, 0x55, 0x01, 0x00, 0x01, 0x04, 0x01, 0x55, - 0x01, 0x52, 0x0d, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0x00, 0x01, 0x0d, - 0x01, 0xff, 0x01, 0xf7, 0x0d, 0x00, 0x01, 0x05, 0x02, 0xff, 0x01, 0x00, - 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf7, 0x0d, 0x00, 0x01, 0x05, 0x02, 0xff, - 0x01, 0x00, 0x01, 0x0d, 0x01, 0xff, 0x01, 0xf7, 0x0d, 0x00, 0x01, 0x04, - 0x02, 0xee, 0x01, 0x00, 0x01, 0x0c, 0x01, 0xee, 0x01, 0xe6, 0x4a, 0x00, - 0x01, 0x17, 0x01, 0xbe, 0x01, 0xff, 0x01, 0xdb, 0x01, 0x60, 0x0e, 0x00, - 0x01, 0x07, 0x04, 0xff, 0x01, 0xfe, 0x01, 0x50, 0x0d, 0x00, 0x01, 0xbf, - 0x05, 0xff, 0x01, 0xf7, 0x0c, 0x00, 0x01, 0x0a, 0x02, 0xff, 0x01, 0x94, - 0x01, 0x23, 0x01, 0x6c, 0x02, 0xff, 0x01, 0x50, 0x0b, 0x00, 0x01, 0x6f, - 0x01, 0xff, 0x01, 0xd2, 0x03, 0x00, 0x01, 0x7f, 0x01, 0xff, 0x01, 0xd0, - 0x0b, 0x00, 0x01, 0xef, 0x01, 0xfe, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, - 0x01, 0xff, 0x01, 0xf6, 0x0a, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf6, - 0x05, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x0a, 0x00, 0x01, 0x09, 0x01, 0xff, - 0x01, 0xf0, 0x05, 0x00, 0x01, 0x8f, 0x01, 0xff, 0x0a, 0x00, 0x01, 0x0d, - 0x01, 0xff, 0x01, 0xb0, 0x05, 0x00, 0x01, 0x4f, 0x01, 0xff, 0x01, 0x30, - 0x09, 0x00, 0x01, 0x0f, 0x01, 0xff, 0x01, 0xb5, 0x05, 0x55, 0x01, 0x7f, - 0x01, 0xff, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1f, 0x09, 0xff, 0x01, 0x70, - 0x09, 0x00, 0x01, 0x2f, 0x09, 0xff, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1f, - 0x01, 0xff, 0x01, 0xb7, 0x07, 0x77, 0x01, 0x40, 0x09, 0x00, 0x01, 0x0f, - 0x01, 0xff, 0x01, 0x80, 0x11, 0x00, 0x01, 0x0e, 0x01, 0xff, 0x01, 0xb0, - 0x11, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xe0, 0x05, 0x00, 0x01, 0x37, - 0x01, 0x77, 0x0a, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf5, 0x05, 0x00, - 0x01, 0xdf, 0x01, 0xfd, 0x0b, 0x00, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, - 0x03, 0x00, 0x01, 0x06, 0x01, 0xff, 0x01, 0xf8, 0x0b, 0x00, 0x01, 0x8f, - 0x01, 0xff, 0x01, 0xc1, 0x03, 0x00, 0x01, 0x5f, 0x01, 0xff, 0x01, 0xf1, - 0x0b, 0x00, 0x01, 0x0c, 0x02, 0xff, 0x01, 0x94, 0x01, 0x23, 0x01, 0x6b, - 0x02, 0xff, 0x01, 0x60, 0x0b, 0x00, 0x01, 0x01, 0x01, 0xcf, 0x05, 0xff, - 0x01, 0xf8, 0x0d, 0x00, 0x01, 0x19, 0x04, 0xff, 0x01, 0xfe, 0x01, 0x50, - 0x0e, 0x00, 0x01, 0x27, 0x01, 0xce, 0x01, 0xff, 0x01, 0xda, 0x01, 0x50, - 0xc0, 0x00, + 0xB6, 0x00, 0x01, 0x01, 0x02, 0x55, 0x01, 0x00, 0x01, 0x04, 0x01, 0x55, + 0x01, 0x52, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, 0x01, 0x00, + 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x05, 0x02, 0xFF, + 0x01, 0x00, 0x01, 0x0D, 0x01, 0xFF, 0x01, 0xF7, 0x0D, 0x00, 0x01, 0x04, + 0x02, 0xEE, 0x01, 0x00, 0x01, 0x0C, 0x01, 0xEE, 0x01, 0xE6, 0x4A, 0x00, + 0x01, 0x17, 0x01, 0xBE, 0x01, 0xFF, 0x01, 0xDB, 0x01, 0x60, 0x0E, 0x00, + 0x01, 0x07, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, 0x0D, 0x00, 0x01, 0xBF, + 0x05, 0xFF, 0x01, 0xF7, 0x0C, 0x00, 0x01, 0x0A, 0x02, 0xFF, 0x01, 0x94, + 0x01, 0x23, 0x01, 0x6C, 0x02, 0xFF, 0x01, 0x50, 0x0B, 0x00, 0x01, 0x6F, + 0x01, 0xFF, 0x01, 0xD2, 0x03, 0x00, 0x01, 0x7F, 0x01, 0xFF, 0x01, 0xD0, + 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x01, 0x10, 0x03, 0x00, 0x01, 0x07, + 0x01, 0xFF, 0x01, 0xF6, 0x0A, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF6, + 0x05, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x0A, 0x00, 0x01, 0x09, 0x01, 0xFF, + 0x01, 0xF0, 0x05, 0x00, 0x01, 0x8F, 0x01, 0xFF, 0x0A, 0x00, 0x01, 0x0D, + 0x01, 0xFF, 0x01, 0xB0, 0x05, 0x00, 0x01, 0x4F, 0x01, 0xFF, 0x01, 0x30, + 0x09, 0x00, 0x01, 0x0F, 0x01, 0xFF, 0x01, 0xB5, 0x05, 0x55, 0x01, 0x7F, + 0x01, 0xFF, 0x01, 0x50, 0x09, 0x00, 0x01, 0x1F, 0x09, 0xFF, 0x01, 0x70, + 0x09, 0x00, 0x01, 0x2F, 0x09, 0xFF, 0x01, 0x70, 0x09, 0x00, 0x01, 0x1F, + 0x01, 0xFF, 0x01, 0xB7, 0x07, 0x77, 0x01, 0x40, 0x09, 0x00, 0x01, 0x0F, + 0x01, 0xFF, 0x01, 0x80, 0x11, 0x00, 0x01, 0x0E, 0x01, 0xFF, 0x01, 0xB0, + 0x11, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xE0, 0x05, 0x00, 0x01, 0x37, + 0x01, 0x77, 0x0A, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF5, 0x05, 0x00, + 0x01, 0xDF, 0x01, 0xFD, 0x0B, 0x00, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x03, 0x00, 0x01, 0x06, 0x01, 0xFF, 0x01, 0xF8, 0x0B, 0x00, 0x01, 0x8F, + 0x01, 0xFF, 0x01, 0xC1, 0x03, 0x00, 0x01, 0x5F, 0x01, 0xFF, 0x01, 0xF1, + 0x0B, 0x00, 0x01, 0x0C, 0x02, 0xFF, 0x01, 0x94, 0x01, 0x23, 0x01, 0x6B, + 0x02, 0xFF, 0x01, 0x60, 0x0B, 0x00, 0x01, 0x01, 0x01, 0xCF, 0x05, 0xFF, + 0x01, 0xF8, 0x0D, 0x00, 0x01, 0x19, 0x04, 0xFF, 0x01, 0xFE, 0x01, 0x50, + 0x0E, 0x00, 0x01, 0x27, 0x01, 0xCE, 0x01, 0xFF, 0x01, 0xDA, 0x01, 0x50, + 0xC0, 0x00, /* 48 */ - 0xff, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, - 0x01, 0xdf, 0x01, 0xff, 0x01, 0xc7, 0x01, 0x10, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf4, 0x01, 0x08, 0x04, 0xff, 0x01, 0xf6, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf4, 0x01, 0xaf, 0x05, 0xff, 0x01, 0x80, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xfc, 0x01, 0xff, 0x01, 0xf9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xdf, - 0x01, 0xff, 0x01, 0xf6, 0x0b, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xff, 0x01, 0xfe, 0x01, 0x10, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf3, 0x04, 0x00, 0x01, 0xbf, - 0x01, 0xff, 0x01, 0x70, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0x90, - 0x04, 0x00, 0x01, 0x1f, 0x01, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0a, 0x01, 0xff, 0x01, 0xf2, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfe, 0x05, 0x00, 0x01, 0x05, 0x01, 0xff, - 0x01, 0xf5, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x05, 0x00, 0x01, 0x02, - 0x01, 0xff, 0x01, 0xf7, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfa, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf8, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfa, 0x06, 0x00, - 0x01, 0xff, 0x01, 0xf9, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfb, 0x05, 0x00, - 0x01, 0x02, 0x01, 0xff, 0x01, 0xf8, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xfe, - 0x05, 0x00, 0x01, 0x05, 0x01, 0xff, 0x01, 0xf5, 0x0a, 0x00, 0x01, 0xef, - 0x01, 0xff, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0b, 0x01, 0xff, 0x01, 0xf2, - 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xa0, 0x04, 0x00, 0x01, 0x2f, - 0x01, 0xff, 0x01, 0xd0, 0x0a, 0x00, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf4, - 0x04, 0x00, 0x01, 0xcf, 0x01, 0xff, 0x01, 0x70, 0x0a, 0x00, 0x01, 0xef, - 0x02, 0xff, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1b, 0x01, 0xff, 0x01, 0xfe, - 0x01, 0x10, 0x0a, 0x00, 0x01, 0xef, 0x02, 0xff, 0x01, 0xfb, 0x01, 0x64, - 0x01, 0x58, 0x01, 0xef, 0x01, 0xff, 0x01, 0xf5, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0xaf, 0x05, 0xff, 0x01, 0x70, 0x0b, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x08, 0x04, 0xff, 0x01, 0xe4, 0x0c, 0x00, 0x01, 0xef, - 0x01, 0xf9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xce, 0x01, 0xed, 0x01, 0xa5, - 0x0d, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, - 0x12, 0x00, 0x01, 0xef, 0x01, 0xf9, 0x12, 0x00, 0x01, 0xde, 0x01, 0xe8, + 0xFF, 0x00, 0x56, 0x00, 0x01, 0x67, 0x01, 0x72, 0x01, 0x00, 0x01, 0x29, + 0x01, 0xDF, 0x01, 0xFF, 0x01, 0xC7, 0x01, 0x10, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xF6, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF4, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x80, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xFC, 0x01, 0xFF, 0x01, 0xF9, 0x01, 0x42, 0x01, 0x37, 0x01, 0xDF, + 0x01, 0xFF, 0x01, 0xF6, 0x0B, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x30, 0x02, 0x00, 0x01, 0x09, 0x01, 0xFF, 0x01, 0xFE, 0x01, 0x10, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF3, 0x04, 0x00, 0x01, 0xBF, + 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0x90, + 0x04, 0x00, 0x01, 0x1F, 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0A, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, + 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, 0x01, 0x02, + 0x01, 0xFF, 0x01, 0xF7, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFA, 0x06, 0x00, + 0x01, 0xFF, 0x01, 0xF9, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFB, 0x05, 0x00, + 0x01, 0x02, 0x01, 0xFF, 0x01, 0xF8, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFE, + 0x05, 0x00, 0x01, 0x05, 0x01, 0xFF, 0x01, 0xF5, 0x0A, 0x00, 0x01, 0xEF, + 0x01, 0xFF, 0x01, 0x30, 0x04, 0x00, 0x01, 0x0B, 0x01, 0xFF, 0x01, 0xF2, + 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xA0, 0x04, 0x00, 0x01, 0x2F, + 0x01, 0xFF, 0x01, 0xD0, 0x0A, 0x00, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF4, + 0x04, 0x00, 0x01, 0xCF, 0x01, 0xFF, 0x01, 0x70, 0x0A, 0x00, 0x01, 0xEF, + 0x02, 0xFF, 0x01, 0x40, 0x02, 0x00, 0x01, 0x1B, 0x01, 0xFF, 0x01, 0xFE, + 0x01, 0x10, 0x0A, 0x00, 0x01, 0xEF, 0x02, 0xFF, 0x01, 0xFB, 0x01, 0x64, + 0x01, 0x58, 0x01, 0xEF, 0x01, 0xFF, 0x01, 0xF5, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0xAF, 0x05, 0xFF, 0x01, 0x70, 0x0B, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x08, 0x04, 0xFF, 0x01, 0xE4, 0x0C, 0x00, 0x01, 0xEF, + 0x01, 0xF9, 0x01, 0x00, 0x01, 0x28, 0x01, 0xCE, 0x01, 0xED, 0x01, 0xA5, + 0x0D, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, + 0x12, 0x00, 0x01, 0xEF, 0x01, 0xF9, 0x12, 0x00, 0x01, 0xDE, 0x01, 0xE8, 0x25, 0x00, }; diff --git a/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp b/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp index cd07258dbf..bd7b9220eb 100644 --- a/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp +++ b/Marlin/src/lcd/tft/images/btn_rounded_42x39x4.cpp @@ -25,44 +25,44 @@ #if HAS_GRAPHICAL_TFT extern const uint8_t btn_rounded_42x39x4[819] = { - 0x87, 0x87, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x78, 0x78, - 0x87, 0x77, 0xab, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xb9, 0x77, 0x78, - 0x87, 0x8e, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd7, 0x68, - 0x87, 0xff, 0x84, 0x32, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x37, 0xff, 0x57, - 0x7b, 0xf6, 0x34, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x43, 0x6f, 0x95, - 0x7d, 0xc3, 0x45, 0x56, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x4d, 0xc4, - 0x7e, 0xc3, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x6d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7e, 0xc3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7d, 0xd3, - 0x7d, 0xd3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x7e, 0xc3, - 0x88, 0xfa, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0xcf, 0x64, - 0x86, 0xbf, 0xdb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xbb, 0xce, 0xfb, 0x34, - 0x87, 0x57, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0x74, 0x45, - 0x87, 0x75, 0x33, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x33, 0x34, 0x56, - 0x87, 0x77, 0x65, 0x54, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x55, 0x67, + 0x87, 0x87, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x78, 0x78, + 0x87, 0x77, 0xAB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xB9, 0x77, 0x78, + 0x87, 0x8E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xD7, 0x68, + 0x87, 0xFF, 0x84, 0x32, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x37, 0xFF, 0x57, + 0x7B, 0xF6, 0x34, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x43, 0x6F, 0x95, + 0x7D, 0xC3, 0x45, 0x56, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x4D, 0xC4, + 0x7E, 0xC3, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x6D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7E, 0xC3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7D, 0xD3, + 0x7D, 0xD3, 0x57, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x7E, 0xC3, + 0x88, 0xFA, 0x56, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0xCF, 0x64, + 0x86, 0xBF, 0xDB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xBB, 0xCE, 0xFB, 0x34, + 0x87, 0x57, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x74, 0x45, + 0x87, 0x75, 0x33, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x22, 0x33, 0x34, 0x56, + 0x87, 0x77, 0x65, 0x54, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x55, 0x67, 0x87, 0x87, 0x77, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x67, 0x78 }; diff --git a/Marlin/src/libs/softspi.h b/Marlin/src/libs/softspi.h index fb02de8653..cc36d658cd 100644 --- a/Marlin/src/libs/softspi.h +++ b/Marlin/src/libs/softspi.h @@ -25,11 +25,7 @@ // Based on https://github.com/niteris/ArduinoSoftSpi // -#include "../HAL/shared/Marduino.h" - -#ifndef FORCE_INLINE - #define FORCE_INLINE inline __attribute__((always_inline)) -#endif +#include "../HAL/shared/Marduino.h" // CORE_TEENSY #define nop __asm__ volatile ("nop") // NOP for timing diff --git a/docs/Serial.md b/docs/Serial.md index 30f6322a82..15c0480bb0 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -1,6 +1,6 @@ # Serial port architecture in Marlin -Marlin is targeting a plethora of different CPU architecture and platforms. Each of these platforms has its own serial interface. +Marlin is targeting a plethora of different CPU architectures and platforms. Each of these platforms has its own serial interface. While many provide a Arduino-like Serial class, it's not all of them, and the differences in the existing API create a very complex brain teaser for writing code that works more or less on each platform. Moreover, many platform have intrinsic needs about serial port (like forwarding the output on multiple serial port, providing a *serial-like* telnet server, mixing USB-based serial port with SD card emulation) that are difficult to handle cleanly in the other platform serial logic. From 301ee6c57aeafbe121f6896b532fada07c2b3477 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 May 2021 04:24:42 -0500 Subject: [PATCH 0041/2168] Add MKS_LCD12864B --- Marlin/Configuration.h | 3 ++- Marlin/src/inc/Conditionals_LCD.h | 4 ++-- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 7 +++++-- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 2 +- 5 files changed, 11 insertions(+), 7 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 7b03cfe68b..d6a7456ccf 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2260,7 +2260,8 @@ // MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout. // https://www.aliexpress.com/item/33018110072.html // -//#define MKS_LCD12864 +//#define MKS_LCD12864A +//#define MKS_LCD12864B // // FYSETC variant of the MINI12864 graphic controller with SD support diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a6df825ad9..d767000501 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,8 +26,8 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ -// MKS_LCD12864 is a variant of MKS_MINI_12864 -#if ENABLED(MKS_LCD12864) +// MKS_LCD12864A/B is a variant of MKS_MINI_12864 +#if EITHER(MKS_LCD12864A, MKS_LCD12864B) #define MKS_MINI_12864 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 208c875982..98b5c06914 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -270,7 +270,7 @@ #elif ENABLED(AZSMZ_12864) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 190 -#elif ENABLED(MKS_LCD12864) +#elif EITHER(MKS_LCD12864A, MKS_LCD12864B) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 205 #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bb4ec75681..0435ab5fb9 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -560,6 +560,8 @@ #error "MEATPACK is now enabled with MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2, etc." #elif defined(CUSTOM_USER_MENUS) #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." +#elif defined(MKS_LCD12864) + #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." #endif /** @@ -2359,7 +2361,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal + ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \ + (ENABLED(U8GLIB_SSD1306) && DISABLED(IS_U8GLIB_SSD1306)) \ + (ENABLED(MINIPANEL) && NONE(MKS_MINI_12864, ENDER2_STOCKDISPLAY)) \ - + (ENABLED(MKS_MINI_12864) && DISABLED(MKS_LCD12864)) \ + + (ENABLED(MKS_MINI_12864) && NONE(MKS_LCD12864A, MKS_LCD12864B)) \ + (ENABLED(EXTENSIBLE_UI) && DISABLED(IS_EXTUI)) \ + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ @@ -2390,7 +2392,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal + ENABLED(MAKRPANEL) \ + ENABLED(MALYAN_LCD) \ + ENABLED(NEXTION_TFT) \ - + ENABLED(MKS_LCD12864) \ + + ENABLED(MKS_LCD12864A) \ + + ENABLED(MKS_LCD12864B) \ + ENABLED(OLED_PANEL_TINYBOY2) \ + ENABLED(OVERLORD_OLED) \ + ENABLED(PANEL_ONE) \ diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 0426e80fd2..50a533cde2 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -222,7 +222,7 @@ #define LCD_BACKLIGHT_PIN -1 #else - #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and MKS_LCD12864 are currently supported on the BIGTREE_SKR_E3_DIP." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and MKS_LCD12864A/B are currently supported on the BIGTREE_SKR_E3_DIP." #endif #endif // HAS_WIRED_LCD From 1eb68e9f9a8d639fded043024d66d78bca16df05 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 May 2021 17:22:46 -0500 Subject: [PATCH 0042/2168] Echo LCD message to serial in kill --- Marlin/src/MarlinCore.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 209c9b59d0..d448b2febe 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -825,18 +825,19 @@ void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control - SERIAL_ERROR_MSG(STR_ERR_KILLED); + // Echo the LCD message to serial for extra context + if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P(lcd_error); } #if HAS_DISPLAY ui.kill_screen(lcd_error ?: GET_TEXT(MSG_KILLED), lcd_component ?: NUL_STR); #else - UNUSED(lcd_error); - UNUSED(lcd_component); + UNUSED(lcd_error); UNUSED(lcd_component); #endif - #if HAS_TFT_LVGL_UI - lv_draw_error_message(lcd_error); - #endif + TERN_(HAS_TFT_LVGL_UI, lv_draw_error_message(lcd_error)); + + // "Error:Printer halted. kill() called!" + SERIAL_ERROR_MSG(STR_ERR_KILLED); #ifdef ACTION_ON_KILL host_action_kill(); From 2470dc822fb1c43aa4fc8a90aa4b62487b1026ad Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 6 May 2021 00:55:43 +0000 Subject: [PATCH 0043/2168] [cron] Bump distribution date (2021-05-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 73edf3914a..da65fcac5b 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 "2021-05-05" + #define STRING_DISTRIBUTION_DATE "2021-05-06" #endif /** From bac72ff0cc5dd193ffac8cf04b36cfbccee4a73f Mon Sep 17 00:00:00 2001 From: ManuelMcLure Date: Wed, 5 May 2021 17:59:56 -0700 Subject: [PATCH 0044/2168] Only look for target disk during Upload (#21804) --- Marlin/src/HAL/LPC1768/upload_extra_script.py | 169 +++++++++--------- 1 file changed, 86 insertions(+), 83 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index 5967a9970f..fb3aaef7cd 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -20,101 +20,104 @@ def print_error(e): 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ %(e, env.get('PIOENV'))) -try: - # - # Find a disk for upload - # - upload_disk = 'Disk not found' - target_file_found = False - target_drive_found = False - if current_OS == 'Windows': +def before_upload(source, target, env): + try: # - # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' - # Windows - doesn't care about the disk's name, only cares about the drive letter - import subprocess,string - from ctypes import windll + # Find a disk for upload + # + upload_disk = 'Disk not found' + target_file_found = False + target_drive_found = False + if current_OS == 'Windows': + # + # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' + # Windows - doesn't care about the disk's name, only cares about the drive letter + import subprocess,string + from ctypes import windll - # getting list of drives - # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python - drives = [] - bitmask = windll.kernel32.GetLogicalDrives() - for letter in string.ascii_uppercase: - if bitmask & 1: - drives.append(letter) - bitmask >>= 1 + # getting list of drives + # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python + drives = [] + bitmask = windll.kernel32.GetLogicalDrives() + for letter in string.ascii_uppercase: + if bitmask & 1: + drives.append(letter) + bitmask >>= 1 - for drive in drives: - final_drive_name = drive + ':\\' - # print ('disc check: {}'.format(final_drive_name)) - try: - volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) - except Exception as e: - print ('error:{}'.format(e)) - continue - else: - if target_drive in volume_info and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = final_drive_name - if target_filename in volume_info: - if not target_file_found: + for drive in drives: + final_drive_name = drive + ':\\' + # print ('disc check: {}'.format(final_drive_name)) + try: + volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_drive in volume_info and not target_file_found: # set upload if not found target file yet + target_drive_found = True upload_disk = final_drive_name - target_file_found = True + if target_filename in volume_info: + if not target_file_found: + upload_disk = final_drive_name + target_file_found = True - elif current_OS == 'Linux': - # - # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' - # - drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) - if target_drive in drives: # If target drive is found, use it. - target_drive_found = True - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep - else: + elif current_OS == 'Linux': + # + # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) + if target_drive in drives: # If target drive is found, use it. + target_drive_found = True + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep + else: + for drive in drives: + try: + files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + except: + continue + else: + if target_filename in files: + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + target_file_found = True + break + # + # set upload_port to drive if found + # + + if target_file_found or target_drive_found: + env.Replace( + UPLOAD_FLAGS="-P$UPLOAD_PORT" + ) + + elif current_OS == 'Darwin': # MAC + # + # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir('/Volumes') # human readable names + if target_drive in drives and not target_file_found: # set upload if not found target file yet + target_drive_found = True + upload_disk = '/Volumes/' + target_drive + '/' for drive in drives: try: - files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected except: continue else: - if target_filename in files: - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + if target_filename in filenames: + if not target_file_found: + upload_disk = '/Volumes/' + drive + '/' target_file_found = True - break - # - # set upload_port to drive if found - # + # + # Set upload_port to drive if found + # if target_file_found or target_drive_found: - env.Replace( - UPLOAD_FLAGS="-P$UPLOAD_PORT" - ) + env.Replace(UPLOAD_PORT=upload_disk) + print('\nUpload disk: ', upload_disk, '\n') + else: + print_error('Autodetect Error') - elif current_OS == 'Darwin': # MAC - # - # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' - # - drives = os.listdir('/Volumes') # human readable names - if target_drive in drives and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = '/Volumes/' + target_drive + '/' - for drive in drives: - try: - filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected - except: - continue - else: - if target_filename in filenames: - if not target_file_found: - upload_disk = '/Volumes/' + drive + '/' - target_file_found = True + except Exception as e: + print_error(str(e)) - # - # Set upload_port to drive if found - # - if target_file_found or target_drive_found: - env.Replace(UPLOAD_PORT=upload_disk) - print('\nUpload disk: ', upload_disk, '\n') - else: - print_error('Autodetect Error') - -except Exception as e: - print_error(str(e)) +env.AddPreAction("upload", before_upload) From cbcc6ef9c4b9d0952b4ddc777bdf9d1986b5c70d Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 5 May 2021 18:11:54 -0700 Subject: [PATCH 0045/2168] Split up SKR V2 Rev A / B (#21805) --- Marlin/src/core/boards.h | 33 ++++++++++--------- Marlin/src/pins/pins.h | 10 ++++-- .../pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h | 29 ++++++++++++++++ .../pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h | 26 +++++++++++++++ ..._SKR_V2_0.h => pins_BTT_SKR_V2_0_common.h} | 2 -- 5 files changed, 80 insertions(+), 20 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h create mode 100644 Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h rename Marlin/src/pins/stm32f4/{pins_BTT_SKR_V2_0.h => pins_BTT_SKR_V2_0_common.h} (99%) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 614a3b6e9e..e32789e744 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -367,22 +367,23 @@ #define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6) #define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VGT6) #define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VGT6) -#define BOARD_BTT_SKR_V2_0 4211 // BigTreeTech SKR v2.0 (STM32F407VGT6) -#define BOARD_BTT_GTR_V1_0 4212 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_LERDGE_K 4213 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4214 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4215 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4216 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4217 // FYSETC S6 (STM32F446VET6) -#define BOARD_FYSETC_S6_V2_0 4218 // FYSETC S6 v2.0 (STM32F446VET6) -#define BOARD_FYSETC_SPIDER 4219 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4220 // FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4221 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4222 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4223 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_ANET_ET4 4224 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4225 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4226 // FYSETC Cheetah V2.0 +#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) +#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_LERDGE_K 4214 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4215 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4216 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4217 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4218 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4219 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4220 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4221 // FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4222 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4223 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4224 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_ANET_ET4 4225 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4226 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4227 // FYSETC Cheetah V2.0 // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index adcf29e5c6..70e6836a32 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -596,8 +596,10 @@ #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 #elif MB(BTT_E3_RRF) #include "stm32f4/pins_BTT_E3_RRF.h" // STM32F4 env:BIGTREE_E3_RRF -#elif MB(BTT_SKR_V2_0) - #include "stm32f4/pins_BTT_SKR_V2_0.h" // STM32F4 env:BIGTREE_SKR_2 +#elif MB(BTT_SKR_V2_0_REV_A) + #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 +#elif MB(BTT_SKR_V2_0_REV_B) + #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 #elif MB(LERDGE_K) #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive #elif MB(LERDGE_S) @@ -706,6 +708,7 @@ #define BOARD_RUMBA32_AUS3D -1019 #define BOARD_RAMPS_DAGOMA -1020 #define BOARD_RAMPS_LONGER3D_LK4PRO -1021 + #define BOARD_BTT_SKR_V2_0 -1022 #if MB(MKS_13) #error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration." @@ -753,6 +756,8 @@ #error "BOARD_RAMPS_DAGOMA is now BOARD_DAGOMA_F5. Please update your configuration." #elif MB(RAMPS_LONGER3D_LK4PRO) #error "BOARD_RAMPS_LONGER3D_LK4PRO is now BOARD_LONGER3D_LKx_PRO. Please update your configuration." + #elif MB(BTT_SKR_V2_0) + #error "BTT_SKR_V2_0 is now BTT_SKR_V2_0_REV_A or BTT_SKR_V2_0_REV_B. Please update your configuration." #else #error "Unknown MOTHERBOARD value set in Configuration.h" #endif @@ -779,6 +784,7 @@ #undef BOARD_RUMBA32_AUS3D #undef BOARD_RAMPS_DAGOMA #undef BOARD_RAMPS_LONGER3D_LK4PRO + #undef BOARD_BTT_SKR_V2_0 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h new file mode 100644 index 0000000000..be9580ee66 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_A.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define BOARD_INFO_NAME "BTT SKR V2 Rev.A" + +#error "SKR V2 Rev.A requires modification or drivers may be damaged. See https://bit.ly/3t5d9JQ for more information. Comment out this line to continue." +#define DISABLE_DRIVER_SAFE_POWER_PROTECT + +#include "pins_BTT_SKR_V2_0_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h new file mode 100644 index 0000000000..b83f41b26a --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_REV_B.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define BOARD_INFO_NAME "BTT SKR V2 Rev.B" + +#include "pins_BTT_SKR_V2_0_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h similarity index 99% rename from Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0.h rename to Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 11f954c400..b88e598e6f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -23,8 +23,6 @@ #include "env_validate.h" -#define BOARD_INFO_NAME "BTT SKR V2.0" - // Use one of these or SDCard-based Emulation will be used #if NO_EEPROM_SELECTED //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation From 857976b29fbb327ee26d8fe335f457b92a54501a Mon Sep 17 00:00:00 2001 From: hannesweisbach Date: Thu, 6 May 2021 03:13:21 +0200 Subject: [PATCH 0046/2168] Allow undefined [XYZ]_ENABLE_PIN (for sensitive pins) (#21801) --- Marlin/src/pins/sensitive_pins.h | 21 ++++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index b8be00bddd..1c811601ca 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -55,8 +55,13 @@ #else #define _X_MS3 #endif +#if PIN_EXISTS(X_ENABLE) + #define _X_ENABLE_PIN X_ENABLE_PIN, +#else + #define _X_ENABLE_PIN +#endif -#define _X_PINS X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS +#define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS #if PIN_EXISTS(Y_MIN) #define _Y_MIN Y_MIN_PIN, @@ -88,8 +93,13 @@ #else #define _Y_MS3 #endif +#if PIN_EXISTS(Y_ENABLE) + #define _Y_ENABLE_PIN Y_ENABLE_PIN, +#else + #define _Y_ENABLE_PIN +#endif -#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS +#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS #if PIN_EXISTS(Z_MIN) #define _Z_MIN Z_MIN_PIN, @@ -121,8 +131,13 @@ #else #define _Z_MS3 #endif +#if PIN_EXISTS(Z_ENABLE) + #define _Z_ENABLE_PIN Z_ENABLE_PIN, +#else + #define _Z_ENABLE_PIN +#endif -#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS +#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS // // Extruder Chip Select, Digital Micro-steps From b1cca43252aafe82ca593224bdedfbba0881b066 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 6 May 2021 18:43:16 +1200 Subject: [PATCH 0047/2168] Fix MMU2 compile with include (#21809) --- Marlin/src/lcd/menu/menu_mmu2.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index 7e71f00d25..af3d9232b2 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -24,6 +24,7 @@ #if BOTH(HAS_LCD_MENU, MMU2_MENUS) +#include "../../MarlinCore.h" #include "../../feature/mmu/mmu2.h" #include "menu_mmu2.h" #include "menu_item.h" From 28318f27d98caf256bca238ef712a9de5fc71da6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 01:51:19 -0500 Subject: [PATCH 0048/2168] Use SERIAL_ECHOLNPAIR for resend --- Marlin/src/gcode/queue.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 39ec338bbf..319ebe8a17 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -268,8 +268,7 @@ void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) { PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command #endif SERIAL_FLUSH(); - SERIAL_ECHOPGM(STR_RESEND); - SERIAL_ECHOLN(serial_state[serial_ind.index].last_N + 1); + SERIAL_ECHOLNPAIR(STR_RESEND, serial_state[serial_ind.index].last_N + 1); SERIAL_ECHOLNPGM(STR_OK); } From fb87b2d1adf667f63dde7d8d19058d5d75bc6aa2 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 6 May 2021 18:54:02 +1200 Subject: [PATCH 0049/2168] Simplify / undef extra endstops (#21808) Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_post.h | 18 +++-- Marlin/src/inc/SanityCheck.h | 103 ++++------------------------- Marlin/src/pins/pins_postprocess.h | 56 ++++++++++++++-- 3 files changed, 71 insertions(+), 106 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 98b5c06914..67a6ce86e1 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1983,15 +1983,6 @@ #if _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif -#if _HAS_STOP(X,STOP) - #define HAS_X_STOP 1 -#endif -#if _HAS_STOP(Y,STOP) - #define HAS_Y_STOP 1 -#endif -#if _HAS_STOP(Z,STOP) - #define HAS_Z_STOP 1 -#endif #if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif @@ -2022,10 +2013,17 @@ #if PIN_EXISTS(Z4_MAX) #define HAS_Z4_MAX 1 #endif -#if HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE) +#if BOTH(HAS_BED_PROBE, HAS_CUSTOM_PROBE_PIN) && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif +#undef IS_PROBE_PIN +#undef IS_X2_ENDSTOP +#undef IS_Y2_ENDSTOP +#undef IS_Z2_ENDSTOP +#undef IS_Z3_ENDSTOP +#undef IS_Z4_ENDSTOP + // // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 0435ab5fb9..6959e07f12 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2103,105 +2103,28 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal // Dual/multiple endstops requirements #if ENABLED(X_DUAL_ENDSTOPS) - #if !X2_USE_ENDSTOP - #error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS." - #elif X2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when X2_USE_ENDSTOP is _XMIN_." - #elif X2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when X2_USE_ENDSTOP is _XMAX_." - #elif X2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when X2_USE_ENDSTOP is _YMIN_." - #elif X2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when X2_USE_ENDSTOP is _YMAX_." - #elif X2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when X2_USE_ENDSTOP is _ZMIN_." - #elif X2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when X2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_X2_MIN && !HAS_X2_MAX - #error "X2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "X_DUAL_ENDSTOPS is not compatible with DELTA." + #elif !X2_USE_ENDSTOP + #error "X2_USE_ENDSTOP must be set with X_DUAL_ENDSTOPS." #endif #endif #if ENABLED(Y_DUAL_ENDSTOPS) - #if !Y2_USE_ENDSTOP - #error "You must set Y2_USE_ENDSTOP with Y_DUAL_ENDSTOPS." - #elif Y2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Y2_USE_ENDSTOP is _XMIN_." - #elif Y2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Y2_USE_ENDSTOP is _XMAX_." - #elif Y2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Y2_USE_ENDSTOP is _YMIN_." - #elif Y2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Y2_USE_ENDSTOP is _YMAX_." - #elif Y2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Y2_USE_ENDSTOP is _ZMIN_." - #elif Y2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Y2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Y2_MIN && !HAS_Y2_MAX - #error "Y2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "Y_DUAL_ENDSTOPS is not compatible with DELTA." + #elif !Y2_USE_ENDSTOP + #error "Y2_USE_ENDSTOP must be set with Y_DUAL_ENDSTOPS." #endif #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #if !Z2_USE_ENDSTOP - #error "You must set Z2_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 2." - #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_." - #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _XMAX_." - #elif Z2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _YMIN_." - #elif Z2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _YMAX_." - #elif Z2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _ZMIN_." - #elif Z2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z2_MIN && !HAS_Z2_MAX - #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #elif ENABLED(DELTA) + #if ENABLED(DELTA) #error "Z_MULTI_ENDSTOPS is not compatible with DELTA." - #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 - #if !Z3_USE_ENDSTOP - #error "You must set Z3_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 3." - #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_." - #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_." - #elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_." - #elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_." - #elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_." - #elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z3_MIN && !HAS_Z3_MAX - #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #endif - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - #if !Z4_USE_ENDSTOP - #error "You must set Z4_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 4." - #elif Z4_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) - #error "USE_XMIN_PLUG is required when Z4_USE_ENDSTOP is _XMIN_." - #elif Z4_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) - #error "USE_XMAX_PLUG is required when Z4_USE_ENDSTOP is _XMAX_." - #elif Z4_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG) - #error "USE_YMIN_PLUG is required when Z4_USE_ENDSTOP is _YMIN_." - #elif Z4_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG) - #error "USE_YMAX_PLUG is required when Z4_USE_ENDSTOP is _YMAX_." - #elif Z4_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG) - #error "USE_ZMIN_PLUG is required when Z4_USE_ENDSTOP is _ZMIN_." - #elif Z4_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG) - #error "USE_ZMAX_PLUG is required when Z4_USE_ENDSTOP is _ZMAX_." - #elif !HAS_Z4_MIN && !HAS_Z4_MAX - #error "Z4_USE_ENDSTOP has been assigned to a nonexistent endstop!" - #endif + #elif !Z2_USE_ENDSTOP + #error "Z2_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS." + #elif !Z3_USE_ENDSTOP && NUM_Z_STEPPER_DRIVERS >= 3 + #error "Z3_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and NUM_Z_STEPPER_DRIVERS >= 3." + #elif !Z4_USE_ENDSTOP && NUM_Z_STEPPER_DRIVERS >= 4 + #error "Z4_USE_ENDSTOP must be set with Z_MULTI_ENDSTOPS and NUM_Z_STEPPER_DRIVERS >= 4." #endif #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index d37dd4352a..d71b79ca95 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -441,40 +441,84 @@ // // Disable unused endstop / probe pins // +#define _STOP_IN_USE(N) (X2_USE_ENDSTOP == N || Y2_USE_ENDSTOP == N || Z2_USE_ENDSTOP == N || Z3_USE_ENDSTOP == N || Z4_USE_ENDSTOP == N) +#if _STOP_IN_USE(_XMAX_) + #define USE_XMAX_PLUG +#endif +#if _STOP_IN_USE(_YMAX_) + #define USE_YMAX_PLUG +#endif +#if _STOP_IN_USE(_ZMAX_) + #define USE_ZMAX_PLUG +#endif +#if _STOP_IN_USE(_XMIN_) + #define USE_XMIN_PLUG +#endif +#if _STOP_IN_USE(_YMIN_) + #define USE_YMIN_PLUG +#endif +#if _STOP_IN_USE(_ZMIN_) + #define USE_ZMIN_PLUG +#endif +#undef _STOP_IN_USE #if !HAS_CUSTOM_PROBE_PIN #undef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN -1 #endif - #if DISABLED(USE_XMAX_PLUG) #undef X_MAX_PIN #define X_MAX_PIN -1 #endif - #if DISABLED(USE_YMAX_PLUG) #undef Y_MAX_PIN #define Y_MAX_PIN -1 #endif - #if DISABLED(USE_ZMAX_PLUG) #undef Z_MAX_PIN #define Z_MAX_PIN -1 #endif - #if DISABLED(USE_XMIN_PLUG) #undef X_MIN_PIN #define X_MIN_PIN -1 #endif - #if DISABLED(USE_YMIN_PLUG) #undef Y_MIN_PIN #define Y_MIN_PIN -1 #endif - #if DISABLED(USE_ZMIN_PLUG) #undef Z_MIN_PIN #define Z_MIN_PIN -1 #endif +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR > 0 + #undef X2_MIN_PIN +#endif +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR < 0 + #undef X2_MAX_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR > 0 + #undef Y2_MIN_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR < 0 + #undef Y2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR > 0 + #undef Z2_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR < 0 + #undef Z2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR > 0 + #undef Z3_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR < 0 + #undef Z3_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR > 0 + #undef Z4_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR < 0 + #undef Z4_MAX_PIN +#endif #if HAS_FILAMENT_SENSOR #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN From 8d9021e8069c0550e9a31107adf44b9112b87471 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 04:17:59 -0500 Subject: [PATCH 0050/2168] Move ExtUI subfolders up a level (#21820) --- Marlin/src/MarlinCore.cpp | 8 +- Marlin/src/gcode/lcd/M995.cpp | 2 +- Marlin/src/gcode/sd/M24_M25.cpp | 2 +- .../anycubic_chiron/FileNavigator.cpp | 6 +- .../{lib => }/anycubic_chiron/FileNavigator.h | 4 +- .../extui/{lib => }/anycubic_chiron/Tunes.cpp | 6 +- .../extui/{lib => }/anycubic_chiron/Tunes.h | 2 +- .../chiron_extui.cpp} | 8 +- .../{lib => }/anycubic_chiron/chiron_tft.cpp | 12 +- .../{lib => }/anycubic_chiron/chiron_tft.h | 6 +- .../anycubic_chiron/chiron_tft_defs.h | 4 +- .../anycubic_extui.cpp} | 8 +- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 12 +- .../anycubic_i3mega/anycubic_i3mega_lcd.h | 4 +- .../lcd/extui/{lib => }/dgus/DGUSDisplay.cpp | 18 +- .../lcd/extui/{lib => }/dgus/DGUSDisplay.h | 8 +- .../lcd/extui/{lib => }/dgus/DGUSDisplayDef.h | 4 +- .../{lib => }/dgus/DGUSScreenHandler.cpp | 22 +-- .../extui/{lib => }/dgus/DGUSScreenHandler.h | 6 +- .../lcd/extui/{lib => }/dgus/DGUSVPVariable.h | 0 .../{dgus_lcd.cpp => dgus/dgus_extui.cpp} | 12 +- .../{lib => }/dgus/fysetc/DGUSDisplayDef.cpp | 12 +- .../{lib => }/dgus/fysetc/DGUSDisplayDef.h | 0 .../dgus/fysetc/DGUSScreenHandler.cpp | 22 +-- .../{lib => }/dgus/fysetc/DGUSScreenHandler.h | 2 +- .../{lib => }/dgus/hiprecy/DGUSDisplayDef.cpp | 12 +- .../{lib => }/dgus/hiprecy/DGUSDisplayDef.h | 0 .../dgus/hiprecy/DGUSScreenHandler.cpp | 22 +-- .../dgus/hiprecy/DGUSScreenHandler.h | 2 +- .../{lib => }/dgus/mks/DGUSDisplayDef.cpp | 14 +- .../extui/{lib => }/dgus/mks/DGUSDisplayDef.h | 0 .../{lib => }/dgus/mks/DGUSScreenHandler.cpp | 26 +-- .../{lib => }/dgus/mks/DGUSScreenHandler.h | 2 +- .../{lib => }/dgus/origin/DGUSDisplayDef.cpp | 14 +- .../{lib => }/dgus/origin/DGUSDisplayDef.h | 0 .../dgus/origin/DGUSScreenHandler.cpp | 22 +-- .../{lib => }/dgus/origin/DGUSScreenHandler.h | 2 +- .../src/lcd/extui/{ => example}/example.cpp | 4 +- .../archim2-flash/flash_storage.cpp | 0 .../archim2-flash/flash_storage.h | 0 .../archim2-flash/media_file_reader.cpp | 0 .../archim2-flash/media_file_reader.h | 6 +- .../{lib => }/ftdi_eve_touch_ui/compat.h | 6 +- .../{lib => }/ftdi_eve_touch_ui/config.h | 0 .../ftdi_eve_extui.cpp} | 108 +++++------- .../ftdi_eve_lib/LICENSE.txt | 0 .../ftdi_eve_touch_ui/ftdi_eve_lib/README.md | 0 .../ftdi_eve_lib/basic/boards.h | 0 .../ftdi_eve_lib/basic/commands.cpp | 0 .../ftdi_eve_lib/basic/commands.h | 0 .../ftdi_eve_lib/basic/constants.h | 0 .../ftdi_eve_lib/basic/display_list.h | 0 .../ftdi_eve_lib/basic/ftdi_basic.h | 0 .../ftdi_eve_lib/basic/registers_ft800.h | 0 .../ftdi_eve_lib/basic/registers_ft810.h | 0 .../ftdi_eve_lib/basic/resolutions.h | 0 .../ftdi_eve_lib/basic/spi.cpp | 0 .../ftdi_eve_lib/basic/spi.h | 0 .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 0 .../ftdi_eve_lib/extended/adjuster_widget.cpp | 0 .../ftdi_eve_lib/extended/adjuster_widget.h | 0 .../ftdi_eve_lib/extended/bitmap_info.h | 0 .../extended/circular_progress.cpp | 0 .../ftdi_eve_lib/extended/circular_progress.h | 0 .../extended/command_processor.cpp | 0 .../ftdi_eve_lib/extended/command_processor.h | 0 .../ftdi_eve_lib/extended/dl_cache.cpp | 0 .../ftdi_eve_lib/extended/dl_cache.h | 0 .../ftdi_eve_lib/extended/event_loop.cpp | 0 .../ftdi_eve_lib/extended/event_loop.h | 0 .../ftdi_eve_lib/extended/ftdi_extended.h | 0 .../ftdi_eve_lib/extended/grid_layout.h | 0 .../ftdi_eve_lib/extended/poly_ui.h | 0 .../ftdi_eve_lib/extended/polygon.h | 0 .../ftdi_eve_lib/extended/rgb_t.h | 0 .../ftdi_eve_lib/extended/screen_types.cpp | 0 .../ftdi_eve_lib/extended/screen_types.h | 0 .../ftdi_eve_lib/extended/sound_list.h | 0 .../ftdi_eve_lib/extended/sound_player.cpp | 0 .../ftdi_eve_lib/extended/sound_player.h | 0 .../ftdi_eve_lib/extended/text_box.cpp | 0 .../ftdi_eve_lib/extended/text_box.h | 0 .../ftdi_eve_lib/extended/text_ellipsis.cpp | 0 .../ftdi_eve_lib/extended/text_ellipsis.h | 0 .../ftdi_eve_lib/extended/tiny_timer.cpp | 0 .../ftdi_eve_lib/extended/tiny_timer.h | 0 .../ftdi_eve_lib/extended/unicode/README.txt | 0 .../extended/unicode/cyrillic_char_set.cpp | 0 .../extended/unicode/cyrillic_char_set.h | 0 .../unicode/cyrillic_char_set_bitmap_31.h | 0 .../extended/unicode/font_bitmaps.cpp | 0 .../extended/unicode/font_bitmaps.h | 0 .../cyrillic_char_set_bitmap_31.png | Bin .../cyrillic_char_set_bitmap_31.svg | 0 .../unicode/font_bitmaps/romfont_31.pbm | Bin .../unicode/font_bitmaps/romfont_31.png | Bin .../western_char_set_bitmap_31.png | Bin .../western_char_set_bitmap_31.svg | 0 .../extended/unicode/font_size_t.cpp | 0 .../extended/unicode/font_size_t.h | 0 .../extended/unicode/standard_char_set.cpp | 0 .../extended/unicode/standard_char_set.h | 0 .../ftdi_eve_lib/extended/unicode/unicode.cpp | 0 .../ftdi_eve_lib/extended/unicode/unicode.h | 0 .../extended/unicode/western_char_set.cpp | 0 .../extended/unicode/western_char_set.h | 0 .../unicode/western_char_set_bitmap_31.h | 0 .../ftdi_eve_lib/ftdi_eve_lib.h | 0 .../ftdi_eve_lib/scripts/bitmap2cpp.py | 0 .../ftdi_eve_lib/scripts/svg2cpp.py | 0 .../ftdi_eve_touch_ui/language/language.cpp | 2 +- .../ftdi_eve_touch_ui/language/language.h | 0 .../ftdi_eve_touch_ui/language/language_en.h | 0 .../ftdi_eve_touch_ui/pin_mappings.h | 2 +- .../screens/about_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/about_screen.h | 0 .../screens/advanced_settings_menu.cpp | 0 .../screens/advanced_settings_menu.h | 0 .../screens/alert_dialog_box.cpp | 0 .../screens/alert_dialog_box.h | 0 .../screens/backlash_compensation_screen.cpp | 0 .../screens/backlash_compensation_screen.h | 0 .../base_numeric_adjustment_screen.cpp | 0 .../screens/base_numeric_adjustment_screen.h | 0 .../ftdi_eve_touch_ui/screens/base_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/base_screen.h | 0 .../screens/bed_mesh_base.cpp | 0 .../ftdi_eve_touch_ui/screens/bed_mesh_base.h | 0 .../screens/bed_mesh_edit_screen.cpp | 0 .../screens/bed_mesh_edit_screen.h | 0 .../screens/bed_mesh_view_screen.cpp | 0 .../screens/bed_mesh_view_screen.h | 0 .../screens/bio_advanced_settings.cpp | 0 .../screens/bio_advanced_settings.h | 0 .../screens/bio_confirm_home_e.cpp | 0 .../screens/bio_confirm_home_e.h | 0 .../screens/bio_confirm_home_xyz.cpp | 0 .../screens/bio_confirm_home_xyz.h | 0 .../screens/bio_main_menu.cpp | 0 .../ftdi_eve_touch_ui/screens/bio_main_menu.h | 0 .../screens/bio_printer_ui_landscape.h | 0 .../screens/bio_printer_ui_portrait.h | 0 .../screens/bio_printing_dialog_box.cpp | 0 .../screens/bio_printing_dialog_box.h | 0 .../screens/bio_status_screen.cpp | 0 .../screens/bio_status_screen.h | 0 .../screens/bio_tune_menu.cpp | 0 .../ftdi_eve_touch_ui/screens/bio_tune_menu.h | 0 .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/boot_screen.h | 0 .../screens/case_light_screen.cpp | 0 .../screens/case_light_screen.h | 0 .../screens/change_filament_screen.cpp | 0 .../screens/change_filament_screen.h | 0 .../cocoa_press_advanced_settings_menu.cpp | 0 .../cocoa_press_advanced_settings_menu.h | 0 .../screens/cocoa_press_load_chocolate.cpp | 0 .../screens/cocoa_press_load_chocolate.h | 0 .../screens/cocoa_press_main_menu.cpp | 0 .../screens/cocoa_press_main_menu.h | 0 .../screens/cocoa_press_move_e_screen.cpp | 0 .../screens/cocoa_press_move_e_screen.h | 0 .../screens/cocoa_press_move_xyz_screen.cpp | 0 .../screens/cocoa_press_move_xyz_screen.h | 0 .../screens/cocoa_press_preheat_menu.cpp | 0 .../screens/cocoa_press_preheat_menu.h | 0 .../screens/cocoa_press_preheat_screen.cpp | 0 .../screens/cocoa_press_preheat_screen.h | 0 .../screens/cocoa_press_status_screen.cpp | 0 .../screens/cocoa_press_status_screen.h | 0 .../screens/cocoa_press_ui.h | 0 .../screens/cocoa_press_unload_cartridge.cpp | 0 .../screens/cocoa_press_unload_cartridge.h | 0 .../confirm_abort_print_dialog_box.cpp | 2 +- .../screens/confirm_abort_print_dialog_box.h | 0 .../confirm_auto_calibration_dialog_box.cpp | 0 .../confirm_auto_calibration_dialog_box.h | 0 .../confirm_erase_flash_dialog_box.cpp | 0 .../screens/confirm_erase_flash_dialog_box.h | 0 .../confirm_start_print_dialog_box.cpp | 0 .../screens/confirm_start_print_dialog_box.h | 0 .../confirm_user_request_alert_box.cpp | 0 .../screens/confirm_user_request_alert_box.h | 0 .../screens/custom_user_menus.cpp | 0 .../screens/custom_user_menus.h | 0 .../screens/default_acceleration_screen.cpp | 0 .../screens/default_acceleration_screen.h | 0 .../screens/developer_menu.cpp | 0 .../screens/developer_menu.h | 0 .../screens/dialog_box_base_class.cpp | 0 .../screens/dialog_box_base_class.h | 0 .../screens/display_tuning_screen.cpp | 0 .../screens/display_tuning_screen.h | 0 .../screens/endstop_state_screen.cpp | 0 .../screens/endstop_state_screen.h | 0 .../screens/feedrate_percent_screen.cpp | 0 .../screens/feedrate_percent_screen.h | 0 .../screens/filament_menu.cpp | 0 .../ftdi_eve_touch_ui/screens/filament_menu.h | 0 .../screens/filament_runout_screen.cpp | 0 .../screens/filament_runout_screen.h | 0 .../screens/files_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/files_screen.h | 0 .../screens/flow_percent_screen.cpp | 0 .../screens/flow_percent_screen.h | 0 .../screens/interface_settings_screen.cpp | 6 +- .../screens/interface_settings_screen.h | 0 .../screens/interface_sounds_screen.cpp | 0 .../screens/interface_sounds_screen.h | 0 .../ftdi_eve_touch_ui/screens/jerk_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/jerk_screen.h | 0 .../screens/junction_deviation_screen.cpp | 0 .../screens/junction_deviation_screen.h | 0 .../ftdi_eve_touch_ui/screens/kill_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/kill_screen.h | 0 .../screens/language_menu.cpp | 0 .../ftdi_eve_touch_ui/screens/language_menu.h | 0 .../screens/leveling_menu.cpp | 2 +- .../ftdi_eve_touch_ui/screens/leveling_menu.h | 0 .../screens/linear_advance_screen.cpp | 0 .../screens/linear_advance_screen.h | 0 .../ftdi_eve_touch_ui/screens/lock_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/lock_screen.h | 0 .../ftdi_eve_touch_ui/screens/main_menu.cpp | 0 .../ftdi_eve_touch_ui/screens/main_menu.h | 0 .../screens/max_acceleration_screen.cpp | 0 .../screens/max_acceleration_screen.h | 0 .../screens/max_velocity_screen.cpp | 0 .../screens/max_velocity_screen.h | 0 .../screens/media_player_screen.cpp | 0 .../screens/media_player_screen.h | 0 .../screens/move_axis_screen.cpp | 0 .../screens/move_axis_screen.h | 0 .../screens/nozzle_offsets_screen.cpp | 0 .../screens/nozzle_offsets_screen.h | 0 .../screens/nudge_nozzle_screen.cpp | 0 .../screens/nudge_nozzle_screen.h | 0 .../screens/restore_failsafe_dialog_box.cpp | 0 .../screens/restore_failsafe_dialog_box.h | 0 .../screens/save_settings_dialog_box.cpp | 0 .../screens/save_settings_dialog_box.h | 0 .../ftdi_eve_touch_ui/screens/screen_data.h | 0 .../ftdi_eve_touch_ui/screens/screens.cpp | 0 .../ftdi_eve_touch_ui/screens/screens.h | 2 + .../screens/spinner_dialog_box.cpp | 0 .../screens/spinner_dialog_box.h | 0 .../screens/statistics_screen.cpp | 0 .../screens/statistics_screen.h | 0 .../screens/status_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/status_screen.h | 0 .../stepper_bump_sensitivity_screen.cpp | 0 .../screens/stepper_bump_sensitivity_screen.h | 0 .../screens/stepper_current_screen.cpp | 0 .../screens/stepper_current_screen.h | 0 .../screens/steps_screen.cpp | 0 .../ftdi_eve_touch_ui/screens/steps_screen.h | 0 .../screens/stress_test_screen.cpp | 0 .../screens/stress_test_screen.h | 0 .../screens/string_format.cpp | 0 .../ftdi_eve_touch_ui/screens/string_format.h | 0 .../screens/temperature_screen.cpp | 0 .../screens/temperature_screen.h | 0 .../screens/touch_calibration_screen.cpp | 0 .../screens/touch_calibration_screen.h | 0 .../screens/touch_registers_screen.cpp | 0 .../screens/touch_registers_screen.h | 0 .../ftdi_eve_touch_ui/screens/tune_menu.cpp | 2 +- .../ftdi_eve_touch_ui/screens/tune_menu.h | 0 .../screens/widget_demo_screen.cpp | 0 .../screens/widget_demo_screen.h | 0 .../screens/z_offset_screen.cpp | 0 .../screens/z_offset_screen.h | 0 .../ftdi_eve_touch_ui/theme/bitmaps.h | 0 .../theme/bootscreen_logo_portrait.h | 0 .../ftdi_eve_touch_ui/theme/colors.h | 0 .../{lib => }/ftdi_eve_touch_ui/theme/fonts.h | 0 .../theme/marlin_bootscreen_landscape.h | 0 .../theme/marlin_bootscreen_portrait.h | 0 .../ftdi_eve_touch_ui/theme/sounds.cpp | 0 .../ftdi_eve_touch_ui/theme/sounds.h | 0 .../{lib => }/ftdi_eve_touch_ui/theme/theme.h | 0 .../{malyan_lcd.cpp => malyan/malyan.cpp} | 148 ++-------------- Marlin/src/lcd/extui/malyan/malyan.h | 53 ++++++ Marlin/src/lcd/extui/malyan/malyan_extui.cpp | 164 ++++++++++++++++++ .../{lib => }/mks_ui/SPIFlashStorage.cpp | 4 +- .../extui/{lib => }/mks_ui/SPIFlashStorage.h | 2 +- .../lcd/extui/{lib => }/mks_ui/SPI_TFT.cpp | 4 +- .../src/lcd/extui/{lib => }/mks_ui/SPI_TFT.h | 9 +- .../lcd/extui/{lib => }/mks_ui/draw_about.cpp | 4 +- .../lcd/extui/{lib => }/mks_ui/draw_about.h | 0 .../mks_ui/draw_acceleration_settings.cpp | 6 +- .../mks_ui/draw_acceleration_settings.h | 0 .../mks_ui/draw_advance_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_advance_settings.h | 0 .../draw_auto_level_offset_settings.cpp | 6 +- .../mks_ui/draw_auto_level_offset_settings.h | 0 .../{lib => }/mks_ui/draw_baby_stepping.cpp | 12 +- .../{lib => }/mks_ui/draw_baby_stepping.h | 0 .../{lib => }/mks_ui/draw_change_speed.cpp | 6 +- .../{lib => }/mks_ui/draw_change_speed.h | 0 .../{lib => }/mks_ui/draw_cloud_bind.cpp | 6 +- .../extui/{lib => }/mks_ui/draw_cloud_bind.h | 0 .../extui/{lib => }/mks_ui/draw_dialog.cpp | 22 +-- .../lcd/extui/{lib => }/mks_ui/draw_dialog.h | 0 .../{lib => }/mks_ui/draw_eeprom_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_eeprom_settings.h | 0 .../mks_ui/draw_encoder_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_encoder_settings.h | 0 .../{lib => }/mks_ui/draw_error_message.cpp | 4 +- .../{lib => }/mks_ui/draw_error_message.h | 0 .../extui/{lib => }/mks_ui/draw_extrusion.cpp | 8 +- .../extui/{lib => }/mks_ui/draw_extrusion.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_fan.cpp | 10 +- .../src/lcd/extui/{lib => }/mks_ui/draw_fan.h | 0 .../{lib => }/mks_ui/draw_filament_change.cpp | 12 +- .../{lib => }/mks_ui/draw_filament_change.h | 0 .../mks_ui/draw_filament_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_filament_settings.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_gcode.cpp | 4 +- .../lcd/extui/{lib => }/mks_ui/draw_gcode.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_home.cpp | 6 +- .../lcd/extui/{lib => }/mks_ui/draw_home.h | 0 .../draw_homing_sensitivity_settings.cpp | 10 +- .../mks_ui/draw_homing_sensitivity_settings.h | 0 .../{lib => }/mks_ui/draw_jerk_settings.cpp | 6 +- .../{lib => }/mks_ui/draw_jerk_settings.h | 0 .../extui/{lib => }/mks_ui/draw_keyboard.cpp | 6 +- .../extui/{lib => }/mks_ui/draw_keyboard.h | 0 .../extui/{lib => }/mks_ui/draw_language.cpp | 4 +- .../extui/{lib => }/mks_ui/draw_language.h | 0 .../{lib => }/mks_ui/draw_level_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_level_settings.h | 0 .../{lib => }/mks_ui/draw_machine_para.cpp | 4 +- .../{lib => }/mks_ui/draw_machine_para.h | 0 .../mks_ui/draw_machine_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_machine_settings.h | 0 .../{lib => }/mks_ui/draw_manuaLevel.cpp | 6 +- .../extui/{lib => }/mks_ui/draw_manuaLevel.h | 0 .../mks_ui/draw_max_feedrate_settings.cpp | 6 +- .../mks_ui/draw_max_feedrate_settings.h | 0 .../{lib => }/mks_ui/draw_media_select.cpp | 6 +- .../{lib => }/mks_ui/draw_media_select.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_more.cpp | 6 +- .../lcd/extui/{lib => }/mks_ui/draw_more.h | 0 .../{lib => }/mks_ui/draw_motor_settings.cpp | 4 +- .../{lib => }/mks_ui/draw_motor_settings.h | 0 .../{lib => }/mks_ui/draw_move_motor.cpp | 8 +- .../extui/{lib => }/mks_ui/draw_move_motor.h | 0 .../{lib => }/mks_ui/draw_number_key.cpp | 18 +- .../extui/{lib => }/mks_ui/draw_number_key.h | 0 .../extui/{lib => }/mks_ui/draw_operation.cpp | 10 +- .../extui/{lib => }/mks_ui/draw_operation.h | 0 .../{lib => }/mks_ui/draw_pause_message.cpp | 6 +- .../{lib => }/mks_ui/draw_pause_message.h | 0 .../{lib => }/mks_ui/draw_pause_position.cpp | 6 +- .../{lib => }/mks_ui/draw_pause_position.h | 0 .../extui/{lib => }/mks_ui/draw_preHeat.cpp | 6 +- .../lcd/extui/{lib => }/mks_ui/draw_preHeat.h | 0 .../{lib => }/mks_ui/draw_print_file.cpp | 6 +- .../extui/{lib => }/mks_ui/draw_print_file.h | 0 .../extui/{lib => }/mks_ui/draw_printing.cpp | 20 +-- .../extui/{lib => }/mks_ui/draw_printing.h | 0 .../{lib => }/mks_ui/draw_ready_print.cpp | 8 +- .../extui/{lib => }/mks_ui/draw_ready_print.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_set.cpp | 8 +- .../src/lcd/extui/{lib => }/mks_ui/draw_set.h | 0 .../{lib => }/mks_ui/draw_step_settings.cpp | 6 +- .../{lib => }/mks_ui/draw_step_settings.h | 0 .../mks_ui/draw_tmc_current_settings.cpp | 8 +- .../mks_ui/draw_tmc_current_settings.h | 0 .../mks_ui/draw_tmc_step_mode_settings.cpp | 10 +- .../mks_ui/draw_tmc_step_mode_settings.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_tool.cpp | 8 +- .../lcd/extui/{lib => }/mks_ui/draw_tool.h | 0 .../mks_ui/draw_touch_calibration.cpp | 6 +- .../{lib => }/mks_ui/draw_touch_calibration.h | 0 .../mks_ui/draw_tramming_pos_settings.cpp | 6 +- .../mks_ui/draw_tramming_pos_settings.h | 0 .../lcd/extui/{lib => }/mks_ui/draw_ui.cpp | 16 +- .../src/lcd/extui/{lib => }/mks_ui/draw_ui.h | 2 +- .../lcd/extui/{lib => }/mks_ui/draw_wifi.cpp | 2 +- .../lcd/extui/{lib => }/mks_ui/draw_wifi.h | 0 .../extui/{lib => }/mks_ui/draw_wifi_list.cpp | 2 +- .../extui/{lib => }/mks_ui/draw_wifi_list.h | 0 .../{lib => }/mks_ui/draw_wifi_settings.cpp | 2 +- .../{lib => }/mks_ui/draw_wifi_settings.h | 0 .../extui/{lib => }/mks_ui/draw_wifi_tips.cpp | 2 +- .../extui/{lib => }/mks_ui/draw_wifi_tips.h | 0 .../extui/{lib => }/mks_ui/gb2312_puhui16.cpp | 4 +- .../extui/{lib => }/mks_ui/irq_overrid.cpp | 4 +- .../{lib => }/mks_ui/mks_hardware_test.cpp | 8 +- .../{lib => }/mks_ui/mks_hardware_test.h | 0 .../extui/{lib => }/mks_ui/pic_manager.cpp | 8 +- .../lcd/extui/{lib => }/mks_ui/pic_manager.h | 4 +- .../{lib => }/mks_ui/printer_operation.cpp | 18 +- .../{lib => }/mks_ui/printer_operation.h | 0 .../extui/{lib => }/mks_ui/tft_Language_en.h | 0 .../extui/{lib => }/mks_ui/tft_Language_fr.h | 0 .../extui/{lib => }/mks_ui/tft_Language_it.h | 0 .../extui/{lib => }/mks_ui/tft_Language_ru.h | 0 .../{lib => }/mks_ui/tft_Language_s_cn.h | 0 .../extui/{lib => }/mks_ui/tft_Language_sp.h | 0 .../{lib => }/mks_ui/tft_Language_t_cn.h | 0 .../mks_ui/tft_lvgl_configuration.cpp | 14 +- .../{lib => }/mks_ui/tft_lvgl_configuration.h | 2 +- .../{lib => }/mks_ui/tft_multi_language.cpp | 2 +- .../{lib => }/mks_ui/tft_multi_language.h | 0 .../lcd/extui/{lib => }/mks_ui/wifiSerial.cpp | 4 +- .../lcd/extui/{lib => }/mks_ui/wifiSerial.h | 0 .../extui/{lib => }/mks_ui/wifi_module.cpp | 26 +-- .../lcd/extui/{lib => }/mks_ui/wifi_module.h | 2 +- .../extui/{lib => }/mks_ui/wifi_upload.cpp | 6 +- .../lcd/extui/{lib => }/mks_ui/wifi_upload.h | 0 .../extui/{lib => }/nextion/FileNavigator.cpp | 6 +- .../extui/{lib => }/nextion/FileNavigator.h | 4 +- .../nextion_extui.cpp} | 0 .../extui/{lib => }/nextion/nextion_tft.cpp | 16 +- .../lcd/extui/{lib => }/nextion/nextion_tft.h | 6 +- .../{lib => }/nextion/nextion_tft_defs.h | 4 +- Marlin/src/module/settings.cpp | 4 +- ini/features.ini | 24 +-- platformio.ini | 17 +- 422 files changed, 716 insertions(+), 653 deletions(-) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/FileNavigator.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/FileNavigator.h (96%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/Tunes.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/Tunes.h (99%) rename Marlin/src/lcd/extui/{anycubic_chiron_lcd.cpp => anycubic_chiron/chiron_extui.cpp} (96%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/chiron_tft.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/chiron_tft.h (96%) rename Marlin/src/lcd/extui/{lib => }/anycubic_chiron/chiron_tft_defs.h (98%) rename Marlin/src/lcd/extui/{anycubic_i3mega_lcd.cpp => anycubic_i3mega/anycubic_extui.cpp} (96%) rename Marlin/src/lcd/extui/{lib => }/anycubic_i3mega/anycubic_i3mega_lcd.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/anycubic_i3mega/anycubic_i3mega_lcd.h (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSDisplay.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSDisplay.h (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSDisplayDef.h (95%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSScreenHandler.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSScreenHandler.h (93%) rename Marlin/src/lcd/extui/{lib => }/dgus/DGUSVPVariable.h (100%) rename Marlin/src/lcd/extui/{dgus_lcd.cpp => dgus/dgus_extui.cpp} (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/fysetc/DGUSDisplayDef.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/dgus/fysetc/DGUSDisplayDef.h (100%) rename Marlin/src/lcd/extui/{lib => }/dgus/fysetc/DGUSScreenHandler.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/fysetc/DGUSScreenHandler.h (99%) rename Marlin/src/lcd/extui/{lib => }/dgus/hiprecy/DGUSDisplayDef.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/dgus/hiprecy/DGUSDisplayDef.h (100%) rename Marlin/src/lcd/extui/{lib => }/dgus/hiprecy/DGUSScreenHandler.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/hiprecy/DGUSScreenHandler.h (99%) rename Marlin/src/lcd/extui/{lib => }/dgus/mks/DGUSDisplayDef.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/dgus/mks/DGUSDisplayDef.h (100%) rename Marlin/src/lcd/extui/{lib => }/dgus/mks/DGUSScreenHandler.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/dgus/mks/DGUSScreenHandler.h (99%) rename Marlin/src/lcd/extui/{lib => }/dgus/origin/DGUSDisplayDef.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/dgus/origin/DGUSDisplayDef.h (100%) rename Marlin/src/lcd/extui/{lib => }/dgus/origin/DGUSScreenHandler.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/dgus/origin/DGUSScreenHandler.h (99%) rename Marlin/src/lcd/extui/{ => example}/example.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/archim2-flash/flash_storage.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h (93%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/compat.h (95%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/config.h (100%) rename Marlin/src/lcd/extui/{lib/ftdi_eve_touch_ui/marlin_events.cpp => ftdi_eve_touch_ui/ftdi_eve_extui.cpp} (57%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/README.md (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/language/language.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/language/language.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/language/language_en.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/pin_mappings.h (99%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/about_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/about_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/advanced_settings_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/alert_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/base_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/base_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_base.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_advanced_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_main_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_main_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_status_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_status_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/bio_tune_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/boot_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/boot_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/case_light_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/case_light_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/change_filament_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/change_filament_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_ui.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/custom_user_menus.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/custom_user_menus.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/default_acceleration_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/developer_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/developer_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/dialog_box_base_class.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/display_tuning_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/endstop_state_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/filament_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/filament_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/filament_runout_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/files_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/files_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/flow_percent_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/interface_settings_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/interface_sounds_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/jerk_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/jerk_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/junction_deviation_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/kill_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/kill_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/language_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/language_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/leveling_menu.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/leveling_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/linear_advance_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/lock_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/lock_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/main_menu.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/main_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/max_acceleration_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/max_velocity_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/media_player_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/media_player_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/move_axis_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/move_axis_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/screen_data.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/screens.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/screens.h (99%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/spinner_dialog_box.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/statistics_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/statistics_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/status_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/status_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stepper_current_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/steps_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/steps_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stress_test_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/stress_test_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/string_format.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/string_format.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/temperature_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/temperature_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/touch_calibration_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/touch_registers_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/tune_menu.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/tune_menu.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/widget_demo_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/z_offset_screen.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/screens/z_offset_screen.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/bitmaps.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/colors.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/fonts.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/sounds.cpp (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/sounds.h (100%) rename Marlin/src/lcd/extui/{lib => }/ftdi_eve_touch_ui/theme/theme.h (100%) rename Marlin/src/lcd/extui/{malyan_lcd.cpp => malyan/malyan.cpp} (75%) create mode 100644 Marlin/src/lcd/extui/malyan/malyan.h create mode 100644 Marlin/src/lcd/extui/malyan/malyan_extui.cpp rename Marlin/src/lcd/extui/{lib => }/mks_ui/SPIFlashStorage.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/SPIFlashStorage.h (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/SPI_TFT.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/SPI_TFT.h (90%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_about.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_about.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_acceleration_settings.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_acceleration_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_advance_settings.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_advance_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_auto_level_offset_settings.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_auto_level_offset_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_baby_stepping.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_baby_stepping.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_change_speed.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_change_speed.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_cloud_bind.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_cloud_bind.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_dialog.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_dialog.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_eeprom_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_eeprom_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_encoder_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_encoder_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_error_message.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_error_message.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_extrusion.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_extrusion.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_fan.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_fan.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_filament_change.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_filament_change.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_filament_settings.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_filament_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_gcode.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_gcode.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_home.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_home.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_homing_sensitivity_settings.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_homing_sensitivity_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_jerk_settings.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_jerk_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_keyboard.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_keyboard.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_language.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_language.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_level_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_level_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_machine_para.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_machine_para.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_machine_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_machine_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_manuaLevel.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_manuaLevel.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_max_feedrate_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_max_feedrate_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_media_select.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_media_select.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_more.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_more.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_motor_settings.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_motor_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_move_motor.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_move_motor.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_number_key.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_number_key.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_operation.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_operation.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_pause_message.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_pause_message.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_pause_position.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_pause_position.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_preHeat.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_preHeat.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_print_file.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_print_file.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_printing.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_printing.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_ready_print.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_ready_print.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_set.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_set.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_step_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_step_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tmc_current_settings.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tmc_current_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tmc_step_mode_settings.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tmc_step_mode_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tool.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tool.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_touch_calibration.cpp (96%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_touch_calibration.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tramming_pos_settings.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_tramming_pos_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_ui.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_ui.h (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_list.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_list.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_settings.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_settings.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_tips.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/draw_wifi_tips.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/gb2312_puhui16.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/irq_overrid.cpp (94%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/mks_hardware_test.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/mks_hardware_test.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/pic_manager.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/pic_manager.h (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/printer_operation.cpp (95%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/printer_operation.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_en.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_fr.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_it.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_ru.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_s_cn.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_sp.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_Language_t_cn.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_lvgl_configuration.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_lvgl_configuration.h (97%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_multi_language.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/tft_multi_language.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifiSerial.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifiSerial.h (100%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifi_module.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifi_module.h (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifi_upload.cpp (99%) rename Marlin/src/lcd/extui/{lib => }/mks_ui/wifi_upload.h (100%) rename Marlin/src/lcd/extui/{lib => }/nextion/FileNavigator.cpp (97%) rename Marlin/src/lcd/extui/{lib => }/nextion/FileNavigator.h (95%) rename Marlin/src/lcd/extui/{nextion_lcd.cpp => nextion/nextion_extui.cpp} (100%) rename Marlin/src/lcd/extui/{lib => }/nextion/nextion_tft.cpp (98%) rename Marlin/src/lcd/extui/{lib => }/nextion/nextion_tft.h (94%) rename Marlin/src/lcd/extui/{lib => }/nextion/nextion_tft_defs.h (97%) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index d448b2febe..053256b743 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -68,9 +68,9 @@ #endif #if HAS_TFT_LVGL_UI - #include "lcd/extui/lib/mks_ui/tft_lvgl_configuration.h" - #include "lcd/extui/lib/mks_ui/draw_ui.h" - #include "lcd/extui/lib/mks_ui/mks_hardware_test.h" + #include "lcd/extui/mks_ui/tft_lvgl_configuration.h" + #include "lcd/extui/mks_ui/draw_ui.h" + #include "lcd/extui/mks_ui/mks_hardware_test.h" #include #endif @@ -229,7 +229,7 @@ #endif #if ENABLED(DGUS_LCD_UI_MKS) - #include "lcd/extui/lib/dgus/DGUSScreenHandler.h" + #include "lcd/extui/dgus/DGUSScreenHandler.h" #endif #if HAS_DRIVER_SAFE_POWER_PROTECT diff --git a/Marlin/src/gcode/lcd/M995.cpp b/Marlin/src/gcode/lcd/M995.cpp index bc8dc35d4e..5e9fddbe8c 100644 --- a/Marlin/src/gcode/lcd/M995.cpp +++ b/Marlin/src/gcode/lcd/M995.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #if ENABLED(TFT_LVGL_UI) - #include "../../lcd/extui/lib/mks_ui/draw_touch_calibration.h" + #include "../../lcd/extui/mks_ui/draw_touch_calibration.h" #else #include "../../lcd/menu/menu.h" #endif diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 1c98791bce..89b166f908 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -42,7 +42,7 @@ #endif #if ENABLED(DGUS_LCD_UI_MKS) - #include "../../lcd/extui/lib/dgus/DGUSDisplayDef.h" + #include "../../lcd/extui/dgus/DGUSDisplayDef.h" #endif #include "../../MarlinCore.h" // for startOrResumeJob diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp rename to Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp index 01a871a542..9a7086bb51 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/extui/lib/FileNavigator.cpp + * lcd/extui/anycubic_chiron/FileNavigator.cpp * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -46,7 +46,7 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_CHIRON) #include "FileNavigator.h" @@ -55,7 +55,7 @@ using namespace ExtUI; #define DEBUG_OUT ACDEBUG(AC_FILE) -#include "../../../../core/debug_out.h" +#include "../../../core/debug_out.h" namespace Anycubic { diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h similarity index 96% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h rename to Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h index 0d55eb47b7..ca4283f54b 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/extui/lib/FileNavigator.h + * lcd/extui/anycubic_chiron/FileNavigator.h * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -30,7 +30,7 @@ */ #include "chiron_tft_defs.h" -#include "../../ui_api.h" +#include "../ui_api.h" using namespace ExtUI; diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp rename to Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp index f09c4db3f2..f228c471c9 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/extui/lib/Tunes.cpp + * lcd/extui/anycubic_chiron/Tunes.cpp * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -33,12 +33,12 @@ * See Tunes.h for note and tune definitions. * ***********************************************************************/ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_CHIRON) #include "Tunes.h" -#include "../../ui_api.h" +#include "../ui_api.h" namespace Anycubic { diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.h similarity index 99% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h rename to Marlin/src/lcd/extui/anycubic_chiron/Tunes.h index 1bafec43ad..bf2e92d03e 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/Tunes.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/extui/lib/Tunes.h + * lcd/extui/anycubic_chiron/Tunes.h * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] diff --git a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp similarity index 96% rename from Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp rename to Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 2ec5104310..0f6f8abe38 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -21,17 +21,17 @@ */ /** - * lcd/extui/anycubic_chiron_lcd.cpp + * lcd/extui/anycubic_chiron/chiron_extui.cpp * * Anycubic Chiron TFT support for Marlin */ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_CHIRON) -#include "ui_api.h" -#include "lib/anycubic_chiron/chiron_tft.h" +#include "../ui_api.h" +#include "chiron_tft.h" using namespace Anycubic; diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp rename to Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 5ad3895da0..14d394db72 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -21,14 +21,14 @@ */ /** - * lcd/extui/lib/chiron_tft.cpp + * lcd/extui/anycubic_chiron/chiron_tft.cpp * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] * (not affiliated with Anycubic, Ltd.) */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_CHIRON) @@ -36,10 +36,10 @@ #include "Tunes.h" #include "FileNavigator.h" -#include "../../../../gcode/queue.h" -#include "../../../../sd/cardreader.h" -#include "../../../../libs/numtostr.h" -#include "../../../../MarlinCore.h" +#include "../../../gcode/queue.h" +#include "../../../sd/cardreader.h" +#include "../../../libs/numtostr.h" +#include "../../../MarlinCore.h" namespace Anycubic { diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h similarity index 96% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h rename to Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h index aeef12afc6..7eb0049993 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/extui/lib/chiron_tft.h + * lcd/extui/anycubic_chiron/chiron_tft.h * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -30,8 +30,8 @@ */ #include "chiron_tft_defs.h" -#include "../../../../inc/MarlinConfigPre.h" -#include "../../ui_api.h" +#include "../../../inc/MarlinConfigPre.h" +#include "../ui_api.h" #if NONE(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) #define AUTO_DETECT_CHIRON_TFT 1 diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h similarity index 98% rename from Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h rename to Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h index 83e64e7973..70ac1490df 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h @@ -21,7 +21,7 @@ */ /** - * lcd/extui/lib/chiron_defs.h + * lcd/extui/anycubic_chiron/chiron_defs.h * * Extensible_UI implementation for Anycubic Chiron * Written By Nick Wells, 2020 [https://github.com/SwiftNick] @@ -29,7 +29,7 @@ */ #pragma once -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" //#define ACDEBUGLEVEL 4 #if ACDEBUGLEVEL diff --git a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp similarity index 96% rename from Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp rename to Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index 9055e7b430..33e7e84a81 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -21,15 +21,15 @@ */ /** - * anycubic_i3mega_lcd.cpp + * lcd/extui/anycubic_i3mega/anycubic_extui.cpp */ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_I3MEGA) -#include "lib/anycubic_i3mega/anycubic_i3mega_lcd.h" -#include "ui_api.h" +#include "anycubic_i3mega_lcd.h" +#include "../ui_api.h" #include // for the ::tone() call diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp rename to Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index f3a9472c20..3277ad4fb4 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -19,17 +19,17 @@ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(ANYCUBIC_LCD_I3MEGA) #include "anycubic_i3mega_lcd.h" -#include "../../ui_api.h" +#include "../ui_api.h" -#include "../../../../libs/numtostr.h" -#include "../../../../module/motion.h" // for quickstop_stepper, A20 read printing speed, feedrate_percentage -#include "../../../../MarlinCore.h" // for disable_steppers -#include "../../../../inc/MarlinConfig.h" +#include "../../../libs/numtostr.h" +#include "../../../module/motion.h" // for quickstop_stepper, A20 read printing speed, feedrate_percentage +#include "../../../MarlinCore.h" // for disable_steppers +#include "../../../inc/MarlinConfig.h" // command sending macro's with debugging capability #define SEND_PGM(x) send_P(PSTR(x)) diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h similarity index 96% rename from Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h rename to Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h index e34cb2fe69..fa62b545dc 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h @@ -20,8 +20,8 @@ */ #pragma once -#include "../../../../inc/MarlinConfigPre.h" -#include "../../../../sd/SdFatConfig.h" // for the FILENAME_LENGTH macro +#include "../../../inc/MarlinConfigPre.h" +#include "../../../sd/SdFatConfig.h" // for the FILENAME_LENGTH macro #define TFTBUFSIZE 4 #define TFT_MAX_CMD_SIZE 96 diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp rename to Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 2f33768655..c2390d63a6 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -20,7 +20,7 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_DGUS_LCD @@ -28,16 +28,16 @@ #warning "More than 2 hotends not implemented on DGUS Display UI." #endif -#include "../../ui_api.h" +#include "../ui_api.h" -#include "../../../../MarlinCore.h" -#include "../../../../module/motion.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/planner.h" -#include "../../../../libs/duration_t.h" -#include "../../../../module/printcounter.h" +#include "../../../MarlinCore.h" +#include "../../../module/motion.h" +#include "../../../gcode/queue.h" +#include "../../../module/planner.h" +#include "../../../libs/duration_t.h" +#include "../../../module/printcounter.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #include "DGUSDisplay.h" diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h similarity index 96% rename from Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h rename to Marlin/src/lcd/extui/dgus/DGUSDisplay.h index f33935a269..f1071f6b0a 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -22,15 +22,15 @@ #pragma once /** - * lcd/extui/lib/dgus/DGUSDisplay.h + * lcd/extui/dgus/DGUSDisplay.h */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #include // size_t #if HAS_BED_PROBE - #include "../../../../module/probe.h" + #include "../../../module/probe.h" #endif #include "DGUSVPVariable.h" @@ -38,7 +38,7 @@ enum DGUSLCD_Screens : uint8_t; //#define DEBUG_DGUSLCD #define DEBUG_OUT ENABLED(DEBUG_DGUSLCD) -#include "../../../../core/debug_out.h" +#include "../../../core/debug_out.h" typedef enum : uint8_t { DGUS_IDLE, //< waiting for DGUS_HEADER1. diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h similarity index 95% rename from Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h rename to Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h index 0b68943593..9cbcf0dd7b 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplayDef.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/extui/lib/dgus/DGUSDisplayDef.h + * lcd/extui/dgus/DGUSDisplayDef.h * Defines the interaction between Marlin and the display firmware */ @@ -44,7 +44,7 @@ extern const struct VPMapping VPMap[]; // List of VPs handled by Marlin / The Display. extern const struct DGUS_VP_Variable ListOfVP[]; -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(DGUS_LCD_UI_ORIGIN) #include "origin/DGUSDisplayDef.h" diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp rename to Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 067ea482c7..5b3bb9e0f3 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -20,24 +20,24 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_DGUS_LCD #include "DGUSScreenHandler.h" -#include "../../../../MarlinCore.h" -#include "../../../../gcode/queue.h" -#include "../../../../libs/duration_t.h" -#include "../../../../module/settings.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" -#include "../../../../module/printcounter.h" -#include "../../../../sd/cardreader.h" +#include "../../../MarlinCore.h" +#include "../../../gcode/queue.h" +#include "../../../libs/duration_t.h" +#include "../../../module/settings.h" +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../module/printcounter.h" +#include "../../../sd/cardreader.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif DGUSScreenHandler ScreenHandler; diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h similarity index 93% rename from Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h rename to Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h index 21e25b3b88..9aeb5b73b1 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h @@ -22,12 +22,12 @@ #pragma once /** - * lcd/extui/lib/dgus/DGUSScreenHandler.h + * lcd/extui/dgus/DGUSScreenHandler.h */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" -#include "../../ui_api.h" +#include "../ui_api.h" #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h b/Marlin/src/lcd/extui/dgus/DGUSVPVariable.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h rename to Marlin/src/lcd/extui/dgus/DGUSVPVariable.h diff --git a/Marlin/src/lcd/extui/dgus_lcd.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp similarity index 96% rename from Marlin/src/lcd/extui/dgus_lcd.cpp rename to Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 4776ceb154..b389294175 100644 --- a/Marlin/src/lcd/extui/dgus_lcd.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -21,17 +21,17 @@ */ /** - * lcd/extui/dgus_lcd.cpp + * lcd/extui/dgus/dgus_extui.cpp */ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_DGUS_LCD -#include "ui_api.h" -#include "lib/dgus/DGUSDisplay.h" -#include "lib/dgus/DGUSDisplayDef.h" -#include "lib/dgus/DGUSScreenHandler.h" +#include "../ui_api.h" +#include "DGUSDisplay.h" +#include "DGUSDisplayDef.h" +#include "DGUSScreenHandler.h" namespace ExtUI { diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp rename to Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index ee0a1c749f..5e164d289e 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -22,7 +22,7 @@ /* DGUS VPs changed by George Fu in 2019 for Marlin */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_FYSETC) @@ -30,12 +30,12 @@ #include "../DGUSDisplay.h" #include "../DGUSScreenHandler.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 "../../../../marlinui.h" +#include "../../ui_api.h" +#include "../../../marlinui.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 10; diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h rename to Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.cpp rename to Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 26dafeaaab..8b97003f6f 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -20,24 +20,24 @@ * */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_FYSETC) #include "../DGUSScreenHandler.h" -#include "../../../../../MarlinCore.h" -#include "../../../../../gcode/queue.h" -#include "../../../../../libs/duration_t.h" -#include "../../../../../module/settings.h" -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" -#include "../../../../../module/printcounter.h" -#include "../../../../../sd/cardreader.h" +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.h rename to Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index 24965597a5..d8e25a8f77 100644 --- a/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -25,7 +25,7 @@ #include "../DGUSVPVariable.h" #include "../DGUSDisplayDef.h" -#include "../../../../../inc/MarlinConfig.h" +#include "../../../../inc/MarlinConfig.h" enum DGUSLCD_Screens : uint8_t; diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp rename to Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index d3c4510fb3..a9fa407dd3 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -22,7 +22,7 @@ /* DGUS VPs changed by George Fu in 2019 for Marlin */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_HIPRECY) @@ -30,12 +30,12 @@ #include "../DGUSDisplay.h" #include "../DGUSScreenHandler.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 "../../../../marlinui.h" +#include "../../ui_api.h" +#include "../../../marlinui.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 10; diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h rename to Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.cpp rename to Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index f91c2737e0..f3729d1253 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -20,24 +20,24 @@ * */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_HYPRECY) #include "../DGUSScreenHandler.h" -#include "../../../../../MarlinCore.h" -#include "../../../../../gcode/queue.h" -#include "../../../../../libs/duration_t.h" -#include "../../../../../module/settings.h" -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" -#include "../../../../../module/printcounter.h" -#include "../../../../../sd/cardreader.h" +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.h rename to Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index 24965597a5..d8e25a8f77 100644 --- a/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -25,7 +25,7 @@ #include "../DGUSVPVariable.h" #include "../DGUSDisplayDef.h" -#include "../../../../../inc/MarlinConfig.h" +#include "../../../../inc/MarlinConfig.h" enum DGUSLCD_Screens : uint8_t; diff --git a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/mks/DGUSDisplayDef.cpp rename to Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 667442b31c..7d98b64991 100644 --- a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -20,7 +20,7 @@ * */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_MKS) @@ -28,15 +28,15 @@ #include "../DGUSDisplay.h" #include "../DGUSScreenHandler.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 "../../../../marlinui.h" +#include "../../ui_api.h" +#include "../../../marlinui.h" #if ENABLED(HAS_STEALTHCHOP) - #include "../../../../../module/stepper/trinamic.h" + #include "../../../../module/stepper/trinamic.h" #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) diff --git a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/mks/DGUSDisplayDef.h rename to Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp rename to Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 2abec905cb..d31a1dcacd 100644 --- a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -20,31 +20,31 @@ * */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_MKS) #include "../DGUSScreenHandler.h" -#include "../../../../../inc/MarlinConfig.h" +#include "../../../../inc/MarlinConfig.h" -#include "../../../../../MarlinCore.h" -#include "../../../../../module/settings.h" -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" -#include "../../../../../module/printcounter.h" +#include "../../../../MarlinCore.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" -#include "../../../../../gcode/gcode.h" +#include "../../../../gcode/gcode.h" #if ENABLED(HAS_STEALTHCHOP) - #include "../../../../../module/stepper/trinamic.h" - #include "../../../../../module/stepper/indirection.h" + #include "../../../../module/stepper/trinamic.h" + #include "../../../../module/stepper/indirection.h" #endif -#include "../../../../../module/probe.h" +#include "../../../../module/probe.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.h rename to Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index ef67635f8d..6713debd83 100644 --- a/Marlin/src/lcd/extui/lib/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -25,7 +25,7 @@ #include "../DGUSVPVariable.h" #include "../DGUSDisplayDef.h" -#include "../../../../../inc/MarlinConfig.h" +#include "../../../../inc/MarlinConfig.h" enum DGUSLCD_Screens : uint8_t; diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp rename to Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index e232bf9b96..1c2944bb4f 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -21,10 +21,10 @@ */ /** - * lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp + * lcd/extui/dgus/origin/DGUSDisplayDef.cpp */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_ORIGIN) @@ -32,12 +32,12 @@ #include "../DGUSDisplay.h" #include "../DGUSScreenHandler.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 "../../../../marlinui.h" -#include "../../../ui_api.h" +#include "../../../marlinui.h" +#include "../../ui_api.h" #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 10; diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h rename to Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp rename to Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index 73e2f4f6f0..f05dfc6f70 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -20,24 +20,24 @@ * */ -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_ORIGIN) #include "../DGUSScreenHandler.h" -#include "../../../../../MarlinCore.h" -#include "../../../../../gcode/queue.h" -#include "../../../../../libs/duration_t.h" -#include "../../../../../module/settings.h" -#include "../../../../../module/temperature.h" -#include "../../../../../module/motion.h" -#include "../../../../../module/planner.h" -#include "../../../../../module/printcounter.h" -#include "../../../../../sd/cardreader.h" +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../libs/duration_t.h" +#include "../../../../module/settings.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" +#include "../../../../module/printcounter.h" +#include "../../../../sd/cardreader.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h similarity index 99% rename from Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.h rename to Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index 24965597a5..d8e25a8f77 100644 --- a/Marlin/src/lcd/extui/lib/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -25,7 +25,7 @@ #include "../DGUSVPVariable.h" #include "../DGUSDisplayDef.h" -#include "../../../../../inc/MarlinConfig.h" +#include "../../../../inc/MarlinConfig.h" enum DGUSLCD_Screens : uint8_t; diff --git a/Marlin/src/lcd/extui/example.cpp b/Marlin/src/lcd/extui/example/example.cpp similarity index 98% rename from Marlin/src/lcd/extui/example.cpp rename to Marlin/src/lcd/extui/example/example.cpp index 8f00d26fd8..959d750872 100644 --- a/Marlin/src/lcd/extui/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -19,11 +19,11 @@ * location: . * ****************************************************************************/ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(EXTUI_EXAMPLE, EXTENSIBLE_UI) -#include "ui_api.h" +#include "../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/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h similarity index 93% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h index 3528dd9e15..249c57b9c6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h @@ -22,11 +22,11 @@ #pragma once -#include "../../../../../inc/MarlinConfigPre.h" +#include "../../../../inc/MarlinConfigPre.h" #if ENABLED(SDSUPPORT) - #include "../../../../../sd/SdFile.h" - #include "../../../../../sd/cardreader.h" + #include "../../../../sd/SdFile.h" + #include "../../../../sd/cardreader.h" #endif class MediaFileReader { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h similarity index 95% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h index c01d45ed7c..dd25af1e74 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h @@ -27,11 +27,11 @@ */ #ifdef __has_include - #if __has_include("../../ui_api.h") - #include "../../ui_api.h" + #if __has_include("../ui_api.h") + #include "../ui_api.h" #endif #else - #include "../../ui_api.h" + #include "../ui_api.h" #endif #ifdef __MARLIN_FIRMWARE__ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp similarity index 57% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index b3a9e42766..08faaa3b6a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -1,26 +1,30 @@ -/********************* - * marlin_events.cpp * - *********************/ +/** + * 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 . + * + */ -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * * - * 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. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ +/** + * lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp + */ -#include "compat.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(TOUCH_UI_FTDI_EVE) @@ -30,13 +34,9 @@ namespace ExtUI { using namespace Theme; using namespace FTDI; - void onStartup() { - EventLoop::setup(); - } + void onStartup() { EventLoop::setup(); } - void onIdle() { - EventLoop::loop(); - } + void onIdle() { EventLoop::loop(); } void onPrinterKilled(PGM_P const error, PGM_P const component) { char str[strlen_P(error) + strlen_P(component) + 3]; @@ -71,24 +71,17 @@ namespace ExtUI { AlertDialogBox::showError(F("Unable to read media.")); } - void onStatusChanged(const char *lcd_msg) { - StatusScreen::setStatusMessage(lcd_msg); - } - - void onStatusChanged(progmem_str lcd_msg) { - StatusScreen::setStatusMessage(lcd_msg); - } + void onStatusChanged(const char *lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } + void onStatusChanged(progmem_str lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } void onPrintTimerStarted() { InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_STARTED); } - void onPrintTimerStopped() { InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FINISHED); } void onPrintTimerPaused() {} - void onPrintFinished() {} void onFilamentRunout(const extruder_t extruder) { @@ -101,38 +94,23 @@ namespace ExtUI { void onHomingStart() {} void onHomingComplete() {} - void onFactoryReset() { - InterfaceSettingsScreen::defaultSettings(); - } - - void onStoreSettings(char *buff) { - InterfaceSettingsScreen::saveSettings(buff); - } - - void onLoadSettings(const char *buff) { - InterfaceSettingsScreen::loadSettings(buff); - } - - void onPostprocessSettings() { - // Called after loading or resetting stored settings - } + void onFactoryReset() { InterfaceSettingsScreen::defaultSettings(); } + void onStoreSettings(char *buff) { InterfaceSettingsScreen::saveSettings(buff); } + void onLoadSettings(const char *buff) { InterfaceSettingsScreen::loadSettings(buff); } + void onPostprocessSettings() {} // Called after loading or resetting stored settings void onConfigurationStoreWritten(bool success) { #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE if (success && InterfaceSettingsScreen::backupEEPROM()) { - SERIAL_ECHOLNPGM("Made backup of EEPROM to SPI Flash"); + SERIAL_ECHOLNPGM("EEPROM backed up to SPI Flash"); } #else UNUSED(success); #endif } + void onConfigurationStoreRead(bool) {} - void onConfigurationStoreRead(bool) { - } - - void onPlayTone(const uint16_t frequency, const uint16_t duration) { - sound.play_tone(frequency, duration); - } + void onPlayTone(const uint16_t frequency, const uint16_t duration) { sound.play_tone(frequency, duration); } void onUserConfirmRequired(const char * const msg) { if (msg) @@ -143,20 +121,12 @@ namespace ExtUI { #if HAS_LEVELING && HAS_MESH void onMeshLevelingStart() {} - - void onMeshUpdate(const int8_t x, const int8_t y, const_float_t val) { - BedMeshViewScreen::onMeshUpdate(x, y, val); - } - - void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { - BedMeshViewScreen::onMeshUpdate(x, y, state); - } + void onMeshUpdate(const int8_t x, const int8_t y, const_float_t val) { BedMeshViewScreen::onMeshUpdate(x, y, val); } + void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { BedMeshViewScreen::onMeshUpdate(x, y, state); } #endif #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() { - // Called on resume from power-loss - } + void onPowerLossResume() {} // Called on resume from power-loss #endif #if HAS_PID_HEATING diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/README.md similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/README.md diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.png diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/cyrillic_char_set_bitmap_31.svg diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.png diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png b/Marlin/src/lcd/extui/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/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg b/Marlin/src/lcd/extui/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/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp index e4ecdc8b49..d909767526 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ -#include "../../../../../MarlinCore.h" +#include "../../../../MarlinCore.h" #include "language.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h index ae95a64709..04cdbe96db 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h @@ -27,7 +27,7 @@ * without adding new pin definitions to the board. */ -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(F6_TFT_PINMAP) // FYSETC F6 - ATmega2560 diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_base.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_base.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_ui.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp index dba565189a..46b27062bf 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp @@ -25,7 +25,7 @@ #ifdef FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX -#include "../../../../../feature/host_actions.h" +#include "../../../../feature/host_actions.h" using namespace ExtUI; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/custom_user_menus.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/custom_user_menus.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/custom_user_menus.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/flow_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/flow_percent_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 2566a960e1..56f0fbdc3c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -28,10 +28,10 @@ #include "../archim2-flash/flash_storage.h" -#include "../../../../../module/settings.h" +#include "../../../../module/settings.h" #if ENABLED(LULZBOT_PRINTCOUNTER) - #include "../../../../../module/printcounter.h" + #include "../../../../module/printcounter.h" #endif bool restoreEEPROM(); @@ -258,7 +258,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { } #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - #include "../../../../../HAL/shared/eeprom_api.h" + #include "../../../../HAL/shared/eeprom_api.h" bool restoreEEPROM() { uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE]; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp index 752b17ee00..1309ab5c09 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp @@ -26,7 +26,7 @@ #ifdef FTDI_LEVELING_MENU #if BOTH(HAS_BED_PROBE,BLTOUCH) - #include "../../../../../feature/bltouch.h" + #include "../../../../feature/bltouch.h" #endif using namespace FTDI; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h index a0cb71a6a6..316896c360 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h @@ -22,6 +22,8 @@ #pragma once +#include "../compat.h" + #if ENABLED(TOUCH_UI_FTDI_EVE) #include "../ftdi_eve_lib/ftdi_eve_lib.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp index df31c0ec6f..5403b4004e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -25,7 +25,7 @@ #ifdef FTDI_TUNE_MENU -#include "../../../../../feature/host_actions.h" +#include "../../../../feature/host_actions.h" using namespace FTDI; using namespace Theme; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/theme.h similarity index 100% rename from Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/theme.h diff --git a/Marlin/src/lcd/extui/malyan_lcd.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp similarity index 75% rename from Marlin/src/lcd/extui/malyan_lcd.cpp rename to Marlin/src/lcd/extui/malyan/malyan.cpp index b4e2e328e4..12cdcdf004 100644 --- a/Marlin/src/lcd/extui/malyan_lcd.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -21,7 +21,7 @@ */ /** - * malyan_lcd.cpp + * lcd/extui/malyan/malyan.cpp * * LCD implementation for Malyan's LCD, a separate ESP8266 MCU running * on Serial1 for the M200 board. This module outputs a pseudo-gcode @@ -41,25 +41,26 @@ * Copyright (c) 2017 Jason Nelson (xC0000005) */ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(MALYAN_LCD) //#define DEBUG_MALYAN_LCD -#include "ui_api.h" +#include "malyan.h" +#include "../ui_api.h" +#include "../../marlinui.h" -#include "../marlinui.h" -#include "../../sd/cardreader.h" -#include "../../module/temperature.h" -#include "../../module/stepper.h" -#include "../../module/motion.h" -#include "../../libs/duration_t.h" -#include "../../module/printcounter.h" -#include "../../gcode/queue.h" +#include "../../../sd/cardreader.h" +#include "../../../module/temperature.h" +#include "../../../module/stepper.h" +#include "../../../module/motion.h" +#include "../../../libs/duration_t.h" +#include "../../../module/printcounter.h" +#include "../../../gcode/queue.h" #define DEBUG_OUT ENABLED(DEBUG_MALYAN_LCD) -#include "../../core/debug_out.h" +#include "../../../core/debug_out.h" // This is based on longest sys command + a filename, plus some buffer // in case we encounter some data we don't recognize @@ -94,7 +95,7 @@ void write_to_lcd(const char * const message) { } // {E:} is for error states. -void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr) { +void set_lcd_error_P(PGM_P const error, PGM_P const component/*=nullptr*/) { write_to_lcd_P(PSTR("{E:")); write_to_lcd_P(error); if (component) { @@ -416,125 +417,4 @@ void update_usb_status(const bool forceUpdate) { } } -namespace ExtUI { - void onStartup() { - /** - * The Malyan LCD actually runs as a separate MCU on Serial 1. - * This code's job is to siphon the weird curly-brace commands from - * it and translate into ExtUI operations where possible. - */ - inbound_count = 0; - - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 500000 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - - // Signal init - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); - - // send a version that says "unsupported" - write_to_lcd_P(PSTR("{VER:99}\r\n")); - - // No idea why it does this twice. - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); - update_usb_status(true); - } - - void onIdle() { - /** - * - from printer on startup: - * {SYS:STARTED}{VER:29}{SYS:STARTED}{R:UD} - */ - - // First report USB status. - update_usb_status(false); - - // now drain commands... - while (LCD_SERIAL.available()) - parse_lcd_byte((byte)LCD_SERIAL.read()); - - #if ENABLED(SDSUPPORT) - // The way last printing status works is simple: - // The UI needs to see at least one TQ which is not 100% - // and then when the print is complete, one which is. - static uint8_t last_percent_done = 100; - - // If there was a print in progress, we need to emit the final - // print status as {TQ:100}. Reset last percent done so a new print will - // issue a percent of 0. - const uint8_t percent_done = (ExtUI::isPrinting() || ExtUI::isPrintingFromMediaPaused()) ? ExtUI::getProgress_percent() : last_printing_status ? 100 : 0; - if (percent_done != last_percent_done) { - char message_buffer[16]; - sprintf_P(message_buffer, PSTR("{TQ:%03i}"), percent_done); - write_to_lcd(message_buffer); - last_percent_done = percent_done; - last_printing_status = ExtUI::isPrinting(); - } - #endif - } - - void onPrinterKilled(PGM_P const error, PGM_P const component) { - set_lcd_error_P(error, component); - } - - #if HAS_PID_HEATING - - void onPidTuning(const result_t rst) { - // Called for temperature PID tuning result - //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); - switch (rst) { - case PID_BAD_EXTRUDER_NUM: - set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); - break; - case PID_TEMP_TOO_HIGH: - set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); - break; - case PID_TUNING_TIMEOUT: - set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); - break; - case PID_DONE: - set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); - break; - } - } - - #endif - - void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } - void onPrintTimerPaused() {} - void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } - - // Not needed for Malyan LCD - void onStatusChanged(const char * const) {} - void onMediaInserted() {} - void onMediaError() {} - void onMediaRemoved() {} - void onPlayTone(const uint16_t, const uint16_t) {} - void onFilamentRunout(const extruder_t extruder) {} - void onUserConfirmRequired(const char * const) {} - void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} - void onFactoryReset() {} - void onStoreSettings(char*) {} - void onLoadSettings(const char*) {} - void onPostprocessSettings() {} - void onConfigurationStoreWritten(bool) {} - void onConfigurationStoreRead(bool) {} - - #if HAS_MESH - void onMeshLevelingStart() {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} - #endif - - #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() {} - #endif - - void onSteppersDisabled() {} - void onSteppersEnabled() {} -} - #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/extui/malyan/malyan.h b/Marlin/src/lcd/extui/malyan/malyan.h new file mode 100644 index 0000000000..e8afbd4a59 --- /dev/null +++ b/Marlin/src/lcd/extui/malyan/malyan.h @@ -0,0 +1,53 @@ +/** + * 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 + +/** + * lcd/extui/malyan/malyan.h + */ + +#include "../../../HAL/shared/Marduino.h" + +// Track incoming command bytes from the LCD +extern uint16_t inbound_count; + +// For sending print completion messages +extern bool last_printing_status; + +void write_to_lcd_P(PGM_P const message); +void write_to_lcd(const char * const message); + +void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr); + +void process_lcd_c_command(const char *command); +void process_lcd_eb_command(const char *command); + +template +void j_move_axis(const char *command, const T axis); + +void process_lcd_j_command(const char *command); +void process_lcd_p_command(const char *command); +void process_lcd_s_command(const char *command); +void process_lcd_command(const char *command); + +void parse_lcd_byte(const byte b); +void update_usb_status(const bool forceUpdate); diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp new file mode 100644 index 0000000000..5815522afc --- /dev/null +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -0,0 +1,164 @@ +/** + * 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 . + * + */ + +/** + * lcd/extui/malyan/malyan_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(MALYAN_LCD) + +#include "../ui_api.h" +#include "malyan.h" + +//#include "../../marlinui.h" +//#include "../../../sd/cardreader.h" +//#include "../../../module/temperature.h" +//#include "../../../module/stepper.h" +//#include "../../../module/motion.h" +//#include "../../../libs/duration_t.h" +//#include "../../../module/printcounter.h" +//#include "../../../gcode/queue.h" + +namespace ExtUI { + void onStartup() { + /** + * The Malyan LCD actually runs as a separate MCU on Serial 1. + * This code's job is to siphon the weird curly-brace commands from + * it and translate into ExtUI operations where possible. + */ + inbound_count = 0; + + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 500000 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + + // Signal init + write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + + // send a version that says "unsupported" + write_to_lcd_P(PSTR("{VER:99}\r\n")); + + // No idea why it does this twice. + write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + update_usb_status(true); + } + + void onIdle() { + /** + * - from printer on startup: + * {SYS:STARTED}{VER:29}{SYS:STARTED}{R:UD} + */ + + // First report USB status. + update_usb_status(false); + + // now drain commands... + while (LCD_SERIAL.available()) + parse_lcd_byte((byte)LCD_SERIAL.read()); + + #if ENABLED(SDSUPPORT) + // The way last printing status works is simple: + // The UI needs to see at least one TQ which is not 100% + // and then when the print is complete, one which is. + static uint8_t last_percent_done = 100; + + // If there was a print in progress, we need to emit the final + // print status as {TQ:100}. Reset last percent done so a new print will + // issue a percent of 0. + const uint8_t percent_done = (ExtUI::isPrinting() || ExtUI::isPrintingFromMediaPaused()) ? ExtUI::getProgress_percent() : last_printing_status ? 100 : 0; + if (percent_done != last_percent_done) { + char message_buffer[16]; + sprintf_P(message_buffer, PSTR("{TQ:%03i}"), percent_done); + write_to_lcd(message_buffer); + last_percent_done = percent_done; + last_printing_status = ExtUI::isPrinting(); + } + #endif + } + + void onPrinterKilled(PGM_P const error, PGM_P const component) { + set_lcd_error_P(error, component); + } + + #if HAS_PID_HEATING + + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + switch (rst) { + case PID_BAD_EXTRUDER_NUM: + set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case PID_TEMP_TOO_HIGH: + set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + break; + case PID_TUNING_TIMEOUT: + set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); + break; + case PID_DONE: + set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + break; + } + } + + #endif + + void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } + void onPrintTimerPaused() {} + void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } + + // Not needed for Malyan LCD + void onStatusChanged(const char * const) {} + void onMediaInserted() {} + void onMediaError() {} + void onMediaRemoved() {} + void onPlayTone(const uint16_t, const uint16_t) {} + void onFilamentRunout(const extruder_t extruder) {} + void onUserConfirmRequired(const char * const) {} + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + void onFactoryReset() {} + void onStoreSettings(char*) {} + void onLoadSettings(const char*) {} + void onPostprocessSettings() {} + void onConfigurationStoreWritten(bool) {} + void onConfigurationStoreRead(bool) {} + + #if HAS_MESH + void onMeshLevelingStart() {} + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) {} + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() {} + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // MALYAN_LCD diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp rename to Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 3ad1ac2bb1..5f5608472c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -20,11 +20,11 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include "SPIFlashStorage.h" extern W25QXXFlash W25QXX; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h rename to Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h index 113814d6c8..f2ce8e44ba 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.h +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h @@ -21,7 +21,7 @@ */ #pragma once -#include "../../../../libs/W25Qxx.h" +#include "../../../libs/W25Qxx.h" #define HAS_SPI_FLASH_COMPRESSION 1 diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp rename to Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp index 76a4de3561..68e4d9de04 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp @@ -20,7 +20,7 @@ * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -28,7 +28,7 @@ #include "pic_manager.h" #include "tft_lvgl_configuration.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h similarity index 90% rename from Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h rename to Marlin/src/lcd/extui/mks_ui/SPI_TFT.h index f3be3dc0ba..62a084fb11 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.h +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h @@ -21,11 +21,8 @@ */ #pragma once -#include "../../../../inc/MarlinConfigPre.h" - -#if HAS_TFT_LVGL_UI - -#include "../../../tft_io/tft_io.h" +#include "../../tft_io/tft_io.h" +#include class TFT { public: @@ -39,5 +36,3 @@ public: }; extern TFT SPI_TFT; - -#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_about.cpp index a57dfc504b..54a8ede64e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h b/Marlin/src/lcd/extui/mks_ui/draw_about.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_about.h rename to Marlin/src/lcd/extui/mks_ui/draw_about.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp index 8137c3a909..22196a28b8 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp index feefc4107c..a564d86cc1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp index 3de078f375..d52abcff23 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) #include "draw_ui.h" #include -#include "../../../../module/probe.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/probe.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp index 1e268c9e82..312353f47e 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -19,23 +19,23 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) - #include "../../../../module/settings.h" + #include "../../../module/settings.h" #endif #if HAS_BED_PROBE - #include "../../../../module/probe.h" + #include "../../../module/probe.h" #endif extern lv_group_t *g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h rename to Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp index 635625950b..645cd2e6e3 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h rename to Marlin/src/lcd/extui/mks_ui/draw_change_speed.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_cloud_bind.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp index c6752939dd..55cfe4491d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_cloud_bind.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "lv_conf.h" #include "draw_ui.h" -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" #include "QR_Encode.h" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_cloud_bind.h b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_cloud_bind.h rename to Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index b4ebc97db3..ff642be294 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -24,34 +24,34 @@ * draw_dialog.cpp */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../sd/cardreader.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/temperature.h" -#include "../../../../module/planner.h" -#include "../../../../gcode/gcode.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../sd/cardreader.h" +#include "../../../gcode/queue.h" +#include "../../../module/temperature.h" +#include "../../../module/planner.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) - #include "../../../../module/settings.h" + #include "../../../module/settings.h" #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" + #include "../../../feature/pause.h" #endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) - #include "../../../tft_io/touch_calibration.h" + #include "../../tft_io/touch_calibration.h" #include "draw_touch_calibration.h" #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h rename to Marlin/src/lcd/extui/mks_ui/draw_dialog.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp index 15e319f4a6..b96c65e547 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp index e090c6a3b5..4c56205465 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if BUTTONS_EXIST(EN1, EN2) diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index bdae725cbb..3297b9da27 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -30,7 +30,7 @@ #include "SPI_TFT.h" #include "mks_hardware_test.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h rename to Marlin/src/lcd/extui/mks_ui/draw_error_message.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index 77ec61c4b7..d070d249f3 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -19,16 +19,16 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" static lv_obj_t *scr; extern lv_group_t *g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h rename to Marlin/src/lcd/extui/mks_ui/draw_extrusion.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_fan.cpp index 700471b4a3..ce804e615d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp @@ -19,17 +19,17 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr, *fanText; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h b/Marlin/src/lcd/extui/mks_ui/draw_fan.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h rename to Marlin/src/lcd/extui/mks_ui/draw_fan.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp index e3cfde3011..a3da638be6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -19,18 +19,18 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/temperature.h" -#include "../../../../gcode/gcode.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../gcode/gcode.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h rename to Marlin/src/lcd/extui/mks_ui/draw_filament_change.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp index d78c9ed0cb..97680f3a0c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_gcode.cpp b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_gcode.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp index 17c625b701..bded5df7e7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_gcode.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr,*outL,*outV = 0; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_gcode.h b/Marlin/src/lcd/extui/mks_ui/draw_gcode.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_gcode.h rename to Marlin/src/lcd/extui/mks_ui/draw_gcode.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_home.cpp index 588b940bb6..447fadd55d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -28,8 +28,8 @@ #include "draw_ui.h" #include -#include "../../../../gcode/queue.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h b/Marlin/src/lcd/extui/mks_ui/draw_home.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_home.h rename to Marlin/src/lcd/extui/mks_ui/draw_home.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp index 696463d3eb..e1ab58ee7b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp @@ -19,17 +19,17 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if HAS_TFT_LVGL_UI && USE_SENSORLESS #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../module/probe.h" -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" +#include "../../../module/planner.h" +#include "../../../module/probe.h" +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp index 4067262f20..8a97e30467 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index 3572991813..671939cbff 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" -#include "../../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h rename to Marlin/src/lcd/extui/mks_ui/draw_keyboard.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_language.cpp index 5953d04184..3db22583aa 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include enum { diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h b/Marlin/src/lcd/extui/mks_ui/draw_language.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_language.h rename to Marlin/src/lcd/extui/mks_ui/draw_language.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp index 015c95a68f..8c8dec8913 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_level_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp index 971ea8a69e..890db3b5cd 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h rename to Marlin/src/lcd/extui/mks_ui/draw_machine_para.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp index b79605d74f..3f43da992c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp index f25c7c0c25..b927b99b76 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/queue.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" extern const char G28_STR[]; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h rename to Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp index 238a9af6ae..2cccf899b4 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_media_select.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 6dc816cc23..6fa5cefef0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MULTI_VOLUME) #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" -#include "../../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../sd/cardreader.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_media_select.h b/Marlin/src/lcd/extui/mks_ui/draw_media_select.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_media_select.h rename to Marlin/src/lcd/extui/mks_ui/draw_media_select.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_more.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_more.cpp index 1eb54d231e..d6f1c9ccca 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_more.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -19,16 +19,16 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI -#include "../../../../MarlinCore.h" +#include "../../../MarlinCore.h" #include "draw_ready_print.h" #include "draw_set.h" #include "lv_conf.h" #include "draw_ui.h" -#include "../../../../gcode/queue.h" +#include "../../../gcode/queue.h" extern lv_group_t * g; static lv_obj_t * scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_more.h b/Marlin/src/lcd/extui/mks_ui/draw_more.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_more.h rename to Marlin/src/lcd/extui/mks_ui/draw_more.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp index ec948f10be..b86370e35a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp index 34c7161300..4b413c5c62 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp @@ -19,16 +19,16 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/queue.h" -#include "../../../../module/motion.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../module/motion.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h rename to Marlin/src/lcd/extui/mks_ui/draw_move_motor.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp index 70e1bba990..ae770a8925 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -19,29 +19,29 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/gcode.h" -#include "../../../../gcode/queue.h" -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/gcode.h" +#include "../../../gcode/queue.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if HAS_TRINAMIC_CONFIG - #include "../../../../module/stepper/indirection.h" - #include "../../../../feature/tmc_util.h" + #include "../../../module/stepper/indirection.h" + #include "../../../feature/tmc_util.h" #endif #if HAS_BED_PROBE - #include "../../../../module/probe.h" + #include "../../../module/probe.h" #endif extern lv_group_t *g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h b/Marlin/src/lcd/extui/mks_ui/draw_number_key.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h rename to Marlin/src/lcd/extui/mks_ui/draw_number_key.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_operation.cpp index cd77db8ae1..9b87df1fdf 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp @@ -19,17 +19,17 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h b/Marlin/src/lcd/extui/mks_ui/draw_operation.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h rename to Marlin/src/lcd/extui/mks_ui/draw_operation.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index 3eb717b712..608b3366b1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) #include "draw_ui.h" #include -#include "../../../../feature/pause.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../feature/pause.h" +#include "../../../inc/MarlinConfig.h" void lv_draw_pause_message(const PauseMessage msg) { switch (msg) { diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h rename to Marlin/src/lcd/extui/mks_ui/draw_pause_message.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp index 2f60bc6685..771a98c11f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h rename to Marlin/src/lcd/extui/mks_ui/draw_pause_position.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index 5fcfec1534..54f0917774 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/temperature.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" static lv_obj_t *scr; extern lv_group_t* g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h rename to Marlin/src/lcd/extui/mks_ui/draw_preHeat.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index 17f5d95d2a..6b973241fe 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -30,8 +30,8 @@ //#include "../lvgl/src/lv_core/lv_disp.h" //#include "../lvgl/src/lv_core/lv_refr.h" -#include "../../../../sd/cardreader.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" static lv_obj_t *scr; extern lv_group_t* g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h b/Marlin/src/lcd/extui/mks_ui/draw_print_file.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h rename to Marlin/src/lcd/extui/mks_ui/draw_print_file.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index f752d605ed..c9172d5887 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -19,27 +19,27 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../MarlinCore.h" // for marlin_state -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" // for marlin_state +#include "../../../module/temperature.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - #include "../../../marlinui.h" + #include "../../marlinui.h" #endif extern lv_group_t *g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h b/Marlin/src/lcd/extui/mks_ui/draw_printing.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h rename to Marlin/src/lcd/extui/mks_ui/draw_printing.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index 26cd55d7f5..18f125b57d 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -32,11 +32,11 @@ #include -#include "../../../../module/temperature.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(TOUCH_SCREEN_CALIBRATION) - #include "../../../tft_io/touch_calibration.h" + #include "../../tft_io/touch_calibration.h" #include "draw_touch_calibration.h" #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h rename to Marlin/src/lcd/extui/mks_ui/draw_ready_print.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_set.cpp index 6b06793f28..a765d0e58a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -30,11 +30,11 @@ #include "pic_manager.h" -#include "../../../../gcode/queue.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../inc/MarlinConfig.h" #if HAS_SUICIDE - #include "../../../../MarlinCore.h" + #include "../../../MarlinCore.h" #endif static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h b/Marlin/src/lcd/extui/mks_ui/draw_set.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_set.h rename to Marlin/src/lcd/extui/mks_ui/draw_set.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp index f48d533691..d4ab028eec 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_step_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp index 7c0fc97c93..5117bd4802 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp @@ -19,16 +19,16 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) #include "draw_ui.h" #include -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index 08d442f8a3..b0f55a1d45 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -19,19 +19,19 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) #include "draw_ui.h" #include -#include "../../../../module/stepper/indirection.h" -#include "../../../../feature/tmc_util.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/stepper/indirection.h" +#include "../../../feature/tmc_util.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) - #include "../../../../module/settings.h" + #include "../../../module/settings.h" #endif extern lv_group_t *g; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_tool.cpp index 8e9e5d59fa..16c1448b3c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -19,16 +19,16 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/queue.h" -#include "../../../../module/temperature.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../gcode/queue.h" +#include "../../../module/temperature.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h b/Marlin/src/lcd/extui/mks_ui/draw_tool.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h rename to Marlin/src/lcd/extui/mks_ui/draw_tool.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp similarity index 96% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_touch_calibration.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index 8b9371fbe7..a4470a4c87 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) @@ -27,8 +27,8 @@ #include "draw_touch_calibration.h" #include -#include "../../../../inc/MarlinConfig.h" -#include "../../../tft_io/touch_calibration.h" +#include "../../../inc/MarlinConfig.h" +#include "../../tft_io/touch_calibration.h" #include "SPI_TFT.h" static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_touch_calibration.h b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_touch_calibration.h rename to Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tramming_pos_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tramming_pos_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp index c87de7caa0..c4a21542e2 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tramming_pos_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp @@ -19,15 +19,15 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" extern lv_group_t *g; static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tramming_pos_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_tramming_pos_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 0a99df08e5..c5ae77dd61 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -34,18 +34,18 @@ #include -#include "../../../../MarlinCore.h" // for marlin_state -#include "../../../../sd/cardreader.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" // for marlin_state +#include "../../../sd/cardreader.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../inc/MarlinConfig.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" + #include "../../../feature/pause.h" #endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h rename to Marlin/src/lcd/extui/mks_ui/draw_ui.h index 2809e4e937..37b19ebd46 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -79,7 +79,7 @@ #include "draw_media_select.h" #include "draw_encoder_settings.h" -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(MKS_WIFI_MODULE) #include "wifiSerial.h" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp index fe22923b44..34b2abd094 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp index bda6306e6c..2c3957fe9c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp index fd2c6467e7..8509cc3ac1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp index 3db89a87c9..c337d18922 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h rename to Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp rename to Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp index f3585cc6cb..b1f0e0e1bb 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/gb2312_puhui16.cpp +++ b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "pic_manager.h" #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #if HAS_SPI_FLASH_FONT diff --git a/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp similarity index 94% rename from Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp rename to Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp index 98b4aff881..df48cbec0a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -36,7 +36,7 @@ #include #include -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #ifdef __cplusplus extern "C" { /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp rename to Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp index 8cbe319d14..bcb3cdb6a2 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -32,9 +32,9 @@ #include "pic_manager.h" #include -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../sd/cardreader.h" +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" +#include "../../../sd/cardreader.h" uint8_t pw_det_sta, pw_off_sta, mt_det_sta, mt_det3_sta; #if PIN_EXISTS(MT_DET_2) diff --git a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.h rename to Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp rename to Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 9318b50d2b..da7b1929ce 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -30,10 +30,10 @@ #include "mks_hardware_test.h" #include "SPIFlashStorage.h" -#include "../../../../libs/W25Qxx.h" +#include "../../../libs/W25Qxx.h" -#include "../../../../sd/cardreader.h" -#include "../../../../MarlinCore.h" +#include "../../../sd/cardreader.h" +#include "../../../MarlinCore.h" extern uint16_t DeviceCode; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h rename to Marlin/src/lcd/extui/mks_ui/pic_manager.h index e9960fc73a..90e2407ab0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -21,9 +21,9 @@ */ #pragma once -#include "../../../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" -#include "../../../../libs/W25Qxx.h" +#include "../../../libs/W25Qxx.h" #include diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp similarity index 95% rename from Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp rename to Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 03bcf22822..b618a01957 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -19,23 +19,23 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI #include "draw_ui.h" #include -#include "../../../../gcode/gcode.h" -#include "../../../../module/planner.h" -#include "../../../../module/motion.h" -#include "../../../../sd/cardreader.h" -#include "../../../../inc/MarlinConfig.h" -#include "../../../../MarlinCore.h" -#include "../../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../module/planner.h" +#include "../../../module/motion.h" +#include "../../../sd/cardreader.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" +#include "../../../gcode/queue.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif extern uint32_t To_pre_view; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h b/Marlin/src/lcd/extui/mks_ui/printer_operation.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h rename to Marlin/src/lcd/extui/mks_ui/printer_operation.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_en.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_it.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_it.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h rename to Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp rename to Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index f54b290c13..84e3040e84 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -34,19 +34,19 @@ #include "SPIFlashStorage.h" #include -#include "../../../../MarlinCore.h" -#include "../../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" +#include "../../../inc/MarlinConfig.h" -#include HAL_PATH(../../../../HAL, tft/xpt2046.h) -#include "../../../marlinui.h" +#include HAL_PATH(../../../HAL, tft/xpt2046.h) +#include "../../marlinui.h" XPT2046 touch; #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) - #include "../../../tft_io/touch_calibration.h" + #include "../../tft_io/touch_calibration.h" #include "draw_touch_calibration.h" #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h similarity index 97% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h rename to Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h index 308162b799..49f6ea0900 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -22,7 +22,7 @@ #pragma once /** - * @file lcd/extui/lib/mks_ui/tft_lvgl_configuration.h + * @file lcd/extui/mks_ui/tft_lvgl_configuration.h * @date 2020-02-21 */ diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp rename to Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp index 5e37acb2b4..b34942303a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h rename to Marlin/src/lcd/extui/mks_ui/tft_multi_language.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp rename to Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp index 9e528821d7..d00fd269d8 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI @@ -36,7 +36,7 @@ #include #include -#include "../../../../MarlinCore.h" +#include "../../../MarlinCore.h" DEFINE_WFSERIAL(WifiSerial1, 1); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h rename to Marlin/src/lcd/extui/mks_ui/wifiSerial.h diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp rename to Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 4dd092e64b..897137d013 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) @@ -28,24 +28,24 @@ #include "wifi_upload.h" #include "SPI_TFT.h" -#include "../../../../MarlinCore.h" -#include "../../../../module/temperature.h" -#include "../../../../gcode/queue.h" -#include "../../../../gcode/gcode.h" -#include "../../../../lcd/marlinui.h" -#include "../../../../sd/cardreader.h" -#include "../../../../module/planner.h" -#include "../../../../module/servo.h" -#include "../../../../module/probe.h" +#include "../../../MarlinCore.h" +#include "../../../module/temperature.h" +#include "../../../gcode/queue.h" +#include "../../../gcode/gcode.h" +#include "../../../lcd/marlinui.h" +#include "../../../sd/cardreader.h" +#include "../../../module/planner.h" +#include "../../../module/servo.h" +#include "../../../module/probe.h" #if DISABLED(EMERGENCY_PARSER) - #include "../../../../module/motion.h" + #include "../../../module/motion.h" #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/powerloss.h" + #include "../../../feature/powerloss.h" #endif #if ENABLED(PARK_HEAD_ON_PAUSE) - #include "../../../../feature/pause.h" + #include "../../../feature/pause.h" #endif #define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h rename to Marlin/src/lcd/extui/mks_ui/wifi_module.h index 0886641b2d..8f64613417 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -25,7 +25,7 @@ extern "C" { /* C-declarations for C++ */ #endif -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #include #include diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp similarity index 99% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp rename to Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index e41d473c11..cb5bb762d0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) @@ -27,8 +27,8 @@ #include "wifi_module.h" #include "wifi_upload.h" -#include "../../../../MarlinCore.h" -#include "../../../../sd/cardreader.h" +#include "../../../MarlinCore.h" +#include "../../../sd/cardreader.h" #define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); #define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h similarity index 100% rename from Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h rename to Marlin/src/lcd/extui/mks_ui/wifi_upload.h diff --git a/Marlin/src/lcd/extui/lib/nextion/FileNavigator.cpp b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp similarity index 97% rename from Marlin/src/lcd/extui/lib/nextion/FileNavigator.cpp rename to Marlin/src/lcd/extui/nextion/FileNavigator.cpp index f82ce1f091..650bbd6645 100644 --- a/Marlin/src/lcd/extui/lib/nextion/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp @@ -21,13 +21,13 @@ */ /* **************************************** - * lcd/extui/lib/nextion/FileNavigator.cpp + * lcd/extui/nextion/FileNavigator.cpp * **************************************** * Extensible_UI implementation for Nextion * https://github.com/Skorpi08 * ***************************************/ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(NEXTION_TFT) @@ -37,7 +37,7 @@ using namespace ExtUI; #define DEBUG_OUT NEXDEBUGLEVEL -#include "../../../../core/debug_out.h" +#include "../../../core/debug_out.h" FileList FileNavigator::filelist; // Instance of the Marlin file API char FileNavigator::currentfoldername[MAX_PATH_LEN]; // Current folder path diff --git a/Marlin/src/lcd/extui/lib/nextion/FileNavigator.h b/Marlin/src/lcd/extui/nextion/FileNavigator.h similarity index 95% rename from Marlin/src/lcd/extui/lib/nextion/FileNavigator.h rename to Marlin/src/lcd/extui/nextion/FileNavigator.h index 1cd29ec671..fd29bceade 100644 --- a/Marlin/src/lcd/extui/lib/nextion/FileNavigator.h +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.h @@ -22,14 +22,14 @@ #pragma once /* **************************************** - * lcd/extui/lib/nextion/FileNavigator.cpp + * lcd/extui/nextion/FileNavigator.cpp * **************************************** * Extensible_UI implementation for Nextion * https://github.com/Skorpi08 * ***************************************/ #include "nextion_tft_defs.h" // for MAX_PATH_LEN -#include "../../ui_api.h" +#include "../ui_api.h" using namespace ExtUI; diff --git a/Marlin/src/lcd/extui/nextion_lcd.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp similarity index 100% rename from Marlin/src/lcd/extui/nextion_lcd.cpp rename to Marlin/src/lcd/extui/nextion/nextion_extui.cpp diff --git a/Marlin/src/lcd/extui/lib/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp similarity index 98% rename from Marlin/src/lcd/extui/lib/nextion/nextion_tft.cpp rename to Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 6272d58970..35a5bb7c68 100644 --- a/Marlin/src/lcd/extui/lib/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -21,26 +21,26 @@ */ /* **************************************** - * lcd/extui/lib/nextion/nextion_tft.h + * lcd/extui/nextion/nextion_tft.h * **************************************** * Extensible_UI implementation for Nextion * https://github.com/Skorpi08 * ***************************************/ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(NEXTION_TFT) -#include "../../../../MarlinCore.h" -#include "../../../../feature/pause.h" -#include "../../../../gcode/queue.h" -#include "../../../../libs/numtostr.h" -#include "../../../../sd/cardreader.h" +#include "../../../MarlinCore.h" +#include "../../../feature/pause.h" +#include "../../../gcode/queue.h" +#include "../../../libs/numtostr.h" +#include "../../../sd/cardreader.h" #include "FileNavigator.h" #include "nextion_tft.h" #define DEBUG_OUT NEXDEBUGLEVEL -#include "../../../../core/debug_out.h" +#include "../../../core/debug_out.h" char NextionTFT::selectedfile[MAX_PATH_LEN]; char NextionTFT::nextion_command[MAX_CMND_LEN]; diff --git a/Marlin/src/lcd/extui/lib/nextion/nextion_tft.h b/Marlin/src/lcd/extui/nextion/nextion_tft.h similarity index 94% rename from Marlin/src/lcd/extui/lib/nextion/nextion_tft.h rename to Marlin/src/lcd/extui/nextion/nextion_tft.h index 9197fcc2c6..4eb5fbe0b7 100644 --- a/Marlin/src/lcd/extui/lib/nextion/nextion_tft.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.h @@ -22,15 +22,15 @@ #pragma once /* **************************************** - * lcd/extui/lib/nextion/nextion_tft.h + * lcd/extui/nextion/nextion_tft.h * **************************************** * Extensible_UI implementation for Nextion * https://github.com/Skorpi08 * ***************************************/ #include "nextion_tft_defs.h" -#include "../../../../inc/MarlinConfigPre.h" -#include "../../ui_api.h" +#include "../../../inc/MarlinConfigPre.h" +#include "../ui_api.h" class NextionTFT { private: diff --git a/Marlin/src/lcd/extui/lib/nextion/nextion_tft_defs.h b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h similarity index 97% rename from Marlin/src/lcd/extui/lib/nextion/nextion_tft_defs.h rename to Marlin/src/lcd/extui/nextion/nextion_tft_defs.h index 75f70fc985..32d3ea3295 100644 --- a/Marlin/src/lcd/extui/lib/nextion/nextion_tft_defs.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h @@ -22,13 +22,13 @@ #pragma once /* **************************************** - * lcd/extui/lib/nextion/nextion_tft_defs.h + * lcd/extui/nextion/nextion_tft_defs.h * **************************************** * Extensible_UI implementation for Nextion * https://github.com/Skorpi08 * ***************************************/ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" //#define NEXDEBUGLEVEL 255 #if NEXDEBUGLEVEL diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 13c01954a0..07253c117a 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -154,8 +154,8 @@ #endif #if ENABLED(DGUS_LCD_UI_MKS) - #include "../lcd/extui/lib/dgus/DGUSScreenHandler.h" - #include "../lcd/extui/lib/dgus/DGUSDisplayDef.h" + #include "../lcd/extui/dgus/DGUSScreenHandler.h" + #include "../lcd/extui/dgus/DGUSDisplayDef.h" #endif #pragma pack(push, 1) // No padding between variables diff --git a/ini/features.ini b/ini/features.ini index 9d8bac5713..db9dff9366 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -12,7 +12,7 @@ [features] YHCB2004 = red-scorp/LiquidCrystal_AIP31068@^1.0.4, red-scorp/SoftSPIB@^1.1.1 HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip - src_filter=+ + src_filter=+ extra_scripts=download_mks_assets.py POSTMORTEM_DEBUGGING = src_filter=+ + build_flags=-funwind-tables @@ -73,17 +73,17 @@ HAS_MENU_TMC = src_filter=+ HAS_MENU_TOUCH_SCREEN = src_filter=+ HAS_MENU_TRAMMING = src_filter=+ HAS_MENU_UBL = src_filter=+ -ANYCUBIC_LCD_CHIRON = src_filter=+ + -ANYCUBIC_LCD_I3MEGA = src_filter=+ + -NEXTION_TFT = src_filter=+ + -HAS_DGUS_LCD = src_filter=+ + -DGUS_LCD_UI_FYSETC = src_filter=+ -DGUS_LCD_UI_HIPRECY = src_filter=+ -DGUS_LCD_UI_MKS = src_filter=+ -DGUS_LCD_UI_ORIGIN = src_filter=+ -TOUCH_UI_FTDI_EVE = src_filter=+ -EXTUI_EXAMPLE = src_filter=+ -MALYAN_LCD = src_filter=+ +ANYCUBIC_LCD_CHIRON = src_filter=+ +ANYCUBIC_LCD_I3MEGA = src_filter=+ +HAS_DGUS_LCD = src_filter=+ +DGUS_LCD_UI_FYSETC = src_filter=+ +DGUS_LCD_UI_HIPRECY = src_filter=+ +DGUS_LCD_UI_MKS = src_filter=+ +DGUS_LCD_UI_ORIGIN = src_filter=+ +EXTUI_EXAMPLE = src_filter=+ +TOUCH_UI_FTDI_EVE = src_filter=+ +MALYAN_LCD = src_filter=+ +NEXTION_TFT = src_filter=+ USE_UHS2_USB = src_filter=+ USE_UHS3_USB = src_filter=+ USB_FLASH_DRIVE_SUPPORT = src_filter=+ diff --git a/platformio.ini b/platformio.ini index bbc9ffd904..e743eb2db4 100644 --- a/platformio.ini +++ b/platformio.ini @@ -70,15 +70,14 @@ default_src_filter = + - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - + - + - - - - - + - + - + - + - + - - - - - From 6f06801f1de44c9ec8bce15e5d2c0a8c7185a6a7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 04:41:40 -0500 Subject: [PATCH 0051/2168] Detab --- .../src/lcd/extui/anycubic_chiron/FileNavigator.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp index 9a7086bb51..58adf9761f 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -31,16 +31,16 @@ * This library allows full folder traversal or flat file display and supports both standerd and new style panels. * * ## Old Style TFT panel - * Supported chars {}[]-+=_"$%^&*()~<>| - * Max display length 22 chars - * Max path len 29 chars + * Supported chars {}[]-+=_"$%^&*()~<>| + * Max display length 22 chars + * Max path len 29 chars * (DOS 8.3 filepath max 29chars) * (long filepath Max 22) * * ## New TFT Panel Format file display format - * Supported chars {}[]-+=_!"$%^&*()~<>\| - * Max display length 26 chars - * Max path len 29 chars + * Supported chars {}[]-+=_!"$%^&*()~<>\| + * Max display length 26 chars + * Max path len 29 chars * (DOS 8.3 filepath must end '.GCO') * (long filepath must end '.gcode') * From a7cb13f3393e8858377d16f0f522736845255da0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 04:38:16 -0500 Subject: [PATCH 0052/2168] Tweak SKR pins comments --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 16 ++++++------ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 28 ++++++++++----------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 28 ++++++++++----------- 3 files changed, 36 insertions(+), 36 deletions(-) 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 05072b6c9e..9066b24390 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -54,14 +54,14 @@ /** - * _____ _____ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 NC | 3 4 | NC - * 0.18 | 5 6 3.25 NC | 5 6 0.15 - * 1.23 | 7 8 | 3.26 0.16 | 7 8 | 0.18 - * 0.15 | 9 10| 0.17 2.11 | 9 10| 1.30 - * ----- ----- - * EXP2 EXP1 + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 NC | 3 4 | NC + * 0.18 | 5 6 3.25 NC | 5 6 0.15 + * 1.23 | 7 8 | 3.26 0.16 | 7 8 | 0.18 + * 0.15 | 9 10 | 0.17 2.11 | 9 10 | 1.30 + * ------ ------ + * EXP2 EXP1 */ #define EXP1_03_PIN -1 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index e671429f84..981006fd90 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -187,13 +187,13 @@ #endif /** - * _____ _____ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) - * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) - * (SD_SS) 0.16 | 7 8 | 3.26 (BTN_EN1) (LCD_RS) 1.19 | 7 8 | 1.18 (LCD_EN) - * (SCK) 0.15 | 9 10| 0.17 (MISO) (BTN_ENC) 0.28 | 9 10| 1.30 (BEEPER) - * ----- ----- + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) + * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) + * (SD_SS) 0.16 | 7 8 | 3.26 (BTN_EN1) (LCD_RS) 1.19 | 7 8 | 1.18 (LCD_EN) + * (SCK) 0.15 | 9 10 | 0.17 (MISO) (BTN_ENC) 0.28 | 9 10 | 1.30 (BEEPER) + * ------ ------ * EXP2 EXP1 */ @@ -233,13 +233,13 @@ * The ANET_FULL_GRAPHICS_LCD connector plug: * * BEFORE AFTER - * _____ _____ - * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND - * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 - * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 - * open 7 | 7 8 | 8 BTN_ENC CLK 7 | 7 8 | 8 BTN_ENC - * CLK 9 | 9 10| 10 Beeper open 9 | 9 10| 10 Beeper - * ----- ----- + * ______ ______ + * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND + * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 + * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 + * open 7 | 7 8 | 8 BTN_ENC CLK 7 | 7 8 | 8 BTN_ENC + * CLK 9 | 9 10 | 10 Beeper open 9 | 9 10 | 10 Beeper + * ------ ------ * LCD LCD */ 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 f3ecf30fc8..4451fc9b02 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -327,13 +327,13 @@ * The ANET_FULL_GRAPHICS_LCD connector plug: * * BEFORE AFTER - * _____ _____ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC - * CLK | 9 10| Beeper open | 9 10| Beeper - * ----- ----- + * ______ ______ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC + * CLK | 9 10 | Beeper open | 9 10 | Beeper + * ------ ------ * LCD LCD */ @@ -361,13 +361,13 @@ #elif ENABLED(ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout - * _____ - * 5V | 1 2 | GND - * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) - * (LCD_A0) 1.21 | 5 6 1.20 (BTN_EN2) - * RESET 1.19 | 7 8 | 1.18 (BTN_EN1) - * (BTN_ENC) 0.28 | 9 10| 1.30 (SCK) - * ----- + * ______ + * 5V | 1 2 | GND + * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) + * (LCD_A0) 1.21 | 5 6 1.20 (BTN_EN2) + * RESET 1.19 | 7 8 | 1.18 (BTN_EN1) + * (BTN_ENC) 0.28 | 9 10 | 1.30 (SCK) + * ------ * EXP1 */ From 64ad96e19ea2cafd396bea4ef7632aa006e4386c Mon Sep 17 00:00:00 2001 From: Luu Lac <45380455+shitcreek@users.noreply.github.com> Date: Thu, 6 May 2021 04:52:18 -0500 Subject: [PATCH 0053/2168] TFT SPI for BTT SKR v1.3 (#21794) --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 69 ++++++++++++++++++++- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 4 -- 2 files changed, 68 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 981006fd90..557a4c4c65 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -267,8 +267,75 @@ #error "ADC BUTTONS do not work unmodifed on SKR 1.3, The ADC ports cannot take more than 3.3v." - #elif IS_TFTGLCD_PANEL + #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + #define TFT_A0_PIN EXP1_03_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define TFT_RST_PIN EXP2_04_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + + #define TOUCH_INT_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_06_PIN + + #define TOUCH_MOSI_PIN EXP2_05_PIN + #define TOUCH_SCK_PIN EXP2_09_PIN + #define TOUCH_MISO_PIN EXP2_10_PIN + + #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_ENC EXP1_09_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define TFT_BUFFER_SIZE 2400 + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #if ENABLED(TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -11386 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 8684 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 689 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -273 + #endif + #elif ENABLED(TFT_COLOR_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -16741 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11258 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 1024 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -367 + #endif + #define TFT_BUFFER_SIZE 2400 + #endif + + #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) #define TFTGLCD_CS EXP2_08_PIN #endif 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 4451fc9b02..aa94bc935d 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -402,10 +402,6 @@ #define SD_MISO_PIN EXP2_10_PIN #define SD_MOSI_PIN EXP2_05_PIN - // Disable any LCD related PINs config - #define LCD_PINS_ENABLE -1 - #define LCD_PINS_RS -1 - #define TFT_BUFFER_SIZE 2400 #elif IS_TFTGLCD_PANEL From 9485d44903579f90a3831d8f71a2d1bc97052cb3 Mon Sep 17 00:00:00 2001 From: sanek88lbl <42996016+sanek88lbl@users.noreply.github.com> Date: Thu, 6 May 2021 14:10:18 +0300 Subject: [PATCH 0054/2168] Patches for CASE_LIGHT_USE_RGB_LED (#21811) Co-authored-by: Scott Lahteine --- Marlin/src/feature/caselight.cpp | 20 +++++--------------- Marlin/src/feature/caselight.h | 2 +- Marlin/src/feature/leds/leds.cpp | 2 +- Marlin/src/feature/leds/leds.h | 2 +- Marlin/src/gcode/feature/caselight/M355.cpp | 2 +- 5 files changed, 9 insertions(+), 19 deletions(-) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index d4cc6b1504..fb0f6e3bee 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -28,10 +28,6 @@ CaseLight caselight; -#if CASE_LIGHT_IS_COLOR_LED - #include "leds/leds.h" -#endif - #if CASELIGHT_USES_BRIGHTNESS && !defined(CASE_LIGHT_DEFAULT_BRIGHTNESS) #define CASE_LIGHT_DEFAULT_BRIGHTNESS 0 // For use on PWM pin as non-PWM just sets a default #endif @@ -43,13 +39,9 @@ CaseLight caselight; bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; #if CASE_LIGHT_IS_COLOR_LED - LEDColor CaseLight::color = - #ifdef CASE_LIGHT_DEFAULT_COLOR - CASE_LIGHT_DEFAULT_COLOR - #else - { 255, 255, 255, 255 } - #endif - ; + #include "leds/leds.h" + constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; + LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) }; #endif #ifndef INVERT_CASE_LIGHT @@ -73,14 +65,12 @@ void CaseLight::update(const bool sflag) { brightness = brightness_sav; // Restore last brightness for M355 S1 const uint8_t i = on ? brightness : 0, n10ct = INVERT_CASE_LIGHT ? 255 - i : i; + UNUSED(n10ct); #endif #if CASE_LIGHT_IS_COLOR_LED - leds.set_color( - MakeLEDColor(color.r, color.g, color.b, color.w, n10ct), - false - ); + leds.set_color(MakeLEDColor(color.r, color.g, color.b, color.w, n10ct)); #else // !CASE_LIGHT_IS_COLOR_LED diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h index 05385ad0cb..b2e82f9b83 100644 --- a/Marlin/src/feature/caselight.h +++ b/Marlin/src/feature/caselight.h @@ -27,7 +27,7 @@ #include "leds/leds.h" // for LEDColor #endif -#if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) || ENABLED(CASE_LIGHT_USE_NEOPIXEL) +#if NONE(CASE_LIGHT_NO_BRIGHTNESS, CASE_LIGHT_IS_COLOR_LED) || ENABLED(CASE_LIGHT_USE_NEOPIXEL) #define CASELIGHT_USES_BRIGHTNESS 1 #endif diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index ef0561a435..8349049a00 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -53,7 +53,7 @@ ); #endif -#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) +#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) LEDColor LEDLights::color; bool LEDLights::lights_on; #endif diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index c34eb57f44..cec95102d7 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -187,7 +187,7 @@ public: static inline LEDColor get_color() { return lights_on ? color : LEDColorOff(); } #endif - #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) static LEDColor color; // last non-off color static bool lights_on; // the last set color was "on" #endif diff --git a/Marlin/src/gcode/feature/caselight/M355.cpp b/Marlin/src/gcode/feature/caselight/M355.cpp index b0d94e7cd8..b3b863f02e 100644 --- a/Marlin/src/gcode/feature/caselight/M355.cpp +++ b/Marlin/src/gcode/feature/caselight/M355.cpp @@ -61,7 +61,7 @@ void GcodeSuite::M355() { SERIAL_ECHOLNPGM(STR_OFF); else { #if CASELIGHT_USES_BRIGHTNESS - if (TERN(CASE_LIGHT_USE_NEOPIXEL, true, PWM_PIN(CASE_LIGHT_PIN))) { + if (TERN(CASE_LIGHT_USE_NEOPIXEL, true, TERN0(NEED_CASE_LIGHT_PIN, PWM_PIN(CASE_LIGHT_PIN)))) { SERIAL_ECHOLN(int(caselight.brightness)); return; } From ecca81beba03c0f15d682dafeab290ea136a1a9e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 19:34:15 -0500 Subject: [PATCH 0055/2168] Reformat features.ini --- ini/features.ini | 414 +++++++++++++++++++++++------------------------ 1 file changed, 207 insertions(+), 207 deletions(-) diff --git a/ini/features.ini b/ini/features.ini index db9dff9366..871741dca8 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -10,211 +10,211 @@ ################################# [features] -YHCB2004 = red-scorp/LiquidCrystal_AIP31068@^1.0.4, red-scorp/SoftSPIB@^1.1.1 -HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip - src_filter=+ - extra_scripts=download_mks_assets.py -POSTMORTEM_DEBUGGING = src_filter=+ + - build_flags=-funwind-tables -MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip -HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.1 - src_filter=+ + + + + -HAS_STEALTHCHOP = src_filter=+ -SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip -HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster - src_filter=+ -HAS_TMC26X = TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip - src_filter=+ -HAS_L64XX = Arduino-L6470@0.8.0 - src_filter=+ + + + -NEOPIXEL_LED = Adafruit NeoPixel@1.5.0 - src_filter=+ -TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 -USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 -USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 -USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 -HAS_WIRED_LCD = src_filter=+ -HAS_MARLINUI_HD44780 = src_filter=+ -HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.4 - src_filter=+ -HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + -HAS_FSMC_TFT = src_filter=+ + -HAS_SPI_TFT = src_filter=+ + -I2C_EEPROM = src_filter=+ -SPI_EEPROM = src_filter=+ -HAS_GRAPHICAL_TFT = src_filter=+ -DWIN_CREALITY_LCD = src_filter=+ -IS_TFTGLCD_PANEL = src_filter=+ -HAS_TOUCH_BUTTONS = src_filter=+ -HAS_LCD_MENU = src_filter=+ -HAS_GAMES = src_filter=+ -MARLIN_BRICKOUT = src_filter=+ -MARLIN_INVADERS = src_filter=+ -MARLIN_MAZE = src_filter=+ -MARLIN_SNAKE = src_filter=+ -HAS_MENU_BACKLASH = src_filter=+ -HAS_MENU_BED_CORNERS = src_filter=+ -LCD_BED_LEVELING = src_filter=+ -HAS_MENU_CANCELOBJECT = src_filter=+ -HAS_MENU_DELTA_CALIBRATE = src_filter=+ -HAS_MENU_FILAMENT = src_filter=+ -LCD_INFO_MENU = src_filter=+ -HAS_MENU_JOB_RECOVERY = src_filter=+ -HAS_MULTI_LANGUAGE = src_filter=+ -HAS_MENU_LED = src_filter=+ -HAS_MENU_MEDIA = src_filter=+ -HAS_MENU_MIXER = src_filter=+ -HAS_MENU_MMU2 = src_filter=+ -HAS_MENU_PASSWORD = src_filter=+ -HAS_MENU_POWER_MONITOR = src_filter=+ -HAS_MENU_CUTTER = src_filter=+ -HAS_MENU_TEMPERATURE = src_filter=+ -HAS_MENU_TMC = src_filter=+ -HAS_MENU_TOUCH_SCREEN = src_filter=+ -HAS_MENU_TRAMMING = src_filter=+ -HAS_MENU_UBL = src_filter=+ -ANYCUBIC_LCD_CHIRON = src_filter=+ -ANYCUBIC_LCD_I3MEGA = src_filter=+ -HAS_DGUS_LCD = src_filter=+ -DGUS_LCD_UI_FYSETC = src_filter=+ -DGUS_LCD_UI_HIPRECY = src_filter=+ -DGUS_LCD_UI_MKS = src_filter=+ -DGUS_LCD_UI_ORIGIN = src_filter=+ -EXTUI_EXAMPLE = src_filter=+ -TOUCH_UI_FTDI_EVE = src_filter=+ -MALYAN_LCD = src_filter=+ -NEXTION_TFT = src_filter=+ -USE_UHS2_USB = src_filter=+ -USE_UHS3_USB = src_filter=+ -USB_FLASH_DRIVE_SUPPORT = src_filter=+ -AUTO_BED_LEVELING_BILINEAR = src_filter=+ +YHCB2004 = red-scorp/LiquidCrystal_AIP31068@^1.0.4, red-scorp/SoftSPIB@^1.1.1 +HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip + src_filter=+ + extra_scripts=download_mks_assets.py +POSTMORTEM_DEBUGGING = src_filter=+ + + build_flags=-funwind-tables +MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip +HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.1 + src_filter=+ + + + + +HAS_STEALTHCHOP = src_filter=+ +SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip +HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster + src_filter=+ +HAS_TMC26X = TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip + src_filter=+ +HAS_L64XX = Arduino-L6470@0.8.0 + src_filter=+ + + + +NEOPIXEL_LED = Adafruit NeoPixel@1.5.0 + src_filter=+ +TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 +USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 +USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 +USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 +HAS_WIRED_LCD = src_filter=+ +HAS_MARLINUI_HD44780 = src_filter=+ +HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.4 + src_filter=+ +HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + +HAS_FSMC_TFT = src_filter=+ + +HAS_SPI_TFT = src_filter=+ + +I2C_EEPROM = src_filter=+ +SPI_EEPROM = src_filter=+ +HAS_GRAPHICAL_TFT = src_filter=+ +DWIN_CREALITY_LCD = src_filter=+ +IS_TFTGLCD_PANEL = src_filter=+ +HAS_TOUCH_BUTTONS = src_filter=+ +HAS_LCD_MENU = src_filter=+ +HAS_GAMES = src_filter=+ +MARLIN_BRICKOUT = src_filter=+ +MARLIN_INVADERS = src_filter=+ +MARLIN_MAZE = src_filter=+ +MARLIN_SNAKE = src_filter=+ +HAS_MENU_BACKLASH = src_filter=+ +HAS_MENU_BED_CORNERS = src_filter=+ +LCD_BED_LEVELING = src_filter=+ +HAS_MENU_CANCELOBJECT = src_filter=+ +HAS_MENU_DELTA_CALIBRATE = src_filter=+ +HAS_MENU_FILAMENT = src_filter=+ +LCD_INFO_MENU = src_filter=+ +HAS_MENU_JOB_RECOVERY = src_filter=+ +HAS_MULTI_LANGUAGE = src_filter=+ +HAS_MENU_LED = src_filter=+ +HAS_MENU_MEDIA = src_filter=+ +HAS_MENU_MIXER = src_filter=+ +HAS_MENU_MMU2 = src_filter=+ +HAS_MENU_PASSWORD = src_filter=+ +HAS_MENU_POWER_MONITOR = src_filter=+ +HAS_MENU_CUTTER = src_filter=+ +HAS_MENU_TEMPERATURE = src_filter=+ +HAS_MENU_TMC = src_filter=+ +HAS_MENU_TOUCH_SCREEN = src_filter=+ +HAS_MENU_TRAMMING = src_filter=+ +HAS_MENU_UBL = src_filter=+ +ANYCUBIC_LCD_CHIRON = src_filter=+ +ANYCUBIC_LCD_I3MEGA = src_filter=+ +HAS_DGUS_LCD = src_filter=+ +DGUS_LCD_UI_FYSETC = src_filter=+ +DGUS_LCD_UI_HIPRECY = src_filter=+ +DGUS_LCD_UI_MKS = src_filter=+ +DGUS_LCD_UI_ORIGIN = src_filter=+ +EXTUI_EXAMPLE = src_filter=+ +TOUCH_UI_FTDI_EVE = src_filter=+ +MALYAN_LCD = src_filter=+ +NEXTION_TFT = src_filter=+ +USE_UHS2_USB = src_filter=+ +USE_UHS3_USB = src_filter=+ +USB_FLASH_DRIVE_SUPPORT = src_filter=+ +AUTO_BED_LEVELING_BILINEAR = src_filter=+ AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ -MESH_BED_LEVELING = src_filter=+ + -AUTO_BED_LEVELING_UBL = src_filter=+ + -UBL_HILBERT_CURVE = src_filter=+ -BACKLASH_COMPENSATION = src_filter=+ -BARICUDA = src_filter=+ + -BINARY_FILE_TRANSFER = src_filter=+ + -BLTOUCH = src_filter=+ -CANCEL_OBJECTS = src_filter=+ + -CASE_LIGHT_ENABLE = src_filter=+ + -EXTERNAL_CLOSED_LOOP_CONTROLLER = src_filter=+ + -USE_CONTROLLER_FAN = src_filter=+ -HAS_MOTOR_CURRENT_DAC = src_filter=+ -DIRECT_STEPPING = src_filter=+ + -EMERGENCY_PARSER = src_filter=+ - -I2C_POSITION_ENCODERS = src_filter=+ -IIC_BL24CXX_EEPROM = src_filter=+ -HAS_SPI_FLASH = src_filter=+ -HAS_ETHERNET = src_filter=+ + -HAS_FANMUX = src_filter=+ -FILAMENT_WIDTH_SENSOR = src_filter=+ + -FWRETRACT = src_filter=+ + -HOST_ACTION_COMMANDS = src_filter=+ -HOTEND_IDLE_TIMEOUT = src_filter=+ -JOYSTICK = src_filter=+ -BLINKM = src_filter=+ -HAS_COLOR_LEDS = src_filter=+ + -PCA9533 = src_filter=+ -PCA9632 = src_filter=+ -PRINTER_EVENT_LEDS = src_filter=+ -TEMP_STAT_LEDS = src_filter=+ -MAX7219_DEBUG = src_filter=+ + -HAS_MEATPACK = src_filter=+ -MIXING_EXTRUDER = src_filter=+ + -HAS_PRUSA_MMU1 = src_filter=+ -HAS_PRUSA_MMU2 = src_filter=+ + -PASSWORD_FEATURE = src_filter=+ + -ADVANCED_PAUSE_FEATURE = src_filter=+ + + -AUTO_POWER_CONTROL = src_filter=+ -HAS_POWER_MONITOR = src_filter=+ + -POWER_LOSS_RECOVERY = src_filter=+ + -PROBE_TEMP_COMPENSATION = src_filter=+ + -HAS_FILAMENT_SENSOR = src_filter=+ + -(EXT|MANUAL)_SOLENOID.* = src_filter=+ + -MK2_MULTIPLEXER = src_filter=+ -HAS_CUTTER = src_filter=+ + -HAS_DRIVER_SAFE_POWER_PROTECT = src_filter=+ -EXPERIMENTAL_I2CBUS = src_filter=+ + -MECHANICAL_GANTRY_CAL.+ = src_filter=+ -Z_MULTI_ENDSTOPS = src_filter=+ -Z_STEPPER_AUTO_ALIGN = src_filter=+ + -G26_MESH_VALIDATION = src_filter=+ -ASSISTED_TRAMMING = src_filter=+ + -HAS_MESH = src_filter=+ -HAS_LEVELING = src_filter=+ + -DELTA_AUTO_CALIBRATION = src_filter=+ -CALIBRATION_GCODE = src_filter=+ -Z_MIN_PROBE_REPEATABILITY_TEST = src_filter=+ -M100_FREE_MEMORY_WATCHER = src_filter=+ -BACKLASH_GCODE = src_filter=+ -IS_KINEMATIC = src_filter=+ -HAS_EXTRA_ENDSTOPS = src_filter=+ -SKEW_CORRECTION_GCODE = src_filter=+ -DIRECT_PIN_CONTROL = src_filter=+ + -PINS_DEBUGGING = src_filter=+ -NO_VOLUMETRICS = src_filter=- -HAS_MULTI_EXTRUDER = src_filter=+ -HAS_HOTEND_OFFSET = src_filter=+ -EDITABLE_SERVO_ANGLES = src_filter=+ -PIDTEMP = src_filter=+ -PREVENT_COLD_EXTRUSION = src_filter=+ -PIDTEMPBED = src_filter=+ -HAS_USER_THERMISTORS = src_filter=+ -SD_ABORT_ON_ENDSTOP_HIT = src_filter=+ -BAUD_RATE_GCODE = src_filter=+ -HAS_SMART_EFF_MOD = src_filter=+ -COOLANT_CONTROL = src_filter=+ -AIR_EVACUATION = src_filter=+ -HAS_SOFTWARE_ENDSTOPS = src_filter=+ -HAS_DUPLICATION_MODE = src_filter=+ -LIN_ADVANCE = src_filter=+ -PHOTO_GCODE = src_filter=+ -CONTROLLER_FAN_EDITABLE = src_filter=+ -GCODE_MACROS = src_filter=+ -GRADIENT_MIX = src_filter=+ -HAS_SAVED_POSITIONS = src_filter=+ + -PARK_HEAD_ON_PAUSE = src_filter=+ -FILAMENT_LOAD_UNLOAD_GCODES = src_filter=+ -CNC_WORKSPACE_PLANES = src_filter=+ -CNC_COORDINATE_SYSTEMS = src_filter=+ -HAS_M206_COMMAND = src_filter=+ -EXPECTED_PRINTER_CHECK = src_filter=+ -HOST_KEEPALIVE_FEATURE = src_filter=+ -REPETIER_GCODE_M360 = src_filter=+ -HAS_GCODE_M876 = src_filter=+ -HAS_RESUME_CONTINUE = src_filter=+ -HAS_LCD_CONTRAST = src_filter=+ -LCD_SET_PROGRESS_MANUALLY = src_filter=+ -TOUCH_SCREEN_CALIBRATION = src_filter=+ -ARC_SUPPORT = src_filter=+ -GCODE_MOTION_MODES = src_filter=+ -BABYSTEPPING = src_filter=+ + -Z_PROBE_SLED = src_filter=+ -G38_PROBE_TARGET = src_filter=+ -MAGNETIC_PARKING_EXTRUDER = src_filter=+ -SDSUPPORT = src_filter=+ + + + + + + -HAS_MEDIA_SUBCALLS = src_filter=+ -GCODE_REPEAT_MARKERS = src_filter=+ + -HAS_EXTRUDERS = src_filter=+ + -HAS_COOLER = src_filter=+ + -AUTO_REPORT_TEMPERATURES = src_filter=+ -INCH_MODE_SUPPORT = src_filter=+ -TEMPERATURE_UNITS_SUPPORT = src_filter=+ -NEED_HEX_PRINT = src_filter=+ -NEED_LSF = src_filter=+ -NOZZLE_PARK_FEATURE = src_filter=+ + -NOZZLE_CLEAN_FEATURE = src_filter=+ + -DELTA = src_filter=+ + -BEZIER_CURVE_SUPPORT = src_filter=+ + -PRINTCOUNTER = src_filter=+ -HAS_BED_PROBE = src_filter=+ + + + -IS_SCARA = src_filter=+ -HAS_SERVOS = src_filter=+ + -MORGAN_SCARA = src_filter=+ -HAS_MICROSTEPS = src_filter=+ -(ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer - ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master.zip - arduinoWebSockets=links2004/WebSockets@2.3.4 - luc-github/ESP32SSDP@^1.1.1 - lib_ignore=ESPAsyncTCP +MESH_BED_LEVELING = src_filter=+ + +AUTO_BED_LEVELING_UBL = src_filter=+ + +UBL_HILBERT_CURVE = src_filter=+ +BACKLASH_COMPENSATION = src_filter=+ +BARICUDA = src_filter=+ + +BINARY_FILE_TRANSFER = src_filter=+ + +BLTOUCH = src_filter=+ +CANCEL_OBJECTS = src_filter=+ + +CASE_LIGHT_ENABLE = src_filter=+ + +EXTERNAL_CLOSED_LOOP_CONTROLLER = src_filter=+ + +USE_CONTROLLER_FAN = src_filter=+ +HAS_MOTOR_CURRENT_DAC = src_filter=+ +DIRECT_STEPPING = src_filter=+ + +EMERGENCY_PARSER = src_filter=+ - +I2C_POSITION_ENCODERS = src_filter=+ +IIC_BL24CXX_EEPROM = src_filter=+ +HAS_SPI_FLASH = src_filter=+ +HAS_ETHERNET = src_filter=+ + +HAS_FANMUX = src_filter=+ +FILAMENT_WIDTH_SENSOR = src_filter=+ + +FWRETRACT = src_filter=+ + +HOST_ACTION_COMMANDS = src_filter=+ +HOTEND_IDLE_TIMEOUT = src_filter=+ +JOYSTICK = src_filter=+ +BLINKM = src_filter=+ +HAS_COLOR_LEDS = src_filter=+ + +PCA9533 = src_filter=+ +PCA9632 = src_filter=+ +PRINTER_EVENT_LEDS = src_filter=+ +TEMP_STAT_LEDS = src_filter=+ +MAX7219_DEBUG = src_filter=+ + +HAS_MEATPACK = src_filter=+ +MIXING_EXTRUDER = src_filter=+ + +HAS_PRUSA_MMU1 = src_filter=+ +HAS_PRUSA_MMU2 = src_filter=+ + +PASSWORD_FEATURE = src_filter=+ + +ADVANCED_PAUSE_FEATURE = src_filter=+ + + +AUTO_POWER_CONTROL = src_filter=+ +HAS_POWER_MONITOR = src_filter=+ + +POWER_LOSS_RECOVERY = src_filter=+ + +PROBE_TEMP_COMPENSATION = src_filter=+ + +HAS_FILAMENT_SENSOR = src_filter=+ + +(EXT|MANUAL)_SOLENOID.* = src_filter=+ + +MK2_MULTIPLEXER = src_filter=+ +HAS_CUTTER = src_filter=+ + +HAS_DRIVER_SAFE_POWER_PROTECT = src_filter=+ +EXPERIMENTAL_I2CBUS = src_filter=+ + +MECHANICAL_GANTRY_CAL.+ = src_filter=+ +Z_MULTI_ENDSTOPS = src_filter=+ +Z_STEPPER_AUTO_ALIGN = src_filter=+ + +G26_MESH_VALIDATION = src_filter=+ +ASSISTED_TRAMMING = src_filter=+ + +HAS_MESH = src_filter=+ +HAS_LEVELING = src_filter=+ + +DELTA_AUTO_CALIBRATION = src_filter=+ +CALIBRATION_GCODE = src_filter=+ +Z_MIN_PROBE_REPEATABILITY_TEST = src_filter=+ +M100_FREE_MEMORY_WATCHER = src_filter=+ +BACKLASH_GCODE = src_filter=+ +IS_KINEMATIC = src_filter=+ +HAS_EXTRA_ENDSTOPS = src_filter=+ +SKEW_CORRECTION_GCODE = src_filter=+ +DIRECT_PIN_CONTROL = src_filter=+ + +PINS_DEBUGGING = src_filter=+ +NO_VOLUMETRICS = src_filter=- +HAS_MULTI_EXTRUDER = src_filter=+ +HAS_HOTEND_OFFSET = src_filter=+ +EDITABLE_SERVO_ANGLES = src_filter=+ +PIDTEMP = src_filter=+ +PREVENT_COLD_EXTRUSION = src_filter=+ +PIDTEMPBED = src_filter=+ +HAS_USER_THERMISTORS = src_filter=+ +SD_ABORT_ON_ENDSTOP_HIT = src_filter=+ +BAUD_RATE_GCODE = src_filter=+ +HAS_SMART_EFF_MOD = src_filter=+ +COOLANT_CONTROL = src_filter=+ +AIR_EVACUATION = src_filter=+ +HAS_SOFTWARE_ENDSTOPS = src_filter=+ +HAS_DUPLICATION_MODE = src_filter=+ +LIN_ADVANCE = src_filter=+ +PHOTO_GCODE = src_filter=+ +CONTROLLER_FAN_EDITABLE = src_filter=+ +GCODE_MACROS = src_filter=+ +GRADIENT_MIX = src_filter=+ +HAS_SAVED_POSITIONS = src_filter=+ + +PARK_HEAD_ON_PAUSE = src_filter=+ +FILAMENT_LOAD_UNLOAD_GCODES = src_filter=+ +CNC_WORKSPACE_PLANES = src_filter=+ +CNC_COORDINATE_SYSTEMS = src_filter=+ +HAS_M206_COMMAND = src_filter=+ +EXPECTED_PRINTER_CHECK = src_filter=+ +HOST_KEEPALIVE_FEATURE = src_filter=+ +REPETIER_GCODE_M360 = src_filter=+ +HAS_GCODE_M876 = src_filter=+ +HAS_RESUME_CONTINUE = src_filter=+ +HAS_LCD_CONTRAST = src_filter=+ +LCD_SET_PROGRESS_MANUALLY = src_filter=+ +TOUCH_SCREEN_CALIBRATION = src_filter=+ +ARC_SUPPORT = src_filter=+ +GCODE_MOTION_MODES = src_filter=+ +BABYSTEPPING = src_filter=+ + +Z_PROBE_SLED = src_filter=+ +G38_PROBE_TARGET = src_filter=+ +MAGNETIC_PARKING_EXTRUDER = src_filter=+ +SDSUPPORT = src_filter=+ + + + + + + +HAS_MEDIA_SUBCALLS = src_filter=+ +GCODE_REPEAT_MARKERS = src_filter=+ + +HAS_EXTRUDERS = src_filter=+ + +HAS_COOLER = src_filter=+ + +AUTO_REPORT_TEMPERATURES = src_filter=+ +INCH_MODE_SUPPORT = src_filter=+ +TEMPERATURE_UNITS_SUPPORT = src_filter=+ +NEED_HEX_PRINT = src_filter=+ +NEED_LSF = src_filter=+ +NOZZLE_PARK_FEATURE = src_filter=+ + +NOZZLE_CLEAN_FEATURE = src_filter=+ + +DELTA = src_filter=+ + +BEZIER_CURVE_SUPPORT = src_filter=+ + +PRINTCOUNTER = src_filter=+ +HAS_BED_PROBE = src_filter=+ + + + +IS_SCARA = src_filter=+ +HAS_SERVOS = src_filter=+ + +MORGAN_SCARA = src_filter=+ +HAS_MICROSTEPS = src_filter=+ +(ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer + ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master.zip + arduinoWebSockets=links2004/WebSockets@2.3.4 + luc-github/ESP32SSDP@^1.1.1 + lib_ignore=ESPAsyncTCP From 32bf44764483e40eddf0cd0361e3356166f70445 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 7 May 2021 00:58:41 +0000 Subject: [PATCH 0056/2168] [cron] Bump distribution date (2021-05-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index da65fcac5b..2ab6071ac1 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 "2021-05-06" + #define STRING_DISTRIBUTION_DATE "2021-05-07" #endif /** From be6fbc76a1ab1618421315958480f6a1d6093533 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 May 2021 22:39:34 -0500 Subject: [PATCH 0057/2168] Serial and pins debug cleanup - Rename some AVR / DUE / ESP32 serial types - Reduce two #error to one static_assert - Update AVR/DUE error messages --- Marlin/src/HAL/AVR/HAL.h | 8 +- Marlin/src/HAL/AVR/MarlinSerial.cpp | 8 +- Marlin/src/HAL/AVR/MarlinSerial.h | 16 ++-- Marlin/src/HAL/DUE/HAL.h | 11 +-- Marlin/src/HAL/DUE/MarlinSerial.cpp | 2 +- Marlin/src/HAL/DUE/MarlinSerial.h | 4 +- Marlin/src/HAL/DUE/MarlinSerialUSB.cpp | 10 +-- Marlin/src/HAL/DUE/MarlinSerialUSB.h | 12 ++- Marlin/src/HAL/ESP32/WebSocketSerial.cpp | 2 +- Marlin/src/HAL/ESP32/WebSocketSerial.h | 4 +- Marlin/src/HAL/LPC1768/MarlinSerial.cpp | 8 +- Marlin/src/HAL/SAMD51/HAL.h | 2 - Marlin/src/HAL/STM32/HAL.h | 6 +- Marlin/src/HAL/STM32F1/HAL.h | 32 ++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 + Marlin/src/core/serial.h | 14 ++- Marlin/src/inc/Conditionals_post.h | 1 - Marlin/src/pins/pinsDebug.h | 105 ++++------------------- 18 files changed, 76 insertions(+), 171 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 7adf1aad49..64e4f764dc 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -93,13 +93,13 @@ typedef int8_t pin_t; #define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0) #else #if !WITHIN(SERIAL_PORT, -1, 3) - #error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #define MYSERIAL1 customizedSerial1 #ifdef SERIAL_PORT_2 #if !WITHIN(SERIAL_PORT_2, -1, 3) - #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." #endif #define MYSERIAL2 customizedSerial2 #endif @@ -107,14 +107,14 @@ typedef int8_t pin_t; #ifdef MMU2_SERIAL_PORT #if !WITHIN(MMU2_SERIAL_PORT, -1, 3) - #error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #define MMU2_SERIAL mmuSerial #endif #ifdef LCD_SERIAL_PORT #if !WITHIN(LCD_SERIAL_PORT, -1, 3) - #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #define LCD_SERIAL lcdSerial #if HAS_DGUS_LCD diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 8f82b7b418..82cdcfbe83 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -567,7 +567,7 @@ ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) { // Because of the template definition above, it's required to instantiate the template to have all methods generated template class MarlinSerial< MarlinSerialCfg >; -MSerialT customizedSerial1(MSerialT::HasEmergencyParser); +MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser); #ifdef SERIAL_PORT_2 @@ -596,7 +596,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); } template class MarlinSerial< MMU2SerialCfg >; - MSerialT3 mmuSerial(MSerialT3::HasEmergencyParser); + MSerialMMU2 mmuSerial(MSerialMMU2::HasEmergencyParser); #endif // MMU2_SERIAL_PORT @@ -611,7 +611,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); } template class MarlinSerial< LCDSerialCfg >; - MSerialT4 lcdSerial(MSerialT4::HasEmergencyParser); + MSerialLCD lcdSerial(MSerialLCD::HasEmergencyParser); #if HAS_DGUS_LCD template @@ -630,7 +630,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser); // For AT90USB targets use the UART for BT interfacing #if defined(USBCON) && ENABLED(BLUETOOTH) - MSerialT5 bluetoothSerial(false); + MSerialBT bluetoothSerial(false); #endif #endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 355ecd41fd..26066d7208 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -238,8 +238,8 @@ static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED); }; - typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT; - extern MSerialT customizedSerial1; + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1; + extern MSerialT1 customizedSerial1; #ifdef SERIAL_PORT_2 typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2; @@ -262,8 +262,8 @@ static constexpr bool RX_OVERRUNS = false; }; - typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialT3; - extern MSerialT3 mmuSerial; + typedef Serial1Class< MarlinSerial< MMU2SerialCfg > > MSerialMMU2; + extern MSerialMMU2 mmuSerial; #endif #ifdef LCD_SERIAL_PORT @@ -281,12 +281,12 @@ static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); }; - typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialT4; - extern MSerialT4 lcdSerial; + typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD; + extern MSerialLCD lcdSerial; #endif // Use the UART for Bluetooth in AT90USB configurations #if defined(USBCON) && ENABLED(BLUETOOTH) - typedef Serial1Class MSerialT5; - extern MSerialT5 bluetoothSerial; + typedef Serial1Class MSerialBT; + extern MSerialBT bluetoothSerial; #endif diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 1bc3bf7410..2fb927948c 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -50,13 +50,12 @@ extern DefaultSerial4 MSerial3; #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -// Define MYSERIAL1/2 before MarlinSerial includes! #if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER) #define MYSERIAL1 customizedSerial1 #elif WITHIN(SERIAL_PORT, 0, 3) #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else - #error "The required SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "The required SERIAL_PORT must be from 0 to 3, or -1 for USB Serial." #endif #ifdef SERIAL_PORT_2 @@ -65,7 +64,7 @@ extern DefaultSerial4 MSerial3; #elif WITHIN(SERIAL_PORT_2, 0, 3) #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial." #endif #endif @@ -78,12 +77,10 @@ extern DefaultSerial4 MSerial3; #endif #ifdef LCD_SERIAL_PORT - #if LCD_SERIAL_PORT == -1 - #define LCD_SERIAL lcdSerial - #elif WITHIN(LCD_SERIAL_PORT, 0, 3) + #if WITHIN(LCD_SERIAL_PORT, 0, 3) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." + #error "LCD_SERIAL_PORT must be from 0 to 3." #endif #endif diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 5b333fbeb5..29d9ab0797 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -478,7 +478,7 @@ void MarlinSerial::flushTX() { // If not using the USB port as serial port #if defined(SERIAL_PORT) && SERIAL_PORT >= 0 template class MarlinSerial< MarlinSerialCfg >; - MSerialT customizedSerial1(MarlinSerialCfg::EMERGENCYPARSER); + MSerialT1 customizedSerial1(MarlinSerialCfg::EMERGENCYPARSER); #endif #if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index 0fb15cf8ad..496e54c151 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -141,8 +141,8 @@ struct MarlinSerialCfg { }; #if defined(SERIAL_PORT) && SERIAL_PORT >= 0 - typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT; - extern MSerialT customizedSerial1; + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT1; + extern MSerialT1 customizedSerial1; #endif #if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0 diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index fca677c798..fb5f013255 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -19,13 +19,13 @@ * along with this program. If not, see . * */ +#ifdef ARDUINO_ARCH_SAM /** * MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE * Copyright (c) 2017 Eduardo José Tagle. All right reserved * Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved. */ -#ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" @@ -65,7 +65,7 @@ int MarlinSerialUSB::peek() { pending_char = udi_cdc_getc(); - TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)pending_char)); + TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)pending_char)); return pending_char; } @@ -87,7 +87,7 @@ int MarlinSerialUSB::read() { int c = udi_cdc_getc(); - TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)c)); + TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast(this)->emergency_state, (char)c)); return c; } @@ -129,10 +129,10 @@ size_t MarlinSerialUSB::write(const uint8_t c) { // Preinstantiate #if SERIAL_PORT == -1 - MSerialT customizedSerial1(TERN0(EMERGENCY_PARSER, true)); + MSerialT1 customizedSerial1(TERN0(EMERGENCY_PARSER, true)); #endif #if SERIAL_PORT_2 == -1 - MSerialT customizedSerial2(TERN0(EMERGENCY_PARSER, true)); + MSerialT2 customizedSerial2(TERN0(EMERGENCY_PARSER, true)); #endif #endif // HAS_USB_SERIAL diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h index 4c299dced5..d19fc60eb6 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h @@ -27,11 +27,9 @@ */ #include "../../inc/MarlinConfig.h" -#if HAS_USB_SERIAL - -#include #include "../../core/serial_hook.h" +#include struct MarlinSerialUSB { void begin(const long); @@ -50,14 +48,14 @@ struct MarlinSerialUSB { FORCE_INLINE int rxMaxEnqueued() { return 0; } #endif }; -typedef Serial1Class MSerialT; #if SERIAL_PORT == -1 - extern MSerialT customizedSerial1; + typedef Serial1Class MSerialT1; + extern MSerialT1 customizedSerial1; #endif #if SERIAL_PORT_2 == -1 - extern MSerialT customizedSerial2; + typedef Serial1Class MSerialT2; + extern MSerialT2 customizedSerial2; #endif -#endif // HAS_USB_SERIAL diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp index 96769f261f..eb5b9d6039 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp +++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp @@ -29,7 +29,7 @@ #include "wifi.h" #include -MSerialT webSocketSerial(false); +MSerialWebSocketT webSocketSerial(false); AsyncWebSocket ws("/ws"); // TODO Move inside the class. // RingBuffer impl diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/WebSocketSerial.h index 574f7b10f0..6b3e419d10 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.h +++ b/Marlin/src/HAL/ESP32/WebSocketSerial.h @@ -81,5 +81,5 @@ public: #endif }; -typedef Serial1Class MSerialT; -extern MSerialT webSocketSerial; +typedef Serial1Class MSerialWebSocketT; +extern MSerialWebSocketT webSocketSerial; diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index f35328d22f..f2aecf54a0 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -26,9 +26,9 @@ #include "../../inc/MarlinConfig.h" #if USING_HW_SERIAL0 - MarlinSerial _MSerial(LPC_UART0); - MSerialT MSerial0(true, _MSerial); - extern "C" void UART0_IRQHandler() { _MSerial.IRQHandler(); } + MarlinSerial _MSerial0(LPC_UART0); + MSerialT MSerial0(true, _MSerial0); + extern "C" void UART0_IRQHandler() { _MSerial0.IRQHandler(); } #endif #if USING_HW_SERIAL1 MarlinSerial _MSerial1((LPC_UART_TypeDef *) LPC_UART1); @@ -52,7 +52,7 @@ // Need to figure out which serial port we are and react in consequence (Marlin does not have CONTAINER_OF macro) if (false) {} #if USING_HW_SERIAL0 - else if (this == &_MSerial) emergency_parser.update(MSerial0.emergency_state, c); + else if (this == &_MSerial0) emergency_parser.update(MSerial0.emergency_state, c); #endif #if USING_HW_SERIAL1 else if (this == &_MSerial1) emergency_parser.update(MSerial1.emergency_state, c); diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 85ac5dd00c..491c3f82c4 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -43,8 +43,6 @@ extern DefaultSerial4 MSerial3; extern DefaultSerial5 MSerial4; - // MYSERIAL1 required before MarlinSerial includes! - #define __MSERIAL(X) MSerial##X #define _MSERIAL(X) __MSERIAL(X) #define MSERIAL(X) _MSERIAL(INCREMENT(X)) diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 469d08e435..8ac9e6bd80 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -37,6 +37,9 @@ #include +// +// Serial Ports +// #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -44,9 +47,6 @@ extern DefaultSerial1 MSerial0; #endif -// ------------------------ -// Defines -// ------------------------ #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index af4d27f43e..8b306f48fa 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -36,7 +36,6 @@ #include "fastio.h" #include "watchdog.h" - #include #include @@ -63,11 +62,10 @@ #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; - - #if !HAS_SD_HOST_DRIVE - #define UsbSerial MSerial0 - #else + #if HAS_SD_HOST_DRIVE #define UsbSerial MarlinCompositeSerial + #else + #define UsbSerial MSerial0 #endif #endif @@ -86,11 +84,7 @@ #define MYSERIAL1 MSERIAL(SERIAL_PORT) #else #define MYSERIAL1 MSERIAL(1) // dummy port - #if NUM_UARTS == 5 - #error "SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB." - #else - #error "SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB." - #endif + static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #ifdef SERIAL_PORT_2 @@ -100,11 +94,7 @@ #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else #define MYSERIAL2 MSERIAL(1) // dummy port - #if NUM_UARTS == 5 - #error "SERIAL_PORT_2 must be from 1 to 5. You can also use -1 if the board supports Native USB." - #else - #error "SERIAL_PORT_2 must be from 1 to 3. You can also use -1 if the board supports Native USB." - #endif + static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #endif @@ -115,11 +105,7 @@ #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) #else #define MMU2_SERIAL MSERIAL(1) // dummy port - #if NUM_UARTS == 5 - #error "MMU2_SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB." - #else - #error "MMU2_SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB." - #endif + static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #endif @@ -130,11 +116,7 @@ #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else #define LCD_SERIAL MSERIAL(1) // dummy port - #if NUM_UARTS == 5 - #error "LCD_SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB." - #else - #error "LCD_SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB." - #endif + static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #if HAS_DGUS_LCD #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 52904465be..8baa7936f5 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -68,6 +68,8 @@ extern USBSerialType USBSerial; #elif WITHIN(SERIAL_PORT, 0, 3) DECLARE_SERIAL(SERIAL_PORT); #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#else + #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif #define HAL_SERVO_LIB libServo diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 842a2b02c5..2628b3d2e5 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -87,16 +87,12 @@ extern uint8_t marlin_debug_flags; // If we have a catchall, use that directly #ifdef SERIAL_CATCHALL #define _SERIAL_LEAF_2 SERIAL_CATCHALL + #elif HAS_ETHERNET + typedef ConditionalSerial SerialLeafT2; // We need to create an instance here + extern SerialLeafT2 msSerial2; + #define _SERIAL_LEAF_2 msSerial2 #else - #if HAS_ETHERNET - // We need to create an instance here - typedef ConditionalSerial SerialLeafT2; - extern SerialLeafT2 msSerial2; - #define _SERIAL_LEAF_2 msSerial2 - #else - // Don't create a useless instance here, directly use the existing instance - #define _SERIAL_LEAF_2 MYSERIAL2 - #endif + #define _SERIAL_LEAF_2 MYSERIAL2 // Don't create a useless instance here, directly use the existing instance #endif // Hook Meatpack if it's enabled on the second leaf diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 67a6ce86e1..d5bb3e68db 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1949,7 +1949,6 @@ #undef _SERIAL_ID #undef _TMC_UART_IS #undef TMC_UART_IS -#undef CONF_SERIAL_IS #undef ANY_SERIAL_IS // diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 72e31b7b25..0c55232969 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -45,34 +45,22 @@ // manually add pins that have names that are macros which don't play well with these macros #if ANY(AVR_ATmega2560_FAMILY, AVR_ATmega1284_FAMILY, ARDUINO_ARCH_SAM, TARGET_LPC1768) - #if SERIAL_PORT == 0 + #if CONF_SERIAL_IS(0) static const char RXD_NAME_0[] PROGMEM = { "RXD0" }; static const char TXD_NAME_0[] PROGMEM = { "TXD0" }; - #elif SERIAL_PORT == 1 + #endif + #if CONF_SERIAL_IS(1) static const char RXD_NAME_1[] PROGMEM = { "RXD1" }; static const char TXD_NAME_1[] PROGMEM = { "TXD1" }; - #elif SERIAL_PORT == 2 + #endif + #if CONF_SERIAL_IS(2) static const char RXD_NAME_2[] PROGMEM = { "RXD2" }; static const char TXD_NAME_2[] PROGMEM = { "TXD2" }; - #elif SERIAL_PORT == 3 + #endif + #if CONF_SERIAL_IS(3) static const char RXD_NAME_3[] PROGMEM = { "RXD3" }; static const char TXD_NAME_3[] PROGMEM = { "TXD3" }; #endif - #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == 0 - static const char RXD_NAME_0[] PROGMEM = { "RXD0" }; - static const char TXD_NAME_0[] PROGMEM = { "TXD0" }; - #elif SERIAL_PORT_2 == 1 - static const char RXD_NAME_1[] PROGMEM = { "RXD1" }; - static const char TXD_NAME_1[] PROGMEM = { "TXD1" }; - #elif SERIAL_PORT_2 == 2 - static const char RXD_NAME_2[] PROGMEM = { "RXD2" }; - static const char TXD_NAME_2[] PROGMEM = { "TXD2" }; - #elif SERIAL_PORT_2 == 3 - static const char RXD_NAME_3[] PROGMEM = { "RXD3" }; - static const char TXD_NAME_3[] PROGMEM = { "TXD3" }; - #endif - #endif #endif ///////////////////////////////////////////////////////////////////////////// @@ -103,12 +91,11 @@ const PinInfo pin_array[] PROGMEM = { * Each entry takes up 6 bytes in FLASH: * 2 byte pointer to location of the name string * 2 bytes containing the pin number - * analog pin numbers were convereted to digital when the array was created + * analog pin numbers were converted to digital when the array was created * 2 bytes containing the digital/analog bool flag */ - // manually add pins ... - #if SERIAL_PORT == 0 + #if CONF_SERIAL_IS(0) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, @@ -119,7 +106,9 @@ const PinInfo pin_array[] PROGMEM = { { RXD_NAME_0, 3, true }, { TXD_NAME_0, 2, true }, #endif - #elif SERIAL_PORT == 1 + #endif + + #if CONF_SERIAL_IS(1) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, @@ -135,7 +124,9 @@ const PinInfo pin_array[] PROGMEM = { { TXD_NAME_1, 15, true }, #endif #endif - #elif SERIAL_PORT == 2 + #endif + + #if CONF_SERIAL_IS(2) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, @@ -148,7 +139,9 @@ const PinInfo pin_array[] PROGMEM = { { TXD_NAME_2, 10, true }, #endif #endif - #elif SERIAL_PORT == 3 + #endif + + #if CONF_SERIAL_IS(3) #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, @@ -166,68 +159,8 @@ const PinInfo pin_array[] PROGMEM = { #endif #endif - #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == 0 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_0, 0, true }, - { TXD_NAME_0, 1, true }, - #elif AVR_ATmega1284_FAMILY - { RXD_NAME_0, 8, true }, - { TXD_NAME_0, 9, true }, - #elif defined(TARGET_LPC1768) // TX P0_02 RX P0_03 - { RXD_NAME_0, 3, true }, - { TXD_NAME_0, 2, true }, - #endif - #elif SERIAL_PORT_2 == 1 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_1, 19, true }, - { TXD_NAME_1, 18, true }, - #elif AVR_ATmega1284_FAMILY - { RXD_NAME_1, 10, true }, - { TXD_NAME_1, 11, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART1_P2_00 // TX P2_00 RX P2_01 - { RXD_NAME_1, 0x41, true }, - { TXD_NAME_1, 0x40, true }, - #else // TX P0_15 RX P0_16 - { RXD_NAME_1, 16, true }, - { TXD_NAME_1, 15, true }, - #endif - #endif - #elif SERIAL_PORT_2 == 2 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_2, 17, true }, - { TXD_NAME_2, 16, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART2_P2_08 // TX P2_08 RX P2_09 - { RXD_NAME_2, 0x49, true }, - { TXD_NAME_2, 0x48, true }, - #else // TX P0_10 RX P0_11 - { RXD_NAME_2, 11, true }, - { TXD_NAME_2, 10, true }, - #endif - #endif - #elif SERIAL_PORT_2 == 3 - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) - { RXD_NAME_3, 15, true }, - { TXD_NAME_3, 14, true }, - #elif defined(TARGET_LPC1768) - #ifdef LPC_PINCFG_UART3_P0_25 // TX P0_25 RX P0_26 - { RXD_NAME_3, 0x1A, true }, - { TXD_NAME_3, 0x19, true }, - #elif defined(LPC_PINCFG_UART3_P4_28) // TX P4_28 RX P4_29 - { RXD_NAME_3, 0x9D, true }, - { TXD_NAME_3, 0x9C, true }, - #else // TX P0_00 RX P0_01 - { RXD_NAME_3, 1, true }, - { TXD_NAME_3, 0, true }, - #endif - #endif - #endif - #endif - #include "pinsDebug_list.h" - #line 231 + #line 164 }; From 02405add76e722701ab49434549e7d8bf5690162 Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 7 May 2021 17:31:45 +1200 Subject: [PATCH 0058/2168] Support a third serial port (#21784) --- Marlin/Configuration.h | 7 ++ Marlin/src/HAL/AVR/HAL.h | 7 ++ Marlin/src/HAL/AVR/MarlinSerial.cpp | 16 ++++ Marlin/src/HAL/AVR/MarlinSerial.h | 5 ++ Marlin/src/HAL/DUE/HAL.h | 10 +++ Marlin/src/HAL/DUE/MarlinSerial.cpp | 5 ++ Marlin/src/HAL/DUE/MarlinSerial.h | 5 ++ Marlin/src/HAL/DUE/MarlinSerialUSB.cpp | 3 + Marlin/src/HAL/DUE/MarlinSerialUSB.h | 4 + Marlin/src/HAL/LPC1768/HAL.h | 10 +++ Marlin/src/HAL/STM32/HAL.h | 10 +++ Marlin/src/HAL/STM32F1/HAL.h | 11 +++ Marlin/src/MarlinCore.cpp | 5 ++ Marlin/src/core/serial.cpp | 12 ++- Marlin/src/core/serial.h | 21 ++++- Marlin/src/core/serial_hook.h | 109 +++++++++++++++---------- Marlin/src/inc/Conditionals_LCD.h | 8 +- Marlin/src/inc/Conditionals_post.h | 1 + Marlin/src/inc/SanityCheck.h | 8 ++ buildroot/tests/LPC1768 | 2 +- 20 files changed, 212 insertions(+), 47 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d6a7456ccf..e1f9a4be70 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -111,6 +111,13 @@ */ //#define SERIAL_PORT_2 -1 +/** + * Select a third serial port on the board to use for communication with the host. + * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_3 1 + /** * This setting determines the communication speed of the printer. * diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 64e4f764dc..e24b923ef0 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -103,6 +103,13 @@ typedef int8_t pin_t; #endif #define MYSERIAL2 customizedSerial2 #endif + + #ifdef SERIAL_PORT_3 + #if !WITHIN(SERIAL_PORT_3, -1, 3) + #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." + #endif + #define MYSERIAL3 customizedSerial3 + #endif #endif #ifdef MMU2_SERIAL_PORT diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 82cdcfbe83..cd8bf5e690 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -585,6 +585,22 @@ MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser); #endif // SERIAL_PORT_2 +#ifdef SERIAL_PORT_3 + + // Hookup ISR handlers + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _RX_vect)) { + MarlinSerial>::store_rxd_char(); + } + + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); + } + + template class MarlinSerial< MarlinSerialCfg >; + MSerialT3 customizedSerial3(MSerialT3::HasEmergencyParser); + +#endif // SERIAL_PORT_3 + #ifdef MMU2_SERIAL_PORT ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _RX_vect)) { diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 26066d7208..0565c7b9db 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -246,6 +246,11 @@ extern MSerialT2 customizedSerial2; #endif + #ifdef SERIAL_PORT_3 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3; + extern MSerialT3 customizedSerial3; + #endif + #endif // !USBCON #ifdef MMU2_SERIAL_PORT diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 2fb927948c..92e26bcf43 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -68,6 +68,16 @@ extern DefaultSerial4 MSerial3; #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 || ENABLED(EMERGENCY_PARSER) + #define MYSERIAL3 customizedSerial3 + #elif WITHIN(SERIAL_PORT_3, 0, 3) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial." + #endif +#endif + #ifdef MMU2_SERIAL_PORT #if WITHIN(MMU2_SERIAL_PORT, 0, 3) #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 29d9ab0797..fe62ff5607 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -486,4 +486,9 @@ void MarlinSerial::flushTX() { MSerialT2 customizedSerial2(MarlinSerialCfg::EMERGENCYPARSER); #endif +#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0 + template class MarlinSerial< MarlinSerialCfg >; + MSerialT3 customizedSerial3(MarlinSerialCfg::EMERGENCYPARSER); +#endif + #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index 496e54c151..4a62e2834f 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -149,3 +149,8 @@ struct MarlinSerialCfg { typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT2; extern MSerialT2 customizedSerial2; #endif + +#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0 + typedef Serial1Class< MarlinSerial< MarlinSerialCfg > > MSerialT3; + extern MSerialT3 customizedSerial3; +#endif diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index fb5f013255..67c597da80 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -134,6 +134,9 @@ size_t MarlinSerialUSB::write(const uint8_t c) { #if SERIAL_PORT_2 == -1 MSerialT2 customizedSerial2(TERN0(EMERGENCY_PARSER, true)); #endif +#if SERIAL_PORT_3 == -1 + MSerialT3 customizedSerial3(TERN0(EMERGENCY_PARSER, true)); +#endif #endif // HAS_USB_SERIAL #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h index d19fc60eb6..6da1ef8c08 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.h +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.h @@ -59,3 +59,7 @@ struct MarlinSerialUSB { extern MSerialT2 customizedSerial2; #endif +#if SERIAL_PORT_3 == -1 + typedef Serial1Class MSerialT3; + extern MSerialT3 customizedSerial3; +#endif diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index bcfa6c412f..85e8933920 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -84,6 +84,16 @@ extern DefaultSerial1 USBSerial; #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 USBSerial + #elif WITHIN(SERIAL_PORT_3, 0, 3) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 3. You can also use -1 if the board supports Native USB." + #endif +#endif + #ifdef MMU2_SERIAL_PORT #if MMU2_SERIAL_PORT == -1 #define MMU2_SERIAL USBSerial diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 8ac9e6bd80..2441c46eab 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -68,6 +68,16 @@ #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 MSerial0 + #elif WITHIN(SERIAL_PORT_3, 1, 6) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 1 to 6. You can also use -1 if the board supports Native USB." + #endif +#endif + #ifdef MMU2_SERIAL_PORT #if MMU2_SERIAL_PORT == -1 #define MMU2_SERIAL MSerial0 diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 8b306f48fa..b3d8dc9d0b 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -98,6 +98,17 @@ #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 UsbSerial + #elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #define MYSERIAL3 MSERIAL(1) // dummy port + static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") + #endif +#endif + #ifdef MMU2_SERIAL_PORT #if MMU2_SERIAL_PORT == -1 #define MMU2_SERIAL UsbSerial diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 053256b743..2794b80695 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1075,6 +1075,11 @@ void setup() { MYSERIAL2.begin(BAUDRATE); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL2.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #ifdef SERIAL_PORT_3 + MYSERIAL3.begin(BAUDRATE); + serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL3.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #endif #endif SERIAL_ECHOLNPGM("start"); diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 8af367c801..28442594ce 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -44,6 +44,9 @@ PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMST #if ENABLED(MEATPACK_ON_SERIAL_PORT_2) SerialLeafT2 mpSerial2(false, _SERIAL_LEAF_2); #endif +#if ENABLED(MEATPACK_ON_SERIAL_PORT_3) + SerialLeafT3 mpSerial3(false, _SERIAL_LEAF_3); +#endif // Step 2: For multiserial, handle the second serial port as well #if HAS_MULTI_SERIAL @@ -52,7 +55,14 @@ PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMST SerialLeafT2 msSerial2(ethernet.have_telnet_client, MYSERIAL2, false); #endif - SerialOutputT multiSerial(SERIAL_LEAF_1, SERIAL_LEAF_2); + #define __S_LEAF(N) ,SERIAL_LEAF_##N + #define _S_LEAF(N) __S_LEAF(N) + + SerialOutputT multiSerial( SERIAL_LEAF_1 REPEAT_S(2, INCREMENT(NUM_SERIAL), _S_LEAF) ); + + #undef __S_LEAF + #undef _S_LEAF + #endif void serialprintPGM(PGM_P str) { diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 2628b3d2e5..4565a7fc87 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -95,6 +95,9 @@ extern uint8_t marlin_debug_flags; #define _SERIAL_LEAF_2 MYSERIAL2 // Don't create a useless instance here, directly use the existing instance #endif + // Nothing complicated here + #define _SERIAL_LEAF_3 MYSERIAL3 + // Hook Meatpack if it's enabled on the second leaf #if ENABLED(MEATPACK_ON_SERIAL_PORT_2) typedef MeatpackSerial SerialLeafT2; @@ -104,7 +107,23 @@ extern uint8_t marlin_debug_flags; #define SERIAL_LEAF_2 _SERIAL_LEAF_2 #endif - typedef MultiSerial SerialOutputT; + // Hook Meatpack if it's enabled on the third leaf + #if ENABLED(MEATPACK_ON_SERIAL_PORT_3) + typedef MeatpackSerial SerialLeafT3; + extern SerialLeafT3 mpSerial3; + #define SERIAL_LEAF_3 mpSerial3 + #else + #define SERIAL_LEAF_3 _SERIAL_LEAF_3 + #endif + + #define __S_MULTI(N) decltype(SERIAL_LEAF_##N), + #define _S_MULTI(N) __S_MULTI(N) + + typedef MultiSerial< REPEAT_S(1, INCREMENT(NUM_SERIAL), _S_MULTI) 0> SerialOutputT; + + #undef __S_MULTI + #undef _S_MULTI + extern SerialOutputT multiSerial; #define SERIAL_IMPL multiSerial #else diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 45cdcd35ed..d56cb55a66 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -195,54 +195,71 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial >, public Seria RuntimeSerial(const bool e, Args... args) : BaseClassT(e), SerialT(args...), writeHook(0), eofHook(0), userPointer(0) {} }; -// A class that duplicates its output conditionally to 2 serial interfaces -template -struct MultiSerial : public SerialBase< MultiSerial > { - typedef SerialBase< MultiSerial > BaseClassT; +#define _S_CLASS(N) class Serial##N##T, +#define _S_NAME(N) Serial##N##T, + +template < REPEAT(NUM_SERIAL, _S_CLASS) const uint8_t offset=0, const uint8_t step=1 > +struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > { + typedef SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > BaseClassT; + + #undef _S_CLASS + #undef _S_NAME SerialMask portMask; - Serial0T & serial0; - Serial1T & serial1; - static constexpr uint8_t Usage = ((1 << step) - 1); // A bit mask containing as many bits as step - static constexpr uint8_t FirstOutput = (Usage << offset); - static constexpr uint8_t SecondOutput = (Usage << (offset + step)); - static constexpr uint8_t Both = FirstOutput | SecondOutput; + #define _S_DECLARE(N) Serial##N##T & serial##N; + REPEAT(NUM_SERIAL, _S_DECLARE); + #undef _S_DECLARE + + static constexpr uint8_t Usage = _BV(step) - 1; // A bit mask containing 'step' bits + + #define _OUT_PORT(N) (Usage << (offset + (step * N))), + static constexpr uint8_t output[] = { REPEAT(NUM_SERIAL, _OUT_PORT) }; + #undef _OUT_PORT + + #define _OUT_MASK(N) | output[N] + static constexpr uint8_t ALL = 0 REPEAT(NUM_SERIAL, _OUT_MASK); + #undef _OUT_MASK NO_INLINE void write(uint8_t c) { - if (portMask.enabled(FirstOutput)) serial0.write(c); - if (portMask.enabled(SecondOutput)) serial1.write(c); + #define _S_WRITE(N) if (portMask.enabled(output[N])) serial##N.write(c); + REPEAT(NUM_SERIAL, _S_WRITE); + #undef _S_WRITE } NO_INLINE void msgDone() { - if (portMask.enabled(FirstOutput)) serial0.msgDone(); - if (portMask.enabled(SecondOutput)) serial1.msgDone(); + #define _S_DONE(N) if (portMask.enabled(output[N])) serial##N.msgDone(); + REPEAT(NUM_SERIAL, _S_DONE); + #undef _S_DONE } int available(serial_index_t index) { - if (index.within(0 + offset, step + offset - 1)) - return serial0.available(index); - else if (index.within(step + offset, 2 * step + offset - 1)) - return serial1.available(index); + uint8_t pos = offset; + #define _S_AVAILABLE(N) if (index.within(pos, pos + step - 1)) return serial##N.available(index); else pos += step; + REPEAT(NUM_SERIAL, _S_AVAILABLE); + #undef _S_AVAILABLE return false; } int read(serial_index_t index) { - if (index.within(0 + offset, step + offset - 1)) - return serial0.read(index); - else if (index.within(step + offset, 2 * step + offset - 1)) - return serial1.read(index); + uint8_t pos = offset; + #define _S_READ(N) if (index.within(pos, pos + step - 1)) return serial##N.read(index); else pos += step; + REPEAT(NUM_SERIAL, _S_READ); + #undef _S_READ return -1; } void begin(const long br) { - if (portMask.enabled(FirstOutput)) serial0.begin(br); - if (portMask.enabled(SecondOutput)) serial1.begin(br); + #define _S_BEGIN(N) if (portMask.enabled(output[N])) serial##N.begin(br); + REPEAT(NUM_SERIAL, _S_BEGIN); + #undef _S_BEGIN } void end() { - if (portMask.enabled(FirstOutput)) serial0.end(); - if (portMask.enabled(SecondOutput)) serial1.end(); + #define _S_END(N) if (portMask.enabled(output[N])) serial##N.end(); + REPEAT(NUM_SERIAL, _S_END); + #undef _S_END } bool connected() { bool ret = true; - if (portMask.enabled(FirstOutput)) ret = CALL_IF_EXISTS(bool, &serial0, connected); - if (portMask.enabled(SecondOutput)) ret = ret && CALL_IF_EXISTS(bool, &serial1, connected); + #define _S_CONNECTED(N) if (portMask.enabled(output[N]) && !CALL_IF_EXISTS(bool, &serial##N, connected)) ret = false; + REPEAT(NUM_SERIAL, _S_CONNECTED); + #undef _S_CONNECTED return ret; } @@ -250,27 +267,32 @@ struct MultiSerial : public SerialBase< MultiSerial= 3 + #define Serial3Class ConditionalSerial + #endif #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index d767000501..afec2c2b44 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -955,15 +955,19 @@ // Serial Port Info // #ifdef SERIAL_PORT_2 - #define NUM_SERIAL 2 #define HAS_MULTI_SERIAL 1 + #ifdef SERIAL_PORT_3 + #define NUM_SERIAL 3 + #else + #define NUM_SERIAL 2 + #endif #elif defined(SERIAL_PORT) #define NUM_SERIAL 1 #else #define NUM_SERIAL 0 #undef BAUD_RATE_GCODE #endif -#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 +#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 || SERIAL_PORT_3 == -1 #define HAS_USB_SERIAL 1 #endif #if SERIAL_PORT_2 == -2 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d5bb3e68db..c237e6edd9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1859,6 +1859,7 @@ // Flag the indexed hardware serial ports in use #define CONF_SERIAL_IS(N) ( (defined(SERIAL_PORT) && SERIAL_PORT == N) \ || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == N) \ + || (defined(SERIAL_PORT_3) && SERIAL_PORT_3 == N) \ || (defined(MMU2_SERIAL_PORT) && MMU2_SERIAL_PORT == N) \ || (defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT == N) ) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 6959e07f12..2cc90e0e8b 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -607,6 +607,14 @@ #error "SERIAL_PORT must be defined." #elif defined(SERIAL_PORT_2) && SERIAL_PORT_2 == SERIAL_PORT #error "SERIAL_PORT_2 cannot be the same as SERIAL_PORT." +#elif defined(SERIAL_PORT_3) + #ifndef SERIAL_PORT_2 + #error "Use SERIAL_PORT_2 before using SERIAL_PORT_3" + #elif SERIAL_PORT_3 == SERIAL_PORT + #error "SERIAL_PORT_3 cannot be the same as SERIAL_PORT." + #elif SERIAL_PORT_3 == SERIAL_PORT_2 + #error "SERIAL_PORT_3 cannot be the same as SERIAL_PORT_2." + #endif #endif #if !(defined(__AVR__) && defined(USBCON)) #if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024 diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 6b9f6aaac3..92fda54483 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -14,7 +14,7 @@ set -e #exec_test $1 $2 "Default Configuration" "$3" restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB NEOPIXEL_PIN P1_16 +opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB NEOPIXEL_PIN P1_16 SERIAL_PORT_3 3 opt_enable VIKI2 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 NEOPIXEL_LED exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3" From 4428affc20eb5ab99a4c0855919f26e5dad1fa1f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 May 2021 00:55:39 -0500 Subject: [PATCH 0059/2168] Let M421 C select any point Fixing #21147 --- Marlin/src/feature/bedlevel/ubl/ubl.h | 2 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 ++-- Marlin/src/gcode/bedlevel/ubl/M421.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 0a758a57e9..562f15f74b 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -32,7 +32,7 @@ #define UBL_OK false #define UBL_ERR true -enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP }; +enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP, CLOSEST }; // External references diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 361f3f1285..6130123f7a 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1282,7 +1282,7 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { static bool test_func(uint8_t i, uint8_t j, void *data) { find_closest_t *d = (find_closest_t*)data; - if ( (d->type == (isnan(ubl.z_values[i][j]) ? INVALID : REAL)) + if ( d->type == CLOSEST || d->type == (isnan(ubl.z_values[i][j]) ? INVALID : REAL) || (d->type == SET_IN_BITMAP && !d->done_flags->marked(i, j)) ) { // Found a Mesh Point of the specified type! @@ -1326,7 +1326,7 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh float best_so_far = 99999.99f; GRID_LOOP(i, j) { - if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL)) + if ( type == CLOSEST || 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! diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index 600c1fc8ba..45c203aaca 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -54,7 +54,7 @@ void GcodeSuite::M421() { hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); - if (hasC) ij = ubl.find_closest_mesh_point_of_type(REAL, current_position); + if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position); if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN)) SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS); From 8fd4bfc0e7fbc27cbd218a68435ca2f20726f111 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 8 May 2021 00:57:21 +0000 Subject: [PATCH 0060/2168] [cron] Bump distribution date (2021-05-08) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2ab6071ac1..572722416f 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 "2021-05-07" + #define STRING_DISTRIBUTION_DATE "2021-05-08" #endif /** From 9f7177c67dc7979ae69c0068ae9a1ece9bc7102c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 May 2021 22:36:36 -0500 Subject: [PATCH 0061/2168] Misc Power Loss cleanup --- Marlin/src/feature/powerloss.cpp | 27 ++++++++++++--------------- Marlin/src/feature/powerloss.h | 5 +++++ 2 files changed, 17 insertions(+), 15 deletions(-) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 10488af709..3736cac453 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -66,9 +66,6 @@ PrintJobRecovery recovery; #ifndef POWER_LOSS_PURGE_LEN #define POWER_LOSS_PURGE_LEN 0 #endif -#ifndef POWER_LOSS_ZRAISE - #define POWER_LOSS_ZRAISE 2 // Move on loss with backup power, or on resume without it -#endif #if DISABLED(BACKUP_POWER_SUPPLY) #undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power @@ -256,7 +253,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ // Raise the Z axis now if (zraise) { char cmd[20], str_1[16]; - sprintf_P(cmd, PSTR("G0 Z%s"), dtostrf(zraise, 1, 3, str_1)); + sprintf_P(cmd, PSTR("G0Z%s"), dtostrf(zraise, 1, 3, str_1)); gcode.process_subcommands_now(cmd); } #else @@ -348,7 +345,7 @@ void PrintJobRecovery::resume() { const celsius_t bt = info.target_temperature_bed; if (bt) { // Restore the bed temperature - sprintf_P(cmd, PSTR("M190 S%i"), bt); + sprintf_P(cmd, PSTR("M190S%i"), bt); gcode.process_subcommands_now(cmd); } #endif @@ -359,10 +356,10 @@ void PrintJobRecovery::resume() { const celsius_t et = info.target_temperature[e]; if (et) { #if HAS_MULTI_HOTEND - sprintf_P(cmd, PSTR("T%i S"), e); + sprintf_P(cmd, PSTR("T%iS"), e); gcode.process_subcommands_now(cmd); #endif - sprintf_P(cmd, PSTR("M109 S%i"), et); + sprintf_P(cmd, PSTR("M109S%i"), et); gcode.process_subcommands_now(cmd); } } @@ -370,7 +367,7 @@ void PrintJobRecovery::resume() { // // Home the axes that can safely be homed, and - // establish the current position as best we can + // establish the current position as best we can. // #if Z_HOME_DIR > 0 @@ -380,7 +377,7 @@ void PrintJobRecovery::resume() { "G28R0" // Home all axes (no raise) )); - #else // "G92.9 E0 ..." + #else // If a Z raise occurred at outage restore Z, otherwise raise Z now sprintf_P(cmd, PSTR("G92.9 E0 " TERN(BACKUP_POWER_SUPPLY, "Z%s", "Z0\nG1Z%s")), dtostrf(info.zraise, 1, 3, str_1)); @@ -475,7 +472,7 @@ void PrintJobRecovery::resume() { // Un-retract if there was a retract at outage #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 - gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_RETRACT_LEN) " F3000")); + gcode.process_subcommands_now_P(PSTR("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000")); #endif // Additional purge on resume if configured @@ -488,8 +485,8 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR("G12")); #endif - // Move back to the saved XY - sprintf_P(cmd, PSTR("G1 X%s Y%s F3000"), + // Move back over to the saved XY + sprintf_P(cmd, PSTR("G1X%sY%sF3000"), dtostrf(info.current_position.x, 1, 3, str_1), dtostrf(info.current_position.y, 1, 3, str_2) ); @@ -506,11 +503,11 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now(cmd); // Restore the feedrate - sprintf_P(cmd, PSTR("G1 F%d"), info.feedrate); + sprintf_P(cmd, PSTR("G1F%d"), info.feedrate); gcode.process_subcommands_now(cmd); // Restore E position with G92.9 - sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); + sprintf_P(cmd, PSTR("G92.9E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); gcode.process_subcommands_now(cmd); TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat); @@ -535,7 +532,7 @@ void PrintJobRecovery::resume() { char *fn = info.sd_filename; sprintf_P(cmd, M23_STR, fn); gcode.process_subcommands_now(cmd); - sprintf_P(cmd, PSTR("M24 S%ld T%ld"), resume_sdpos, info.print_job_elapsed); + sprintf_P(cmd, PSTR("M24S%ldT%ld"), resume_sdpos, info.print_job_elapsed); gcode.process_subcommands_now(cmd); TERN_(DEBUG_POWER_LOSS_RECOVERY, marlin_debug_flags = old_flags); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 0777466cc1..03e467432c 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -42,6 +42,10 @@ #define POWER_LOSS_STATE HIGH #endif +#ifndef POWER_LOSS_ZRAISE + #define POWER_LOSS_ZRAISE 2 +#endif + //#define DEBUG_POWER_LOSS_RECOVERY //#define SAVE_EACH_CMD_MODE //#define SAVE_INFO_INTERVAL_MS 0 @@ -52,6 +56,7 @@ typedef struct { // Machine state xyze_pos_t current_position; uint16_t feedrate; + float zraise; // Repeat information From 1292ff76b34c15cf6bc78259985440e13b5cb1f8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 May 2021 22:37:31 -0500 Subject: [PATCH 0062/2168] Debounce for Power-Loss pin --- Marlin/src/feature/powerloss.h | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 03e467432c..df3ae222a2 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -186,8 +186,14 @@ class PrintJobRecovery { #if PIN_EXISTS(POWER_LOSS) static inline void outage() { - if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) - _outage(); + static constexpr uint8_t OUTAGE_THRESHOLD = 3; + static uint8_t outage_counter = 0; + if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) { + outage_counter++; + if (outage_counter >= OUTAGE_THRESHOLD) _outage(); + } + else + outage_counter = 0; } #endif From 206d495ba4235a79db158fe6687e301bb055623f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 May 2021 22:39:34 -0500 Subject: [PATCH 0063/2168] Misc. code cleanup --- Marlin/src/MarlinCore.cpp | 4 ++-- Marlin/src/gcode/queue.cpp | 10 +++------- Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 4 +--- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 12 ++++-------- 5 files changed, 12 insertions(+), 22 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 2794b80695..78a881a1d8 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -390,8 +390,8 @@ void startOrResumeJob() { } inline void finishSDPrinting() { - if (queue.enqueue_one_P(PSTR("M1001"))) { - marlin_state = MF_RUNNING; + if (queue.enqueue_one_P(PSTR("M1001"))) { // Keep trying until it gets queued + marlin_state = MF_RUNNING; // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished()); } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 319ebe8a17..47b7d1febb 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -501,13 +501,9 @@ void GCodeQueue::get_serial_commands() { char* gpos = strchr(command, 'G'); if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { - case 0: case 1: - #if ENABLED(ARC_SUPPORT) - case 2: case 3: - #endif - #if ENABLED(BEZIER_CURVE_SUPPORT) - case 5: - #endif + case 0 ... 1: + TERN_(ARC_SUPPORT, case 2 ... 3:) + TERN_(BEZIER_CURVE_SUPPORT, case 5:) PORT_REDIRECT(SERIAL_PORTMASK(p)); // Reply to the serial port that sent the command SERIAL_ECHOLNPGM(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index d31a1dcacd..c502d0ae27 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -1477,7 +1477,7 @@ void DGUSScreenHandler::DGUS_ExtrudeLoadInit(void) { void DGUSScreenHandler::DGUS_RunoutInit(void) { #if PIN_EXISTS(MT_DET_1) - pinMode(MT_DET_1_PIN, INPUT_PULLUP); + SET_INPUT_PULLUP(MT_DET_1_PIN); #endif runout_mks.de_count = 0; runout_mks.de_times = 10; @@ -1496,7 +1496,7 @@ void DGUSScreenHandler::DGUS_Runout_Idle(void) { GotoScreen(MKSLCD_SCREEN_PAUSE); sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please change filament!"), nullptr, true, true, true, true); - // SetupConfirmAction(nullptr); + //SetupConfirmAction(nullptr); GotoScreen(DGUSLCD_SCREEN_POPUP); break; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index c5ae77dd61..4134759b75 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -645,9 +645,7 @@ char *creat_title_text() { gcode_preview_over = false; card.closefile(); - char *cur_name; - - cur_name = strrchr(list_file.file_name[sel_id], '/'); + char *cur_name = strrchr(list_file.file_name[sel_id], '/'); SdFile file; SdFile *curDir; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 897137d013..1e3262be3b 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -1789,18 +1789,14 @@ void get_wifi_commands() { char* command = wifi_line_buffer; while (*command == ' ') command++; // skip any leading spaces - // Movement commands alert when stopped - if (IsStopped()) { + // Movement commands alert when stopped + if (IsStopped()) { char* gpos = strchr(command, 'G'); if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { case 0 ... 1: - #if ENABLED(ARC_SUPPORT) - case 2 ... 3: - #endif - #if ENABLED(BEZIER_CURVE_SUPPORT) - case 5: - #endif + TERN_(ARC_SUPPORT, case 2 ... 3:) + TERN_(BEZIER_CURVE_SUPPORT, case 5:) SERIAL_ECHOLNPGM(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); break; From a03811f4e8bcc794c02108ec8a33edc071221187 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 May 2021 22:54:06 -0500 Subject: [PATCH 0064/2168] Update MF states --- Marlin/src/MarlinCore.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index d43d46bbd8..d016151c2d 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -56,18 +56,18 @@ void minkill(const bool steppers_off=false); // Global State of the firmware enum MarlinState : uint8_t { - MF_INITIALIZING = 0, - MF_RUNNING = _BV(0), - MF_PAUSED = _BV(1), - MF_WAITING = _BV(2), - MF_STOPPED = _BV(3), - MF_SD_COMPLETE = _BV(4), - MF_KILLED = _BV(7) + MF_INITIALIZING = 0, + MF_STOPPED, + MF_KILLED, + MF_RUNNING, + MF_SD_COMPLETE, + MF_PAUSED, + MF_WAITING, }; extern MarlinState marlin_state; -inline bool IsRunning() { return marlin_state == MF_RUNNING; } -inline bool IsStopped() { return marlin_state != MF_RUNNING; } +inline bool IsRunning() { return marlin_state >= MF_RUNNING; } +inline bool IsStopped() { return marlin_state == MF_STOPPED; } bool printingIsActive(); bool printingIsPaused(); From f09fa69e867d1cfb18cbad720a5c1e566cb1bab4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 01:41:40 -0500 Subject: [PATCH 0065/2168] Add and apply REPEAT_1 macro --- Marlin/src/core/macros.h | 1 + Marlin/src/core/serial.h | 2 +- Marlin/src/feature/runout.h | 2 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 6 ++++-- Marlin/src/lcd/marlinui.cpp | 4 ++-- Marlin/src/module/endstops.cpp | 2 +- 6 files changed, 10 insertions(+), 7 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 6092dc4a59..b026af1187 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -581,6 +581,7 @@ // Repeat a macro passing S...N-1. #define REPEAT_S(S,N,OP) EVAL(_REPEAT(S,SUB##S(N),OP)) #define REPEAT(N,OP) REPEAT_S(0,N,OP) +#define REPEAT_1(N,OP) REPEAT_S(1,INCREMENT(N),OP) // Repeat a macro passing 0...N-1 plus additional arguments. #define REPEAT2_S(S,N,OP,V...) EVAL(_REPEAT2(S,SUB##S(N),OP,V)) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 4565a7fc87..5406bb3a7d 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -119,7 +119,7 @@ extern uint8_t marlin_debug_flags; #define __S_MULTI(N) decltype(SERIAL_LEAF_##N), #define _S_MULTI(N) __S_MULTI(N) - typedef MultiSerial< REPEAT_S(1, INCREMENT(NUM_SERIAL), _S_MULTI) 0> SerialOutputT; + typedef MultiSerial< REPEAT_1(NUM_SERIAL, _S_MULTI) 0> SerialOutputT; #undef __S_MULTI #undef _S_MULTI diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 15bf607550..93eb59c2a5 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -207,7 +207,7 @@ class FilamentSensorBase { // Return a bitmask of runout pin states static inline uint8_t poll_runout_pins() { #define _OR_RUNOUT(N) | (READ(FIL_RUNOUT##N##_PIN) ? _BV((N) - 1) : 0) - return (0 REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _OR_RUNOUT)); + return (0 REPEAT_1(NUM_RUNOUT_SENSORS, _OR_RUNOUT)); #undef _OR_RUNOUT } diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 68b75900ef..681e8da01d 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -243,9 +243,11 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #endif #if STATUS_HOTEND_BITMAPS > 1 - static const unsigned char* const status_hotend_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = ARRAY_N(STATUS_HOTEND_BITMAPS, OFF_BMP(1), OFF_BMP(2), OFF_BMP(3), OFF_BMP(4), OFF_BMP(5), OFF_BMP(6)); + #define _OFF_BMP(N) OFF_BMP(N), + #define _ON_BMP(N) ON_BMP(N), + static const unsigned char* const status_hotend_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = { REPEAT_1(STATUS_HOTEND_BITMAPS, _OFF_BMP) }; #if ANIM_HOTEND - static const unsigned char* const status_hotend_on_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = ARRAY_N(STATUS_HOTEND_BITMAPS, ON_BMP(1), ON_BMP(2), ON_BMP(3), ON_BMP(4), ON_BMP(5), ON_BMP(6)); + static const unsigned char* const status_hotend_on_gfx[STATUS_HOTEND_BITMAPS] PROGMEM = { REPEAT_1(STATUS_HOTEND_BITMAPS, _ON_BMP) }; #define HOTEND_BITMAP(N,S) (unsigned char*)pgm_read_ptr((S) ? &status_hotend_on_gfx[(N) % (STATUS_HOTEND_BITMAPS)] : &status_hotend_gfx[(N) % (STATUS_HOTEND_BITMAPS)]) #else #define HOTEND_BITMAP(N,S) (unsigned char*)pgm_read_ptr(&status_hotend_gfx[(N) % (STATUS_HOTEND_BITMAPS)]) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1b517f7d21..f83d129b2f 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -114,8 +114,8 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; PGM_P MarlinUI::get_preheat_label(const uint8_t m) { #define _PDEF(N) static PGMSTR(preheat_##N##_label, PREHEAT_##N##_LABEL); #define _PLBL(N) preheat_##N##_label, - REPEAT_S(1, INCREMENT(PREHEAT_COUNT), _PDEF); - static PGM_P const preheat_labels[PREHEAT_COUNT] PROGMEM = { REPEAT_S(1, INCREMENT(PREHEAT_COUNT), _PLBL) }; + REPEAT_1(PREHEAT_COUNT, _PDEF); + static PGM_P const preheat_labels[PREHEAT_COUNT] PROGMEM = { REPEAT_1(PREHEAT_COUNT, _PLBL) }; return (PGM_P)pgm_read_ptr(&preheat_labels[m]); } #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index e11c4605e4..14c5f13367 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -475,7 +475,7 @@ void _O2 Endstops::report_states() { uint8_t state; switch (i) { default: continue; - REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _CASE_RUNOUT) + REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_RUNOUT) } SERIAL_ECHOPGM(STR_FILAMENT_RUNOUT_SENSOR); if (i > 1) SERIAL_CHAR(' ', '0' + i); From 01741576ebea06faa4ec98623a28eab19251f111 Mon Sep 17 00:00:00 2001 From: charlespick Date: Fri, 7 May 2021 23:44:34 -0700 Subject: [PATCH 0066/2168] Active MMU slot indicator (#21842) --- Marlin/src/lcd/dogm/status/hotend.h | 274 ++++++++++++++++++++- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 6 +- 2 files changed, 270 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/dogm/status/hotend.h b/Marlin/src/lcd/dogm/status/hotend.h index 4dddc42bee..3a6e02acb6 100644 --- a/Marlin/src/lcd/dogm/status/hotend.h +++ b/Marlin/src/lcd/dogm/status/hotend.h @@ -25,16 +25,21 @@ // lcd/dogm/status/hotend.h - Status Screen Hotends bitmaps // -#define STATUS_HOTEND1_WIDTH 16 - -#define MAX_HOTEND_BITMAPS 5 -#if HOTENDS > MAX_HOTEND_BITMAPS - #define STATUS_HOTEND_BITMAPS MAX_HOTEND_BITMAPS +#if HAS_MMU + #define STATUS_HOTEND_BITMAPS EXTRUDERS + #define MAX_HOTEND_BITMAPS 8 #else #define STATUS_HOTEND_BITMAPS HOTENDS + #define MAX_HOTEND_BITMAPS 5 +#endif +#if STATUS_HOTEND_BITMAPS > MAX_HOTEND_BITMAPS + #undef STATUS_HOTEND_BITMAPS + #define STATUS_HOTEND_BITMAPS MAX_HOTEND_BITMAPS #endif -#if HOTENDS == 1 || ENABLED(STATUS_HOTEND_NUMBERLESS) +#define STATUS_HOTEND1_WIDTH 16 + +#if STATUS_HOTEND_BITMAPS == 1 || ENABLED(STATUS_HOTEND_NUMBERLESS) const unsigned char status_hotend_a_bmp[] PROGMEM = { B00011111,B11100000, @@ -70,7 +75,7 @@ #endif -#elif HOTENDS >= 2 +#elif STATUS_HOTEND_BITMAPS > 1 #ifdef STATUS_HOTEND_ANIM @@ -483,4 +488,259 @@ #endif + #if STATUS_HOTEND_BITMAPS >= 6 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend6_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B11110000, + B00011000,B11100000, + B00011111,B01100000, + B00111111,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111100,B01110000, + B00111011,B11110000, + B00011011,B11100000, + B00011000,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend6_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100111,B10010000, + B00100100,B00010000, + B00010111,B00100000, + B00010000,B10100000, + B00100000,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100011,B10010000, + B00100100,B00010000, + B00010100,B00100000, + B00010111,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend6_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B11110000, + B00111000,B11110000, + B00011111,B01100000, + B00011111,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111100,B01110000, + B00111011,B11110000, + B00111011,B11110000, + B00011000,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 7 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend7_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111100,B01110000, + B00111011,B11110000, + B00011011,B11100000, + B00011000,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111000,B01110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111110,B11110000, + B00111101,B11110000, + B00111101,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend7_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100011,B10010000, + B00100100,B00010000, + B00010100,B00100000, + B00010111,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #else + B00100111,B10010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100001,B00010000, + B00100010,B00010000, + B00110010,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend7_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111100,B01110000, + B00111011,B11110000, + B00111011,B11110000, + B00011000,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #else + B00111000,B01110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011110,B11100000, + B00111101,B11110000, + B00111101,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + + #if STATUS_HOTEND_BITMAPS >= 8 + + #ifdef STATUS_HOTEND_ANIM + + const unsigned char status_hotend8_a_bmp[] PROGMEM = { + B00011111,B11100000, + B00111111,B11110000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B01110000, + B00011111,B01100000, + B00011110,B11100000, + B00111110,B11110000, + B00111101,B11110000, + B00111101,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00011011,B01100000, + B00011100,B11100000, + B00111011,B01110000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + const unsigned char status_hotend8_b_bmp[] PROGMEM = { + B00011111,B11100000, + B00100000,B00010000, + #if LCD_FIRST_TOOL == 0 + B00100111,B10010000, + B00100100,B10010000, + B00010000,B10100000, + B00010001,B00100000, + B00100001,B00010000, + B00100010,B00010000, + B00110010,B00110000, + #else + B00100011,B00010000, + B00100100,B10010000, + B00010100,B10100000, + B00010011,B00100000, + B00100100,B10010000, + B00100100,B10010000, + B00110011,B00110000, + #endif + B00001000,B01000000, + B00000100,B10000000, + B00000011,B00000000 + }; + + #else + + const unsigned char status_hotend8_a_bmp[] PROGMEM = { + B00011111,B11100000, + #if LCD_FIRST_TOOL == 0 + B00111000,B01110000, + B00111011,B01110000, + B00111111,B01110000, + B00011110,B11100000, + B00011110,B11100000, + B00111101,B11110000, + B00111101,B11110000, + #else + B00111100,B11110000, + B00111011,B01110000, + B00111011,B01110000, + B00011100,B11100000, + B00011011,B01100000, + B00111011,B01110000, + B00111100,B11110000, + #endif + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + B00000011,B00000000 + }; + + #endif + + #endif + #endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 681e8da01d..33cb9575f1 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -274,12 +274,12 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #if ENABLED(STATUS_HEAT_PERCENT) if (isHeat && tall <= BAR_TALL) { const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(heater_id, false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(heater_id, true) + ph * bw); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); } else #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater_id, isHeat)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); #endif } // PAGE_CONTAINS From 57025b75e13f05ec53b9117c890f0e5a8db8d01e Mon Sep 17 00:00:00 2001 From: Adrian DC Date: Sat, 8 May 2021 08:46:21 +0200 Subject: [PATCH 0067/2168] Fix E3V2 Control Menu icon/text order (#21838) Fixes #21837 --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 36 ++++++++++++++++--------------- 1 file changed, 19 insertions(+), 17 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index dc729263db..620b267bd2 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -815,8 +815,6 @@ void Draw_Control_Menu() { if (CVISI(CONTROL_CASE_ADVSET)) { DWIN_Draw_Label(CLINE(CONTROL_CASE_ADVSET), GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // Advanced Settings - Draw_More_Icon(CSCROL(CONTROL_CASE_ADVSET)); - Draw_Menu_Line(CSCROL(CONTROL_CASE_ADVSET), ICON_AdvSet); } if (CVISI(CONTROL_CASE_INFO)) Item_Control_Info(CLINE(CONTROL_CASE_INFO)); @@ -825,23 +823,26 @@ void Draw_Control_Menu() { Draw_Menu_Cursor(CSCROL(select_control.now)); // Draw icons and lines - uint8_t i = 0; - #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_Temperature + (N) - 1); }while(0) + #define _TEMP_ICON(N, I, M) do { \ + if (CVISI(N)) { \ + Draw_Menu_Line(CSCROL(N), I); \ + if (M) { \ + Draw_More_Icon(CSCROL(N)); \ + } \ + } \ + } while(0) - _TEMP_ICON(CONTROL_CASE_TEMP); - if (CVISI(i)) Draw_More_Icon(CSCROL(i)); - - _TEMP_ICON(CONTROL_CASE_MOVE); - Draw_More_Icon(CSCROL(i)); + _TEMP_ICON(CONTROL_CASE_TEMP, ICON_Temperature, true); + _TEMP_ICON(CONTROL_CASE_MOVE, ICON_Motion, true); #if ENABLED(EEPROM_SETTINGS) - _TEMP_ICON(CONTROL_CASE_SAVE); - _TEMP_ICON(CONTROL_CASE_LOAD); - _TEMP_ICON(CONTROL_CASE_RESET); + _TEMP_ICON(CONTROL_CASE_SAVE, ICON_WriteEEPROM, false); + _TEMP_ICON(CONTROL_CASE_LOAD, ICON_ReadEEPROM, false); + _TEMP_ICON(CONTROL_CASE_RESET, ICON_ResumeEEPROM, false); #endif - _TEMP_ICON(CONTROL_CASE_INFO); - if (CVISI(CONTROL_CASE_INFO)) Draw_More_Icon(CSCROL(i)); + _TEMP_ICON(CONTROL_CASE_ADVSET, ICON_AdvSet, true); + _TEMP_ICON(CONTROL_CASE_INFO, ICON_Info, true); } void Draw_Tune_Menu() { @@ -2653,11 +2654,12 @@ void HMI_Control() { Scroll_Menu(DWIN_SCROLL_UP); switch (index_control) { // Last menu items - case CONTROL_CASE_ADVSET: // Advance Settings > + case CONTROL_CASE_ADVSET: // Advanced Settings > Draw_Menu_Item(MROWS, ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), true); break; case CONTROL_CASE_INFO: // Info > - Draw_Menu_Item(MROWS, ICON_Info, GET_TEXT(MSG_INFO_SCREEN), true); + Item_Control_Info(MBASE(MROWS)); + Draw_Menu_Icon(MROWS, ICON_Info); break; default: break; } @@ -2721,7 +2723,7 @@ void HMI_Control() { HMI_AudioFeedback(); break; #endif - case CONTROL_CASE_ADVSET: // Advance Settings + case CONTROL_CASE_ADVSET: // Advanced Settings checkkey = AdvSet; select_advset.reset(); Draw_AdvSet_Menu(); From b65cdbed91782c83188706a9c340de9c503cf430 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 04:35:35 -0500 Subject: [PATCH 0068/2168] Signal SD completion later (#21840) --- Marlin/src/MarlinCore.cpp | 18 ++---- Marlin/src/MarlinCore.h | 1 + Marlin/src/feature/pause.cpp | 2 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/gcode/queue.cpp | 3 +- Marlin/src/gcode/sd/M1001.cpp | 6 ++ Marlin/src/gcode/sd/M24_M25.cpp | 2 +- Marlin/src/gcode/sd/M27.cpp | 2 +- Marlin/src/gcode/sd/M32.cpp | 2 +- Marlin/src/gcode/sd/M524.cpp | 2 +- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 4 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 4 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 4 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 7 +- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 10 +-- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 8 +-- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 20 +++--- Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 22 ++----- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 64 +++++++++++-------- Marlin/src/sd/cardreader.h | 60 +++++++++++------ 23 files changed, 133 insertions(+), 116 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 78a881a1d8..85ee920e72 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -331,18 +331,14 @@ void disable_all_steppers() { } /** - * A Print Job exists when the timer is running or SD printing + * A Print Job exists when the timer is running or SD is printing */ -bool printJobOngoing() { - return print_job_timer.isRunning() || IS_SD_PRINTING(); -} +bool printJobOngoing() { return print_job_timer.isRunning() || IS_SD_PRINTING(); } /** - * Printing is active when the print job timer is running + * Printing is active when a job is underway but not paused */ -bool printingIsActive() { - return !did_pause_print && (print_job_timer.isRunning() || IS_SD_PRINTING()); -} +bool printingIsActive() { return !did_pause_print && printJobOngoing(); } /** * Printing is paused according to SD or host indicators @@ -367,7 +363,7 @@ void startOrResumeJob() { inline void abortSDPrinting() { IF_DISABLED(NO_SD_AUTOSTART, card.autofile_cancel()); - card.endFilePrint(TERN_(SD_RESORT, true)); + card.abortFilePrintNow(TERN_(SD_RESORT, true)); queue.clear(); quickstop_stepper(); @@ -748,7 +744,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) - if (printJobOngoing()) recovery.outage(); + if (IS_SD_PRINTING()) recovery.outage(); #endif // Run StallGuard endstop checks @@ -901,7 +897,7 @@ void stop() { thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif - if (IsRunning()) { + if (!IsStopped()) { SERIAL_ERROR_MSG(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); safe_delay(350); // allow enough time for messages to get out before stopping diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index d016151c2d..ce1b106bfa 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -70,6 +70,7 @@ inline bool IsRunning() { return marlin_state >= MF_RUNNING; } inline bool IsStopped() { return marlin_state == MF_STOPPED; } bool printingIsActive(); +bool printJobOngoing(); bool printingIsPaused(); void startOrResumeJob(); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 93b4a2aa81..58e0c3df0d 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -649,7 +649,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ #if ENABLED(SDSUPPORT) if (did_pause_print) { --did_pause_print; - card.startFileprint(); + card.startOrResumeFilePrinting(); // Write PLR now to update the z axis value TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 3736cac453..9d6e0b42f5 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -137,7 +137,7 @@ void PrintJobRecovery::load() { * Set info fields that won't change */ void PrintJobRecovery::prepare() { - card.getAbsFilename(info.sd_filename); // SD filename + card.getAbsFilenameInCWD(info.sd_filename); // SD filename cmd_sdpos = 0; } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 47b7d1febb..c007537398 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -550,7 +550,8 @@ void GCodeQueue::get_serial_commands() { inline void GCodeQueue::get_sdcard_commands() { static uint8_t sd_input_state = PS_NORMAL; - if (!IS_SD_PRINTING()) return; + // Get commands if there are more in the file + if (!IS_SD_FETCHING()) return; int sd_count = 0; while (!ring_buffer.full() && !card.eof()) { diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 415fbb6fa7..418e594deb 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -25,6 +25,7 @@ #if ENABLED(SDSUPPORT) #include "../gcode.h" +#include "../../module/planner.h" #include "../../module/printcounter.h" #if DISABLED(NO_SD_AUTOSTART) @@ -64,6 +65,11 @@ * M1001: Execute actions for SD print completion */ void GcodeSuite::M1001() { + planner.synchronize(); + + // SD Printing is finished when the queue reaches M1001 + card.flag.sdprinting = card.flag.sdprintdone = false; + // If there's another auto#.g file to run... if (TERN(NO_SD_AUTOSTART, false, card.autofile_check())) return; diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 89b166f908..f46a964af0 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -70,7 +70,7 @@ void GcodeSuite::M24() { #endif if (card.isFileOpen()) { - card.startFileprint(); // SD card will now be read for commands + card.startOrResumeFilePrinting(); // SD card will now be read for commands startOrResumeJob(); // Start (or resume) the print job timer TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); } diff --git a/Marlin/src/gcode/sd/M27.cpp b/Marlin/src/gcode/sd/M27.cpp index a76070fda8..f6e48d4ae8 100644 --- a/Marlin/src/gcode/sd/M27.cpp +++ b/Marlin/src/gcode/sd/M27.cpp @@ -35,7 +35,7 @@ void GcodeSuite::M27() { if (parser.seen('C')) { SERIAL_ECHOPGM("Current file: "); - card.printFilename(); + card.printSelectedFilename(); return; } diff --git a/Marlin/src/gcode/sd/M32.cpp b/Marlin/src/gcode/sd/M32.cpp index ea893c9232..3baa552e6e 100644 --- a/Marlin/src/gcode/sd/M32.cpp +++ b/Marlin/src/gcode/sd/M32.cpp @@ -49,7 +49,7 @@ void GcodeSuite::M32() { if (parser.seenval('S')) card.setIndex(parser.value_long()); - card.startFileprint(); + card.startOrResumeFilePrinting(); // Procedure calls count as normal print time. if (!call_procedure) startOrResumeJob(); diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp index 089d2e2f0c..e715915565 100644 --- a/Marlin/src/gcode/sd/M524.cpp +++ b/Marlin/src/gcode/sd/M524.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M524() { if (IS_SD_PRINTING()) - card.flag.abort_sd_printing = true; + card.abortFilePrintSoon(); else if (card.isMounted()) card.closefile(); diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 2e5f967c2f..85430c18b0 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -755,7 +755,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink) char buffer[14]; #if ENABLED(SHOW_REMAINING_TIME) - const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && (printingIsActive() || marlin_state == MF_SD_COMPLETE); + const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && printingIsActive(); if (show_remain) { #if ENABLED(USE_M73_REMAINING_TIME) duration_t remaining = ui.get_remaining_time(); @@ -889,7 +889,7 @@ void MarlinUI::draw_status_screen() { #else // !HAS_DUAL_MIXING - const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive() || marlin_state == MF_SD_COMPLETE); + const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive()); if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 33cb9575f1..010d9a6680 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -41,7 +41,7 @@ #include "../../gcode/parser.h" // for units (and volumetric) #if ENABLED(LCD_SHOW_E_TOTAL) - #include "../../MarlinCore.h" // for printingIsActive(), marlin_state and MF_SD_COMPLETE + #include "../../MarlinCore.h" // for printingIsActive() #endif #if ENABLED(FILAMENT_LCD_DISPLAY) @@ -464,7 +464,7 @@ void MarlinUI::draw_status_screen() { #endif #endif - const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive() || marlin_state == MF_SD_COMPLETE); + const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive()); // At the first page, generate new display values if (first_page) { diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 620b267bd2..76118d6814 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -1891,7 +1891,7 @@ void HMI_SDCardUpdate() { else if (checkkey == PrintProcess || checkkey == Tune || printingIsActive()) { // TODO: Move card removed abort handling // to CardReader::manage_media. - card.flag.abort_sd_printing = true; + card.abortFilePrintSoon(); wait_for_heatup = wait_for_user = false; dwin_abort_flag = true; // Reset feedrate, return to Home } @@ -2311,7 +2311,7 @@ void HMI_PauseOrStop() { checkkey = Back_Main; if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user - card.flag.abort_sd_printing = true; // Let the main loop handle SD abort + card.abortFilePrintSoon(); // Let the main loop handle SD abort dwin_abort_flag = true; // Reset feedrate, return to Home #ifdef ACTION_ON_CANCEL host_action_cancel(); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index c502d0ae27..c0b3b60a16 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -289,7 +289,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // if robin nano is printing. when it is, dgus will enter the printing // page to continue print; // - //if (print_job_timer.isRunning() || print_job_timer.isPaused()) { + //if (printJobOngoing() || printingIsPaused()) { // if (target == MKSLCD_PAUSE_SETTING_MOVE || target == MKSLCD_PAUSE_SETTING_EX // || target == MKSLCD_SCREEN_PRINT || target == MKSLCD_SCREEN_PAUSE // ) { @@ -324,7 +324,7 @@ void DGUSScreenHandler::ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr) { void DGUSScreenHandler::ZoffsetConfirm(DGUS_VP_Variable &var, void *val_ptr) { settings.save(); - if (print_job_timer.isRunning()) + if (printJobOngoing()) GotoScreen(MKSLCD_SCREEN_PRINT); else if (print_job_timer.isPaused) GotoScreen(MKSLCD_SCREEN_PAUSE); @@ -1442,8 +1442,7 @@ bool DGUSScreenHandler::loop() { } #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) - if (booted && (IS_SD_PRINTING() || IS_SD_PAUSED())) - DGUS_Runout_Idle(); + if (booted && printingIsActive()) DGUS_Runout_Idle(); #endif #endif // SHOW_BOOTSCREEN diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index ff642be294..6d207b86a7 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -91,8 +91,8 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { cur_name = strrchr(list_file.file_name[sel_id], '/'); SdFile file, *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, curDir, cur_name); + card.abortFilePrintNow(); + const char * const fname = card.diveToFile(false, curDir, cur_name); if (!fname) return; if (file.open(curDir, fname, O_READ)) { gCfgItems.curFilesize = file.fileSize(); @@ -108,7 +108,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; #endif - card.startFileprint(); + card.startOrResumeFilePrinting(); #if ENABLED(POWER_LOSS_RECOVERY) recovery.prepare(); #endif @@ -124,8 +124,8 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { lv_draw_ready_print(); #if ENABLED(SDSUPPORT) - uiCfg.print_state = IDLE; - card.flag.abort_sd_printing = true; + uiCfg.print_state = IDLE; + card.abortFilePrintSoon(); #endif } else if (DIALOG_IS(TYPE_FINISH_PRINT)) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 4134759b75..76898997eb 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -638,19 +638,18 @@ char *creat_title_text() { W25QXX.SPI_FLASH_BufferWrite(bmp_public_buf, BAK_VIEW_ADDR_TFT35 + row * 400, 400); #endif row++; + card.abortFilePrintNow(); if (row >= 200) { size = 809; row = 0; gcode_preview_over = false; - card.closefile(); char *cur_name = strrchr(list_file.file_name[sel_id], '/'); SdFile file; SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, curDir, cur_name); + const char * const fname = card.diveToFile(false, curDir, cur_name); if (!fname) return; if (file.open(curDir, fname, O_READ)) { gCfgItems.curFilesize = file.fileSize(); @@ -667,13 +666,12 @@ char *creat_title_text() { planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01; #endif - card.startFileprint(); + card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; } return; } - card.closefile(); #endif // SDSUPPORT } diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 1e3262be3b..be693a748f 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -505,7 +505,7 @@ int write_to_file(char *buf, int len) { if (res == -1) { upload_file.close(); - const char * const fname = card.diveToFile(true, upload_curDir, saveFilePath); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); if (upload_file.open(upload_curDir, fname, O_WRITE)) { upload_file.setpos(&pos); @@ -732,12 +732,10 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { if (!gcode_preview_over) { char *cur_name = strrchr(list_file.file_name[sel_id], '/'); - card.endFilePrint(); - SdFile file; SdFile *curDir; - card.endFilePrint(); - const char * const fname = card.diveToFile(true, curDir, cur_name); + card.abortFilePrintNow(); + const char * const fname = card.diveToFile(false, curDir, cur_name); if (!fname) return; if (file.open(curDir, fname, O_READ)) { gCfgItems.curFilesize = file.fileSize(); @@ -754,7 +752,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; #endif - card.startFileprint(); + card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; } @@ -814,7 +812,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { clear_cur_ui(); #if ENABLED(SDSUPPORT) uiCfg.print_state = IDLE; - card.flag.abort_sd_printing = true; + card.abortFilePrintSoon(); #endif lv_draw_ready_print(); @@ -1317,7 +1315,7 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { card.cdroot(); upload_file.close(); - const char * const fname = card.diveToFile(true, upload_curDir, saveFilePath); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); if (!upload_file.open(upload_curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { clear_cur_ui(); @@ -1370,7 +1368,7 @@ static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { int res = upload_file.write(public_buf, file_writer.write_index); if (res == -1) { upload_file.close(); - const char * const fname = card.diveToFile(true, upload_curDir, saveFilePath); + const char * const fname = card.diveToFile(false, upload_curDir, saveFilePath); if (upload_file.open(upload_curDir, fname, O_WRITE)) { upload_file.setpos(&pos); res = upload_file.write(public_buf, file_writer.write_index); @@ -1378,7 +1376,7 @@ static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { } upload_file.close(); SdFile file, *curDir; - const char * const fname = card.diveToFile(true, curDir, saveFilePath); + const char * const fname = card.diveToFile(false, curDir, saveFilePath); if (file.open(curDir, fname, O_RDWR)) { gCfgItems.curFilesize = file.fileSize(); file.close(); @@ -1744,7 +1742,7 @@ void mks_wifi_firmware_update() { if (wifi_upload(0) >= 0) { card.removeFile((char *)ESP_FIRMWARE_FILE_RENAME); SdFile file, *curDir; - const char * const fname = card.diveToFile(true, curDir, ESP_FIRMWARE_FILE); + const char * const fname = card.diveToFile(false, curDir, ESP_FIRMWARE_FILE); if (file.open(curDir, fname, O_READ)) { file.rename(curDir, (char *)ESP_FIRMWARE_FILE_RENAME); file.close(); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index cb5bb762d0..4a8e473a5c 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -625,7 +625,7 @@ void upload_spin() { // Try to upload the given file at the given address void SendUpdateFile(const char *file, uint32_t address) { - const char * const fname = card.diveToFile(true, update_curDir, ESP_FIRMWARE_FILE); + const char * const fname = card.diveToFile(false, update_curDir, ESP_FIRMWARE_FILE); if (!update_file.open(update_curDir, fname, O_READ)) return; esp_upload.fileSize = update_file.fileSize(); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 9cc8b9962c..faa23665bb 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -54,6 +54,7 @@ #include "../../module/printcounter.h" #include "../../libs/duration_t.h" #include "../../HAL/shared/Delay.h" +#include "../../MarlinCore.h" #include "../../sd/cardreader.h" #if ENABLED(PRINTCOUNTER) @@ -106,9 +107,6 @@ namespace ExtUI { #if ENABLED(JOYSTICK) uint8_t jogging : 1; #endif - #if ENABLED(SDSUPPORT) - uint8_t was_sd_printing : 1; - #endif } flags; #ifdef __SAM3X8E__ @@ -1017,27 +1015,17 @@ namespace ExtUI { void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } void printFile(const char *filename) { - UNUSED(filename); - TERN_(SDSUPPORT, card.openAndPrintFile(filename)); + TERN(SDSUPPORT, card.openAndPrintFile(filename), UNUSED(filename)); } bool isPrintingFromMediaPaused() { - return TERN0(SDSUPPORT, isPrintingFromMedia() && !IS_SD_PRINTING()); + return TERN0(SDSUPPORT, isPrintingFromMedia() && printingIsPaused()); } - bool isPrintingFromMedia() { - #if ENABLED(SDSUPPORT) - // Account for when IS_SD_PRINTING() reports the end of the - // print when there is still SD card data in the planner. - flags.was_sd_printing = card.isFileOpen() || (flags.was_sd_printing && commandsInQueue()); - return flags.was_sd_printing; - #else - return false; - #endif - } + bool isPrintingFromMedia() { return IS_SD_PRINTING(); } bool isPrinting() { - return (commandsInQueue() || isPrintingFromMedia() || TERN0(SDSUPPORT, IS_SD_PRINTING())) || print_job_timer.isRunning() || print_job_timer.isPaused(); + return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); } bool isPrintingPaused() { diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index f83d129b2f..4c33b924c4 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1487,7 +1487,7 @@ void MarlinUI::update() { void MarlinUI::abort_print() { #if ENABLED(SDSUPPORT) wait_for_heatup = wait_for_user = false; - card.flag.abort_sd_printing = true; + card.abortFilePrintSoon(); #endif #ifdef ACTION_ON_CANCEL host_action_cancel(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 14c5f13367..d7f728ad4b 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -395,7 +395,7 @@ void Endstops::event_handler() { #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { - card.endFilePrint(); + card.abortFilePrintNow(); quickstop_stepper(); thermalManager.disable_all_heaters(); print_job_timer.stop(); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index a54884bec1..3f6b50dd4b 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -161,7 +161,7 @@ CardReader::CardReader() { #endif #endif - flag.sdprinting = flag.mounted = flag.saving = flag.logging = false; + flag.sdprinting = flag.sdprintdone = flag.mounted = flag.saving = flag.logging = false; filesize = sdpos = 0; TERN_(HAS_MEDIA_SUBCALLS, file_subcall_ctr = 0); @@ -379,7 +379,7 @@ void CardReader::ls() { // // Echo the DOS 8.3 filename (and long filename, if any) // -void CardReader::printFilename() { +void CardReader::printSelectedFilename() { if (file.isOpen()) { char dosFilename[FILENAME_LENGTH]; file.getDosName(dosFilename); @@ -487,9 +487,9 @@ void CardReader::manage_media() { void CardReader::release() { // Card removed while printing? Abort! if (IS_SD_PRINTING()) - card.flag.abort_sd_printing = true; + abortFilePrintSoon(); else - endFilePrint(); + endFilePrintNow(); flag.mounted = false; flag.workDirIsRoot = true; @@ -516,9 +516,10 @@ void CardReader::openAndPrintFile(const char *name) { * since you cannot browse files during active printing. * Used by M24 and anywhere Start / Resume applies. */ -void CardReader::startFileprint() { +void CardReader::startOrResumeFilePrinting() { if (isMounted()) { flag.sdprinting = true; + flag.sdprintdone = false; TERN_(SD_RESORT, flush_presort()); } } @@ -526,14 +527,19 @@ void CardReader::startFileprint() { // // Run tasks upon finishing or aborting a file print. // -void CardReader::endFilePrint(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { +void CardReader::endFilePrintNow(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { TERN_(ADVANCED_PAUSE_FEATURE, did_pause_print = 0); TERN_(DWIN_CREALITY_LCD, HMI_flag.print_finish = flag.sdprinting); - flag.sdprinting = flag.abort_sd_printing = false; + flag.abort_sd_printing = false; if (isFileOpen()) file.close(); TERN_(SD_RESORT, if (re_sort) presort()); } +void CardReader::abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { + flag.sdprinting = flag.sdprintdone = false; + endFilePrintNow(TERN_(SD_RESORT, re_sort)); +} + void CardReader::openLogFile(const char * const path) { flag.logging = DISABLED(SDCARD_READONLY); IF_DISABLED(SDCARD_READONLY, openFileWrite(path)); @@ -542,7 +548,7 @@ void CardReader::openLogFile(const char * const path) { // // Get the root-relative DOS path of the selected file // -void CardReader::getAbsFilename(char *dst) { +void CardReader::getAbsFilenameInCWD(char *dst) { *dst++ = '/'; uint8_t cnt = 1; @@ -608,7 +614,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ } // Store current filename (based on workDirParents) and position - getAbsFilename(proc_filenames[file_subcall_ctr]); + getAbsFilenameInCWD(proc_filenames[file_subcall_ctr]); filespos[file_subcall_ctr] = sdpos; // For sub-procedures say 'SUBROUTINE CALL target: "..." parent: "..." pos12345' @@ -623,7 +629,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ #endif } - endFilePrint(); + abortFilePrintNow(); SdFile *diveDir; const char * const fname = diveToFile(true, diveDir, path); @@ -659,7 +665,7 @@ void CardReader::openFileWrite(const char * const path) { announceOpen(2, path); TERN_(HAS_MEDIA_SUBCALLS, file_subcall_ctr = 0); - endFilePrint(); + abortFilePrintNow(); SdFile *diveDir; const char * const fname = diveToFile(false, diveDir, path); @@ -712,7 +718,7 @@ bool CardReader::fileExists(const char * const path) { void CardReader::removeFile(const char * const name) { if (!isMounted()) return; - //endFilePrint(); + //abortFilePrintNow(); SdFile *curDir; const char * const fname = diveToFile(false, curDir, name); @@ -856,6 +862,9 @@ uint16_t CardReader::countFilesInWorkDir() { /** * Dive to the given DOS 8.3 file path, with optional echo of the dive paths. * + * On entry: + * - The workDir points to the last-set navigation target by cd, cdup, cdroot, or diveToFile(true, ...) + * * On exit: * - Your curDir pointer contains an SdFile reference to the file's directory. * - If update_cwd was 'true' the workDir now points to the file's directory. @@ -865,6 +874,8 @@ uint16_t CardReader::countFilesInWorkDir() { * A nullptr result indicates an unrecoverable error. */ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, const char * const path, const bool echo/*=false*/) { + DEBUG_SECTION(est, "diveToFile", true); + // Track both parent and subfolder static SdFile newDir1, newDir2; SdFile *sub = &newDir1, *startDir; @@ -872,12 +883,12 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, cons // Parsing the path string const char *item_name_adr = path; - DEBUG_ECHOLNPAIR("diveToFile: path = '", path, "'"); + DEBUG_ECHOLNPAIR(" path = '", path, "'"); if (path[0] == '/') { // Starting at the root directory? diveDir = &root; item_name_adr++; - DEBUG_ECHOLNPAIR("diveToFile: CWD to root: ", hex_address((void*)diveDir)); + DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)diveDir)); if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else @@ -885,7 +896,7 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, cons startDir = diveDir; - DEBUG_ECHOLNPAIR("diveToFile: startDir = ", hex_address((void*)startDir)); + DEBUG_ECHOLNPAIR(" startDir = ", hex_address((void*)startDir)); while (item_name_adr) { // Find next subdirectory delimiter @@ -902,7 +913,7 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, cons if (echo) SERIAL_ECHOLN(dosSubdirname); - DEBUG_ECHOLNPAIR("diveToFile: sub = ", hex_address((void*)sub)); + DEBUG_ECHOLNPAIR(" sub = ", hex_address((void*)sub)); // Open diveDir (closing first) sub->close(); @@ -914,24 +925,24 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, cons // Close diveDir if not at starting-point if (diveDir != startDir) { - DEBUG_ECHOLNPAIR("diveToFile: closing diveDir: ", hex_address((void*)diveDir)); + DEBUG_ECHOLNPAIR(" closing diveDir: ", hex_address((void*)diveDir)); diveDir->close(); } // diveDir now subDir diveDir = sub; - DEBUG_ECHOLNPAIR("diveToFile: diveDir = sub: ", hex_address((void*)diveDir)); + DEBUG_ECHOLNPAIR(" diveDir = sub: ", hex_address((void*)diveDir)); // Update workDirParents and workDirDepth if (update_cwd) { - DEBUG_ECHOLNPAIR("diveToFile: update_cwd"); + DEBUG_ECHOLNPAIR(" update_cwd"); if (workDirDepth < MAX_DIR_DEPTH) workDirParents[workDirDepth++] = *diveDir; } // Point sub at the other scratch object sub = (diveDir != &newDir1) ? &newDir1 : &newDir2; - DEBUG_ECHOLNPAIR("diveToFile: swapping sub = ", hex_address((void*)sub)); + DEBUG_ECHOLNPAIR(" swapping sub = ", hex_address((void*)sub)); // Next path atom address item_name_adr = name_end + 1; @@ -939,11 +950,12 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, cons if (update_cwd) { workDir = *diveDir; - DEBUG_ECHOLNPAIR("diveToFile: final workDir = ", hex_address((void*)diveDir)); + DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)diveDir)); flag.workDirIsRoot = (workDirDepth == 0); TERN_(SDCARD_SORT_ALPHA, presort()); } + DEBUG_ECHOLNPAIR(" returning string ", item_name_adr ?: "nullptr"); return item_name_adr; } @@ -1225,21 +1237,21 @@ uint16_t CardReader::get_num_Files() { // Return from procedure or close out the Print Job // void CardReader::fileHasFinished() { - planner.synchronize(); file.close(); - #if HAS_MEDIA_SUBCALLS if (file_subcall_ctr > 0) { // Resume calling file after closing procedure file_subcall_ctr--; openFileRead(proc_filenames[file_subcall_ctr], 2); // 2 = Returning from sub-procedure setIndex(filespos[file_subcall_ctr]); - startFileprint(); + startOrResumeFilePrinting(); return; } #endif - endFilePrint(TERN_(SD_RESORT, true)); - marlin_state = MF_SD_COMPLETE; + endFilePrintNow(TERN_(SD_RESORT, true)); + + flag.sdprintdone = true; // Stop getting bytes from the SD card + marlin_state = MF_SD_COMPLETE; // Tell Marlin to enqueue M1001 soon } #if ENABLED(AUTO_REPORT_SD_STATUS) diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 5fdd1222ae..6f1633d30e 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -70,6 +70,7 @@ typedef struct { bool saving:1, logging:1, sdprinting:1, + sdprintdone:1, mounted:1, filenameIsDir:1, workDirIsRoot:1, @@ -147,23 +148,33 @@ public: // Select a file static void selectFileByIndex(const uint16_t nr); - static void selectFileByName(const char * const match); + static void selectFileByName(const char * const match); // (working directory only) // Print job - static void openAndPrintFile(const char *name); // (working directory) - static void fileHasFinished(); - static void getAbsFilename(char *dst); - static void printFilename(); - static void startFileprint(); - static void endFilePrint(TERN_(SD_RESORT, const bool re_sort=false)); static void report_status(); - static inline void pauseSDPrint() { flag.sdprinting = false; } - static inline bool isPaused() { return isFileOpen() && !flag.sdprinting; } - static inline bool isPrinting() { return flag.sdprinting; } + static void getAbsFilenameInCWD(char *dst); + static void printSelectedFilename(); + static void openAndPrintFile(const char *name); // (working directory or full path) + static void startOrResumeFilePrinting(); + static void endFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); + static void abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); + static void fileHasFinished(); + static inline void abortFilePrintSoon() { flag.abort_sd_printing = true; } + static inline void pauseSDPrint() { flag.sdprinting = false; } + static inline bool isPrinting() { return flag.sdprinting; } + static inline bool isPaused() { return isFileOpen() && !isPrinting(); } #if HAS_PRINT_PROGRESS_PERMYRIAD - static inline uint16_t permyriadDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 9999) / 10000) : 0; } + static inline uint16_t permyriadDone() { + if (flag.sdprintdone) return 10000; + if (isFileOpen() && filesize) return sdpos / ((filesize + 9999) / 10000); + return 0; + } #endif - static inline uint8_t percentDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 99) / 100) : 0; } + static inline uint8_t percentDone() { + if (flag.sdprintdone) return 100; + if (isFileOpen() && filesize) return sdpos / ((filesize + 99) / 100); + return 0; + } // Helper for open and remove static const char* diveToFile(const bool update_cwd, SdFile* &curDir, const char * const path, const bool echo=false); @@ -186,15 +197,20 @@ public: static void removeJobRecoveryFile(); #endif - static inline bool isFileOpen() { return isMounted() && file.isOpen(); } - static inline uint32_t getIndex() { return sdpos; } - static inline uint32_t getFileSize() { return filesize; } - static inline bool eof() { return sdpos >= filesize; } - static inline void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } - static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } - static inline int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } - static inline int16_t read(void *buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } + // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) + static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } + + // Print File stats + static inline uint32_t getFileSize() { return filesize; } + static inline uint32_t getIndex() { return sdpos; } + static inline bool isFileOpen() { return isMounted() && file.isOpen(); } + static inline bool eof() { return getIndex() >= getFileSize(); } + + // File data operations + static inline int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } + static inline int16_t read(void *buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } static inline int16_t write(void *buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } + static inline void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } // TODO: rename to diskIODriver() static DiskIODriver* diskIODriver() { return driver; } @@ -318,7 +334,8 @@ private: #define IS_SD_INSERTED() true #endif -#define IS_SD_PRINTING() card.flag.sdprinting +#define IS_SD_PRINTING() (card.flag.sdprinting && !card.flag.abort_sd_printing) +#define IS_SD_FETCHING() (!card.flag.sdprintdone && IS_SD_PRINTING()) #define IS_SD_PAUSED() card.isPaused() #define IS_SD_FILE_OPEN() card.isFileOpen() @@ -327,6 +344,7 @@ extern CardReader card; #else // !SDSUPPORT #define IS_SD_PRINTING() false +#define IS_SD_FETCHING() false #define IS_SD_PAUSED() false #define IS_SD_FILE_OPEN() false From 6f494e9bed374de9f5eed2544ad4ac8f708e05fc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 05:49:06 -0500 Subject: [PATCH 0069/2168] Better opt_set comment of old val --- buildroot/bin/opt_set | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/bin/opt_set b/buildroot/bin/opt_set index d2d0cc241f..3f67d78900 100755 --- a/buildroot/bin/opt_set +++ b/buildroot/bin/opt_set @@ -8,7 +8,7 @@ SED=$(which gsed || which sed) while [[ $# > 1 ]]; do DID=0 for FN in Configuration Configuration_adv; do - "${SED}" -i "/^\(\s*\)\/*\s*\(#define\s\+${1}\b\)\(.*\)$/{s//\1\2 ${2} \/\/ \3/;h};\${x;/./{x;q0};x;q9}" Marlin/$FN.h && DID=1 + "${SED}" -i "/^\(\s*\)\/*\s*\(#define\s\+${1}\b\) *\(.*\)$/{s//\1\2 ${2} \/\/ \3/;h};\${x;/./{x;q0};x;q9}" Marlin/$FN.h && DID=1 done ((DID)) || eval "echo '#define ${1} ${2}' >>Marlin/Configuration.h" || From 98e7e6324074d1583e04f1fefbdb5d52a17c173a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 May 2021 03:29:29 -0500 Subject: [PATCH 0070/2168] TFT pins for BTT GTR V1 Proposed in #21772 --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 108 ++++++++++++------ .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 6 +- 2 files changed, 73 insertions(+), 41 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index cae1261a81..70d502f68a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -342,7 +342,7 @@ #endif #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif // @@ -352,8 +352,8 @@ // #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN PB10 - #define SDSS PB12 + #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) @@ -371,31 +371,63 @@ #endif /** - * ----- ----- - * NC | · · | GND 5V | · · | GND - * RESET | · · | PB10(SD_DETECT) (LCD_D7) PG5 | · · | PG6 (LCD_D6) - * (MOSI)PB15 | · · | PH10(BTN_EN2) (LCD_D5) PG7 | · · | PG8 (LCD_D4) - * (SD_SS)PB12 | · · | PD10(BTN_EN1) (LCD_RS) PA8 | · · | PC10 (LCD_EN) - * (SCK)PB13 | · · | PB14(MISO) (BTN_ENC) PA15 | · · | PC11 (BEEPER) - * ----- ----- - * EXP2 EXP1 + * ------ ------ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PB10 (SD_DETECT) (LCD_D7) PG5 | 3 4 | PG6 (LCD_D6) + * (MOSI) PB15 | 5 6 | PH10 (BTN_EN2) (LCD_D5) PG7 | 5 6 | PG8 (LCD_D4) + * (SD_SS) PB12 | 7 8 | PD10 (BTN_EN1) (LCD_RS) PA8 | 7 8 | PC10 (LCD_EN) + * (SCK) PB13 | 9 10 | PB14 (MISO) (BTN_ENC) PA15 | 9 10 | PC11 (BEEPER) + * ------ ------ + * EXP2 EXP1 */ +#define EXP1_03_PIN PG5 +#define EXP1_04_PIN PG6 +#define EXP1_05_PIN PG7 +#define EXP1_06_PIN PG8 +#define EXP1_07_PIN PA8 +#define EXP1_08_PIN PC10 +#define EXP1_09_PIN PA15 +#define EXP1_10_PIN PC11 + +#define EXP2_04_PIN PB10 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PH10 +#define EXP2_07_PIN PB12 +#define EXP2_08_PIN PD10 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 // // LCDs and Controllers // -#if HAS_WIRED_LCD - #define BEEPER_PIN PC11 - #define BTN_ENC PA15 +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + + #define TFT_CS_PIN EXP2_07_PIN + #define TFT_A0_PIN EXP2_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + + #define TOUCH_INT_PIN EXP1_04_PIN + #define TOUCH_MISO_PIN EXP1_05_PIN + #define TOUCH_MOSI_PIN EXP1_08_PIN + #define TOUCH_SCK_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_07_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + +#elif HAS_WIRED_LCD + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PG6 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 PC10 - #define BTN_EN2 PG8 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE PG5 - #define LCD_PINS_D4 PG7 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN // CR10_STOCKDISPLAY default timing is too fast #undef BOARD_ST7920_DELAY_1 @@ -403,53 +435,53 @@ #undef BOARD_ST7920_DELAY_3 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 PG6 - #define DOGLCD_CS PG7 - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif #else - #define LCD_PINS_RS PA8 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PD10 - #define BTN_EN2 PH10 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_PINS_ENABLE PC10 - #define LCD_PINS_D4 PG8 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS PC10 - #define DOGLCD_A0 PA8 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PG8 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PG7 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PG6 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PG5 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PG7 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 PG7 - #define LCD_PINS_D6 PG6 - #define LCD_PINS_D7 PG5 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index b88e598e6f..14cc047649 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -200,9 +200,9 @@ #if HOTENDS == 1 #if TEMP_SENSOR_PROBE - #define TEMP_PROBE_PIN TEMP_1_PIN + #define TEMP_PROBE_PIN TEMP_1_PIN #elif TEMP_SENSOR_CHAMBER - #define TEMP_CHAMBER_PIN TEMP_1_PIN + #define TEMP_CHAMBER_PIN TEMP_1_PIN #endif #endif @@ -288,7 +288,7 @@ // SD Connection // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION LCD #endif /** From 4f2ff42003dda54dd20e6884564f36ee97339f7d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 06:00:59 -0500 Subject: [PATCH 0071/2168] Update SKR 1.3 touch pins --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 557a4c4c65..625de05996 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -280,13 +280,6 @@ #define TFT_SCK_PIN EXP2_09_PIN #define TFT_MISO_PIN EXP2_10_PIN - #define TOUCH_INT_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_06_PIN - - #define TOUCH_MOSI_PIN EXP2_05_PIN - #define TOUCH_SCK_PIN EXP2_09_PIN - #define TOUCH_MISO_PIN EXP2_10_PIN - #define BTN_EN2 EXP2_06_PIN #define BTN_EN1 EXP2_08_PIN #define BTN_ENC EXP1_09_PIN @@ -434,6 +427,14 @@ #endif // HAS_WIRED_LCD +#if NEED_TOUCH_PINS + #define TOUCH_CS_PIN EXP1_06_PIN + #define TOUCH_SCK_PIN EXP2_09_PIN + #define TOUCH_MOSI_PIN EXP2_05_PIN + #define TOUCH_MISO_PIN EXP2_10_PIN + #define TOUCH_INT_PIN EXP1_05_PIN +#endif + /** * Special pins * P1_30 (37) (NOT 5V tolerant) From adefecca6cea42f0baca81705c078fa4dbd8c442 Mon Sep 17 00:00:00 2001 From: Antonino Di Guardo <64427768+digant73@users.noreply.github.com> Date: Sat, 8 May 2021 11:27:02 +0000 Subject: [PATCH 0072/2168] Always prompt in M125 if host-prompt (as with Ext UI) (#21828) Co-authored-by: Scott Lahteine --- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index dcd3e99f7a..3e495eb9d3 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -81,7 +81,7 @@ void GcodeSuite::M125() { TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); if (pause_print(retract, park_point, show_lcd, 0)) { - if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) { + if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); } From f95f18c8e51ab5ff2782a3fbd873d2f48207cb10 Mon Sep 17 00:00:00 2001 From: sanek88lbl <42996016+sanek88lbl@users.noreply.github.com> Date: Sun, 9 May 2021 01:06:21 +0300 Subject: [PATCH 0073/2168] Lerdge K EEPROM and TFT (#21812) Co-authored-by: Scott Lahteine --- .github/workflows/test-builds.yml | 1 + Marlin/src/HAL/shared/eeprom_if_i2c.cpp | 10 +++- Marlin/src/lcd/tft_io/st7796s.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 62 ++++++++++++++++++------- buildroot/tests/LERDGEK | 18 +++++++ ini/features.ini | 1 + ini/stm32f4.ini | 3 +- 7 files changed, 76 insertions(+), 23 deletions(-) create mode 100755 buildroot/tests/LERDGEK diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 93bda9726e..6fdd7d67bc 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -86,6 +86,7 @@ jobs: - FLYF407ZG - rumba32 - LERDGEX + - LERDGEK - mks_robin_nano35_stm32 - NUCLEO_F767ZI - REMRAM_V1 diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index f6dd33b7c4..27f0233562 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -30,11 +30,17 @@ #if ENABLED(I2C_EEPROM) #include "eeprom_if.h" -#include + +#if ENABLED(SOFT_I2C_EEPROM) + #include + SlowSoftWire Wire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true); +#else + #include +#endif void eeprom_init() { Wire.begin( - #if PINS_EXIST(I2C_SCL, I2C_SDA) + #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN) #endif ); diff --git a/Marlin/src/lcd/tft_io/st7796s.h b/Marlin/src/lcd/tft_io/st7796s.h index 8653a49ca2..e1931ed551 100644 --- a/Marlin/src/lcd/tft_io/st7796s.h +++ b/Marlin/src/lcd/tft_io/st7796s.h @@ -154,6 +154,9 @@ static const uint16_t st7796s_init[] = { static const uint16_t lerdge_st7796s_init[] = { DATASIZE_8BIT, + ESC_REG(ST7796S_SWRESET), ESC_DELAY(100), + ESC_REG(ST7796S_SLPOUT), ESC_DELAY(20), + ESC_REG(ST7796S_CSCON), 0x00C3, // enable command 2 part I ESC_REG(ST7796S_CSCON), 0x0096, // enable command 2 part II @@ -165,7 +168,6 @@ static const uint16_t lerdge_st7796s_init[] = { ESC_REG(ST7796S_PWR2), 0x0015, ESC_REG(ST7796S_PWR3), 0x00AF, - ESC_REG(0xC3), 0x0009, // Register not documented in datasheet ESC_REG(ST7796S_VCMPCTL), 0x0022, ESC_REG(ST7796S_VCMOST), 0x0000, ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 1bc7bbc99e..b92056ea86 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -28,7 +28,14 @@ #define BOARD_INFO_NAME "Lerdge K" #define DEFAULT_MACHINE_NAME "LERDGE" -#define I2C_EEPROM +// EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define SOFT_I2C_EEPROM // Force the use of Software I2C + #define I2C_SCL_PIN PG14 + #define I2C_SDA_PIN PG13 + #define MARLIN_EEPROM_SIZE 0x10000 +#endif // USB Flash Drive support #define HAS_OTG_USB_HOST_SUPPORT @@ -36,7 +43,7 @@ // // Servos // -//#define SERVO0_PIN PB11 +#define SERVO0_PIN PB11 // // Limit Switches @@ -96,6 +103,13 @@ // #define E1_CS_PIN PE4 //#endif +//#define E2_STEP_PIN PF4 // best guess +//#define E2_DIR_PIN PF3 // best guess +//#define E2_ENABLE_PIN PF5 // best guess +//#ifndef E2_CS_PIN +// #define E2_CS_PIN PB2 // best guess +//#endif + #if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers @@ -163,13 +177,19 @@ #ifndef FAN_PIN #define FAN_PIN PF7 #endif + #define FAN1_PIN PF6 -#define FAN2_PIN PF8 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PF6 + #define E0_AUTO_FAN_PIN PB1 #endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN PB0 +#endif + +#define CONTROLLER_FAN_PIN PF8 + // // LED / Lighting // @@ -177,10 +197,10 @@ //#define CASE_LIGHT_PIN_DO -1 //#define NEOPIXEL_PIN -1 #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB7 + #define RGB_LED_R_PIN PB8 // swap R and G pin for compatibility with real wires #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB8 + #define RGB_LED_G_PIN PB7 #endif #ifndef RGB_LED_B_PIN #define RGB_LED_B_PIN PB9 @@ -197,7 +217,7 @@ // #define SDSS PC11 #define LED_PIN PA15 // Alive -#define PS_ON_PIN -1 +#define PS_ON_PIN PA4 #define KILL_PIN -1 #define POWER_LOSS_PIN PA4 // Power-loss / nAC_FAULT @@ -213,17 +233,23 @@ // LCD / Controller // -#define TFT_RESET_PIN PD6 -#define TFT_BACKLIGHT_PIN PD3 +#if HAS_FSMC_TFT + //#define TFT_DRIVER LERDGE_ST7796 -#define TFT_CS_PIN PD7 -#define TFT_RS_PIN PD11 + #define TFT_RESET_PIN PD6 + #define TFT_BACKLIGHT_PIN PD3 -#define TOUCH_CS_PIN PG15 -#define TOUCH_SCK_PIN PB3 -#define TOUCH_MOSI_PIN PB5 -#define TOUCH_MISO_PIN PB4 + #define TFT_CS_PIN PD7 + #define TFT_RS_PIN PD11 -#define BTN_EN1 PG10 -#define BTN_EN2 PG11 -#define BTN_ENC PG9 + #define TOUCH_CS_PIN PG15 + #define TOUCH_SCK_PIN PB3 + #define TOUCH_MOSI_PIN PB5 + #define TOUCH_MISO_PIN PB4 +#endif + +#if IS_NEWPANEL + #define BTN_EN1 PG10 + #define BTN_EN2 PG11 + #define BTN_ENC PG9 +#endif diff --git a/buildroot/tests/LERDGEK b/buildroot/tests/LERDGEK new file mode 100755 index 0000000000..1aca42c18a --- /dev/null +++ b/buildroot/tests/LERDGEK @@ -0,0 +1,18 @@ +#!/usr/bin/env bash +# +# Build tests for LERDGEK environment +# + +# exit on first failure +set -e + +# +# Build with the typical configuration +# +restore_configs +opt_set MOTHERBOARD BOARD_LERDGE_K SERIAL_PORT 1 +opt_enable TFT_GENERIC TFT_INTERFACE_FSMC TFT_COLOR_UI +exec_test $1 $2 "LERDGE K with Generic FSMC TFT with ColorUI" "$3" + +# clean up +restore_configs diff --git a/ini/features.ini b/ini/features.ini index 871741dca8..6fa74a343f 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -41,6 +41,7 @@ HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + HAS_SPI_TFT = src_filter=+ + I2C_EEPROM = src_filter=+ +SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/master.zip SPI_EEPROM = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index ff99296877..325dc4b502 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -308,8 +308,7 @@ build_flags = ${stm_flash_drive.build_flags} platform = ${lerdge_common.platform} extends = lerdge_common board_build.firmware = Lerdge_K_firmware_force.bin -build_flags = ${lerdge_common.build_flags} - -DLERDGEK +build_flags = ${lerdge_common.build_flags} -DLERDGEK # # Lerdge K with USB Flash Drive Support From 42a2b5c3ec1c4067113b87ad8c1977018bbb763e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 17:34:21 -0500 Subject: [PATCH 0074/2168] Move temp errors calling kill() out of ISR (#21832) --- Marlin/src/module/temperature.cpp | 173 +++++++++++++++--------------- Marlin/src/module/temperature.h | 12 ++- 2 files changed, 94 insertions(+), 91 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 2f1a54e91d..72d801652f 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -576,8 +576,7 @@ volatile bool Temperature::raw_temps_ready = false; const millis_t ms = millis(); - if (raw_temps_ready) { // temp sample ready - updateTemperaturesFromRawValues(); + if (updateTemperaturesIfReady()) { // temp sample ready // Get the current temperature and constrain it current_temp = GHV(degChamber(), degBed(), degHotend(heater_id)); @@ -1212,9 +1211,7 @@ void Temperature::manage_heater() { } #endif - if (!raw_temps_ready) return; - - updateTemperaturesFromRawValues(); // also resets the watchdog + if (!updateTemperaturesIfReady()) return; // Will also reset the watchdog if temperatures are ready #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) #if TEMP_SENSOR_0_IS_MAX_TC @@ -1890,29 +1887,88 @@ void Temperature::manage_heater() { #endif // HAS_TEMP_PROBE /** - * Get the raw values into the actual temperatures. - * The raw values are created in interrupt context, - * and this function is called from normal context - * as it would block the stepper routine. + * Convert the raw sensor readings into actual Celsius temperatures and + * validate raw temperatures. Bad readings generate min/maxtemp errors. + * + * The raw values are generated entirely in interrupt context, and this + * method is called from normal context once 'raw_temps_ready' has been + * set by update_raw_temperatures(). + * + * The watchdog is dependent on this method. If 'raw_temps_ready' stops + * being set by the interrupt so that this method is not called for over + * 4 seconds then something has gone afoul and the machine will be reset. */ void Temperature::updateTemperaturesFromRawValues() { + + watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt + TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); TERN_(TEMP_SENSOR_1_IS_MAX_TC, TERN(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant, temp_hotend[1]).raw = READ_MAX_TC(1)); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant.celsius = analog_to_celsius_hotend(temp_redundant.raw, 1)); - TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); + + TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); - TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); - TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); + TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); - TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); + TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); - // Reset the watchdog on good temperature measurement - watchdog_refresh(); + #if HAS_HOTEND - raw_temps_ready = false; + static constexpr int8_t temp_dir[] = { + TERN(TEMP_SENSOR_0_IS_MAX_TC, 0, TEMPDIR(0)) + #if HAS_MULTI_HOTEND + , TERN(TEMP_SENSOR_1_IS_MAX_TC, 0, TEMPDIR(1)) + #if HOTENDS > 2 + #define _TEMPDIR(N) , TEMPDIR(N) + REPEAT_S(2, HOTENDS, _TEMPDIR) + #endif + #endif + }; + + 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 + if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); + + const bool heater_on = temp_hotend[e].target > 0; + if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 + if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) + #endif + min_temp_error((heater_id_t)e); + } + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 + else + consecutive_low_temperature_error[e] = 0; + #endif + } + } + + #endif // HAS_HOTEND + + #if ENABLED(THERMAL_PROTECTION_BED) + #define BEDCMP(A,B) (TEMPDIR(BED) < 0 ? ((A)<(B)) : ((A)>(B))) + if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); + if (temp_bed.target > 0 && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); + #endif + + #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) + #define CHAMBERCMP(A,B) (TEMPDIR(CHAMBER) < 0 ? ((A)<(B)) : ((A)>(B))) + if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); + if (temp_chamber.target > 0 && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); + #endif + + #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) + #define COOLERCMP(A,B) (TEMPDIR(COOLER) < 0 ? ((A)<(B)) : ((A)>(B))) + if (cutter.unitPower > 0 && COOLERCMP(temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); + if (COOLERCMP(mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); + #endif } #if THERMO_SEPARATE_SPI @@ -2657,6 +2713,9 @@ void Temperature::disable_all_heaters() { /** * Update raw temperatures + * + * Called by ISR => readings_ready when new temperatures have been set by updateTemperaturesFromRawValues. + * Applies all the accumulators to the current raw temperatures. */ void Temperature::update_raw_temperatures() { @@ -2686,14 +2745,19 @@ void Temperature::update_raw_temperatures() { TERN_(HAS_JOY_ADC_X, joystick.x.update()); TERN_(HAS_JOY_ADC_Y, joystick.y.update()); TERN_(HAS_JOY_ADC_Z, joystick.z.update()); - - raw_temps_ready = true; } +/** + * Called by the Temperature ISR when all the ADCs have been processed. + * Reset all the ADC accumulators for another round of updates. + */ void Temperature::readings_ready() { - // Update the raw values if they've been read. Else we could be updating them during reading. - if (!raw_temps_ready) update_raw_temperatures(); + // Update raw values only if they're not already set. + if (!raw_temps_ready) { + update_raw_temperatures(); + raw_temps_ready = true; + } // Filament Sensor - can be read any time since IIR filtering is used TERN_(FILAMENT_WIDTH_SENSOR, filwidth.reading_ready()); @@ -2711,75 +2775,6 @@ void Temperature::readings_ready() { TERN_(HAS_JOY_ADC_X, joystick.x.reset()); TERN_(HAS_JOY_ADC_Y, joystick.y.reset()); TERN_(HAS_JOY_ADC_Z, joystick.z.reset()); - - #if HAS_HOTEND - - static constexpr int8_t temp_dir[] = { - TERN(TEMP_SENSOR_0_IS_MAX_TC, 0, TEMPDIR(0)) - #if HAS_MULTI_HOTEND - , TERN(TEMP_SENSOR_1_IS_MAX_TC, 0, TEMPDIR(1)) - #if HOTENDS > 2 - #define _TEMPDIR(N) , TEMPDIR(N) - REPEAT_S(2, HOTENDS, _TEMPDIR) - #endif - #endif - }; - - 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 - if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); - - const bool heater_on = (temp_hotend[e].target > 0 || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount > 0)); - if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { - #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 - if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) - #endif - min_temp_error((heater_id_t)e); - } - #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 - else - consecutive_low_temperature_error[e] = 0; - #endif - } - } - - #endif // HAS_HOTEND - - #if ENABLED(THERMAL_PROTECTION_BED) - #if TEMPDIR(BED) < 0 - #define BEDCMP(A,B) ((A)<(B)) - #else - #define BEDCMP(A,B) ((A)>(B)) - #endif - const bool bed_on = (temp_bed.target > 0) || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount > 0); - if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); - if (bed_on && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); - #endif - - #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) - #if TEMPDIR(CHAMBER) < 0 - #define CHAMBERCMP(A,B) ((A)<(B)) - #else - #define CHAMBERCMP(A,B) ((A)>(B)) - #endif - const bool chamber_on = (temp_chamber.target > 0); - if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); - if (chamber_on && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); - #endif - - #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) - #if TEMPDIR(COOLER) < 0 - #define COOLERCMP(A,B) ((A)<(B)) - #else - #define COOLERCMP(A,B) ((A)>(B)) - #endif - if (cutter.unitPower > 0) { - if (COOLERCMP(temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); - } - if (COOLERCMP(mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); - #endif } /** diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 96ff8b5895..83fbc8fd46 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -419,8 +419,6 @@ class Temperature { private: - static volatile bool raw_temps_ready; - #if ENABLED(WATCH_HOTENDS) static hotend_watch_t watch_hotend[HOTENDS]; #endif @@ -880,9 +878,19 @@ class Temperature { #endif private: + + // Reading raw temperatures and converting to Celsius when ready + static volatile bool raw_temps_ready; static void update_raw_temperatures(); static void updateTemperaturesFromRawValues(); + static inline bool updateTemperaturesIfReady() { + if (!raw_temps_ready) return false; + updateTemperaturesFromRawValues(); + raw_temps_ready = false; + return true; + } + // MAX Thermocouples #if HAS_MAX_TC #define MAX_TC_COUNT 1 + BOTH(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC) #if MAX_TC_COUNT > 1 From 9f10695b3f7460a1981c5d1c6ea3999a85f63cc2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 May 2021 19:00:47 -0500 Subject: [PATCH 0075/2168] Fix TFT typo --- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index c1a56101ad..f2509ce5e4 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -312,7 +312,7 @@ void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uin uint16_t offline = TFT_WIDTH - (ex - sx); uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx]; - CBI(DMA2D->CR, 0) + CBI(DMA2D->CR, 0); DMA2D->CR = 0 << 16; DMA2D->FGPFCCR = 0X02; DMA2D->FGOR = 0; From 6cc45d2578fe925841bce17c917f7778849a30d1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 9 May 2021 01:08:03 +0000 Subject: [PATCH 0076/2168] [cron] Bump distribution date (2021-05-09) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 572722416f..9991da493f 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 "2021-05-08" + #define STRING_DISTRIBUTION_DATE "2021-05-09" #endif /** From c9de9d4f9b8aee4ac3dfd0f49591b822230f43c7 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Sun, 9 May 2021 10:02:16 +0800 Subject: [PATCH 0077/2168] Capacitive Touch Screen (GT911) for SKR SE BX (#21843) Co-authored-by: Msq001 Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 2 +- Marlin/src/HAL/LPC1768/tft/xpt2046.cpp | 2 +- Marlin/src/HAL/STM32/tft/gt911.cpp | 202 +++++++++++++++++++ Marlin/src/HAL/STM32/tft/gt911.h | 120 +++++++++++ Marlin/src/HAL/STM32/tft/xpt2046.cpp | 2 +- Marlin/src/HAL/STM32F1/tft/xpt2046.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 27 ++- Marlin/src/inc/Conditionals_adv.h | 4 +- Marlin/src/inc/SanityCheck.h | 18 +- Marlin/src/lcd/tft/touch.cpp | 25 ++- Marlin/src/lcd/tft/touch.h | 13 +- Marlin/src/lcd/tft/ui_1024x600.cpp | 43 ++-- Marlin/src/lcd/touch/touch_buttons.cpp | 11 +- Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h | 16 +- 14 files changed, 425 insertions(+), 62 deletions(-) create mode 100644 Marlin/src/HAL/STM32/tft/gt911.cpp create mode 100644 Marlin/src/HAL/STM32/tft/gt911.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index e1f9a4be70..755b58fe15 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2571,7 +2571,7 @@ //#define DWIN_CREALITY_LCD // -// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 +// Touch Screen Settings // //#define TOUCH_SCREEN #if ENABLED(TOUCH_SCREEN) diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index cf14405484..9c1e158981 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp new file mode 100644 index 0000000000..f99fa46e19 --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -0,0 +1,202 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + +#include "gt911.h" +#include "pinconfig.h" + +SW_IIC::SW_IIC(uint16_t sda, uint16_t scl) { + scl_pin = scl; + sda_pin = sda; +} + +// Software I2C hardware io init +void SW_IIC::init() { + OUT_WRITE(scl_pin, HIGH); + OUT_WRITE(sda_pin, HIGH); +} + +// Software I2C start signal +void SW_IIC::start() { + write_sda(HIGH); // SDA = 1 + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_sda(LOW); // SDA = 0 + iic_delay(1); + write_scl(LOW); // SCL = 0 // keep SCL low, avoid false stop caused by level jump caused by SDA switching IN/OUT +} + +// Software I2C stop signal +void SW_IIC::stop() { + write_scl(LOW); // SCL = 0 + iic_delay(2); + write_sda(LOW); // SDA = 0 + iic_delay(2); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_sda(HIGH); // SDA = 1 +} + +// Software I2C sends ACK or NACK signal +void SW_IIC::send_ack(bool ack) { + write_sda(ack ? LOW : HIGH); // SDA = !ack + iic_delay(2); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_scl(LOW); // SCL = 0 +} + +// Software I2C read ACK or NACK signal +bool SW_IIC::read_ack() { + bool error = 0; + set_sda_in(); + + iic_delay(2); + + write_scl(HIGH); // SCL = 1 + error = read_sda(); + + iic_delay(2); + + write_scl(LOW); // SCL = 0 + + set_sda_out(); + return error; +} + +void SW_IIC::send_byte(uint8_t txd) { + LOOP_L_N(i, 8) { + write_sda(txd & 0x80); // write data bit + txd <<= 1; + iic_delay(1); + write_scl(HIGH); // SCL = 1 + iic_delay(2); + write_scl(LOW); // SCL = 0 + iic_delay(1); + } + + read_ack(); // wait ack +} + +uint8_t SW_IIC::read_byte(bool ack) { + uint8_t data = 0; + + set_sda_in(); + LOOP_L_N(i, 8) { + write_scl(HIGH); // SCL = 1 + iic_delay(1); + data <<= 1; + if (read_sda()) data++; + write_scl(LOW); // SCL = 0 + iic_delay(2); + } + set_sda_out(); + + send_ack(ack); + + return data; +} + +GT911_REG_MAP GT911::reg; +SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN); + +void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) { + sw_iic.start(); + sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address + LOOP_L_N(i, reg_len) { // Set reg address + uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; + sw_iic.send_byte(r); + } + + LOOP_L_N(i, w_len) { // Write data to reg + sw_iic.send_byte(w_data[i]); + } + sw_iic.stop(); +} + +void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) { + sw_iic.start(); + sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address + LOOP_L_N(i, reg_len) { // Set reg address + uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; + sw_iic.send_byte(r); + } + + sw_iic.start(); + sw_iic.send_byte(gt911_slave_address + 1); // Set read mode + + LOOP_L_N(i, r_len) { + r_data[i] = sw_iic.read_byte(1); // Read data from reg + } + sw_iic.stop(); +} + +void GT911::Init() { + OUT_WRITE(GT911_RST_PIN, LOW); + OUT_WRITE(GT911_INT_PIN, LOW); + delay(20); + WRITE(GT911_RST_PIN, HIGH); + SET_INPUT(GT911_INT_PIN); + + sw_iic.init(); + + uint8_t clear_reg = 0x0000; + write_reg(0x814E, 2, &clear_reg, 2); // Reset to 0 for start +} + +bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) { + read_reg(0x814E, 2, ®.REG.status, 1); + + if (reg.REG.status & 0x80) { + uint8_t clear_reg = 0x00; + write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start + read_reg(0x8150, 2, reg.map + 2, 8 * (reg.REG.status & 0x0F)); + + // First touch point + *x = ((reg.REG.point[0].xh & 0x0F) << 8) | reg.REG.point[0].xl; + *y = ((reg.REG.point[0].yh & 0x0F) << 8) | reg.REG.point[0].yl; + return true; + } + return false; +} + +bool GT911::getPoint(int16_t *x, int16_t *y) { + static bool touched = 0; + static int16_t read_x = 0, read_y = 0; + static millis_t next_time = 0; + + if (ELAPSED(millis(), next_time)) { + touched = getFirstTouchPoint(&read_x, &read_y); + next_time = millis() + 20; + } + + *x = read_x; + *y = read_y; + return touched; +} + +#endif // TFT_TOUCH_DEVICE_GT911 +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h new file mode 100644 index 0000000000..752a554d98 --- /dev/null +++ b/Marlin/src/HAL/STM32/tft/gt911.h @@ -0,0 +1,120 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../../../inc/MarlinConfig.h" + +#define GT911_SLAVE_ADDRESS 0xBA + +#if !PIN_EXISTS(GT911_RST) + #error "GT911_RST_PIN is not defined." +#elif !PIN_EXISTS(GT911_INT) + #error "GT911_INT_PIN is not defined." +#elif !PIN_EXISTS(GT911_SW_I2C_SCL) + #error "GT911_SW_I2C_SCL_PIN is not defined." +#elif !PIN_EXISTS(GT911_SW_I2C_SDA) + #error "GT911_SW_I2C_SDA_PIN is not defined." +#endif + +class SW_IIC { + private: + uint16_t scl_pin; + uint16_t sda_pin; + void write_scl(bool level) + { + WRITE(scl_pin, level); + } + void write_sda(bool level) + { + WRITE(sda_pin, level); + } + bool read_sda() + { + return READ(sda_pin); + } + void set_sda_out() + { + SET_OUTPUT(sda_pin); + } + void set_sda_in() + { + SET_INPUT_PULLUP(sda_pin); + } + static void iic_delay(uint8_t t) + { + delayMicroseconds(t); + } + + public: + SW_IIC(uint16_t sda, uint16_t scl); + // setSCL/SDA have to be called before begin() + void setSCL(uint16_t scl) + { + scl_pin = scl; + }; + void setSDA(uint16_t sda) + { + sda_pin = sda; + }; + void init(); // Initialize the IO port of IIC + void start(); // Send IIC start signal + void stop(); // Send IIC stop signal + void send_byte(uint8_t txd); // IIC sends a byte + uint8_t read_byte(bool ack); // IIC reads a byte + void send_ack(bool ack); // IIC sends ACK or NACK signal + bool read_ack(); +}; + +typedef struct __attribute__((__packed__)) { + uint8_t xl; + uint8_t xh; + uint8_t yl; + uint8_t yh; + uint8_t sizel; + uint8_t sizeh; + uint8_t reserved; + uint8_t track_id; +} GT911_POINT; + +typedef union __attribute__((__packed__)) { + uint8_t map[42]; + struct { + uint8_t status; // 0x814E + uint8_t track_id; // 0x814F + + GT911_POINT point[5]; // [0]:0x8150 - 0x8157 / [1]:0x8158 - 0x815F / [2]:0x8160 - 0x8167 / [3]:0x8168 - 0x816F / [4]:0x8170 - 0x8177 + } REG; +} GT911_REG_MAP; + +class GT911 { + private: + static const uint8_t gt911_slave_address = GT911_SLAVE_ADDRESS; + static GT911_REG_MAP reg; + static SW_IIC sw_iic; + static void write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len); + static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len); + + public: + static void Init(); + static bool getFirstTouchPoint(int16_t *x, int16_t *y); + static bool getPoint(int16_t *x, int16_t *y); +}; diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index 04294e669c..dffeb6aaf7 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include "pinconfig.h" diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp index 98371c5ffb..ac9ad072aa 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" #include diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index afec2c2b44..ed86c1bf65 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1131,6 +1131,9 @@ #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) #define TFT_RES_1024x600 #define TFT_INTERFACE_LTDC + #if ENABLED(TOUCH_SCREEN) + #define TFT_TOUCH_DEVICE_GT911 + #endif #elif ENABLED(TFT_GENERIC) #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320) @@ -1219,16 +1222,30 @@ #define HAS_UI_1024x600 1 #endif #if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272) - #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen + #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen #elif HAS_UI_1024x600 #define LCD_HEIGHT TERN(TOUCH_SCREEN, 12, 13) // Fewer lines with touch buttons onscreen #endif // This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046' -#if ENABLED(TOUCH_SCREEN) && !HAS_GRAPHICAL_TFT - #undef TOUCH_SCREEN - #if ENABLED(TFT_CLASSIC_UI) - #define HAS_TOUCH_BUTTONS 1 +#if ENABLED(TOUCH_SCREEN) + #if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046) + #define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 + #endif + #if ENABLED(TFT_TOUCH_DEVICE_GT911) // GT911 Capacitive touch screen such as BIQU_BX_TFT70 + #undef TOUCH_SCREEN_CALIBRATION + #undef TOUCH_CALIBRATION_AUTO_SAVE + #endif + #if !HAS_GRAPHICAL_TFT + #undef TOUCH_SCREEN + #if ENABLED(TFT_CLASSIC_UI) + #define HAS_TOUCH_BUTTONS 1 + #if ENABLED(TFT_TOUCH_DEVICE_GT911) + #define HAS_CAP_TOUCH_BUTTONS 1 + #else + #define HAS_RES_TOUCH_BUTTONS 1 + #endif + #endif #endif #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 19ab98fed3..44ea34a490 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -371,13 +371,13 @@ #endif // Full Touch Screen needs 'tft/xpt2046' -#if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI) +#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) #define HAS_TFT_XPT2046 1 #endif // Touch Screen or "Touch Buttons" need XPT2046 pins // but they use different components -#if EITHER(HAS_TFT_XPT2046, HAS_TOUCH_BUTTONS) +#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #define NEED_TOUCH_PINS 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2cc90e0e8b..bbd646a30d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3180,21 +3180,11 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif /** - * Touch Buttons + * Touch Screen Calibration */ -#if ENABLED(TOUCH_SCREEN) && DISABLED(TOUCH_SCREEN_CALIBRATION) - #ifndef TOUCH_CALIBRATION_X - #error "TOUCH_CALIBRATION_X must be defined with TOUCH_SCREEN." - #endif - #ifndef TOUCH_CALIBRATION_Y - #error "TOUCH_CALIBRATION_Y must be defined with TOUCH_SCREEN." - #endif - #ifndef TOUCH_OFFSET_X - #error "TOUCH_OFFSET_X must be defined with TOUCH_SCREEN." - #endif - #ifndef TOUCH_OFFSET_Y - #error "TOUCH_OFFSET_Y must be defined with TOUCH_SCREEN." - #endif +#if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && DISABLED(TOUCH_SCREEN_CALIBRATION) \ + && (!defined(TOUCH_CALIBRATION_X) || !defined(TOUCH_CALIBRATION_Y) || !defined(TOUCH_OFFSET_X) || !defined(TOUCH_OFFSET_Y)) + #error "TOUCH_CALIBRATION_[XY] and TOUCH_OFFSET_[XY] are required for resistive touch screens with TOUCH_SCREEN_CALIBRATION disabled." #endif /** diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 83a7ea78b7..3d4e0a40e1 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -257,18 +257,23 @@ void Touch::hold(touch_control_t *control, millis_t delay) { } bool Touch::get_point(int16_t *x, int16_t *y) { - #if ENABLED(TOUCH_SCREEN_CALIBRATION) - bool is_touched = (touch_calibration.calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); + #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + bool is_touched = (touch_calibration.calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); - if (is_touched && touch_calibration.calibration.orientation != TOUCH_ORIENTATION_NONE) { - *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x; - *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y; - } - #else - bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); - *x = uint16_t((uint32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X; - *y = uint16_t((uint32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y; + if (is_touched && touch_calibration.calibration.orientation != TOUCH_ORIENTATION_NONE) { + *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x; + *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y; + } + #else + bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y)); + *x = uint16_t((uint32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X; + *y = uint16_t((uint32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y; + #endif + #elif ENABLED(TFT_TOUCH_DEVICE_GT911) + bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y)); #endif + return is_touched; } Touch touch; diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 6726f031ff..8d6001b8d8 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -30,8 +30,15 @@ #include "../tft_io/touch_calibration.h" #endif -#include HAL_PATH(../../HAL, tft/xpt2046.h) -#define TOUCH_DRIVER XPT2046 +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + #include HAL_PATH(../../HAL, tft/gt911.h) + #define TOUCH_DRIVER_CLASS GT911 +#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #include HAL_PATH(../../HAL, tft/xpt2046.h) + #define TOUCH_DRIVER_CLASS XPT2046 +#else + #error "Unknown Touch Screen Type." +#endif // Menu Navigation extern int8_t encoderTopLine, encoderLine, screen_items; @@ -85,7 +92,7 @@ typedef struct __attribute__((__packed__)) { class Touch { private: - static TOUCH_DRIVER io; + static TOUCH_DRIVER_CLASS io; static int16_t x, y; static bool enabled; diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index c9c0aae05a..3b12ab2b60 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -48,9 +48,9 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (draw_menu_navigation) { - add_control(104, TFT_HEIGHT - 34, PAGE_UP, imgPageUp, encoderTopLine > 0); - add_control(344, TFT_HEIGHT - 34, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); - add_control(224, TFT_HEIGHT - 34, BACK, imgBack); + add_control(164, TFT_HEIGHT - 50, PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(796, TFT_HEIGHT - 50, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(480, TFT_HEIGHT - 50, BACK, imgBack); draw_menu_navigation = false; } #endif @@ -60,6 +60,7 @@ void MarlinUI::tft_idle() { } #if ENABLED(SHOW_BOOTSCREEN) + void MarlinUI::show_bootscreen() { tft.queue.reset(); @@ -81,9 +82,13 @@ void MarlinUI::tft_idle() { #endif tft.queue.sync(); - safe_delay(BOOTSCREEN_TIMEOUT); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); clear_lcd(); } + #endif void MarlinUI::draw_kill_screen() { @@ -289,7 +294,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 96, 176, 100, 32)); + TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 274, y, 100, 32)); // flow rate tft.canvas(650, y, 100, 32); @@ -299,10 +304,10 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder])); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 284, 176, 100, 32, active_extruder)); + TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 650, y, 100, 32, active_extruder)); #if ENABLED(TOUCH_SCREEN) - add_control(404, y, menu_main, imgSettings); + add_control(900, y, menu_main, imgSettings); TERN_(SDSUPPORT, add_control(12, y, menu_media, imgSD, !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED)); #endif @@ -375,8 +380,8 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val extern screenFunc_t _manual_move_func_ptr; if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { - #define SLIDER_LENGTH 336 - #define SLIDER_Y_POSITION 186 + #define SLIDER_LENGTH 600 + #define SLIDER_Y_POSITION 200 tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16); tft.set_background(COLOR_BACKGROUND); @@ -398,9 +403,9 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(64, TFT_HEIGHT - 64, DECREASE, imgDecrease); - add_control(352, TFT_HEIGHT - 64, INCREASE, imgIncrease); - add_control(208, TFT_HEIGHT - 64, CLICK, imgConfirm); + add_control(164, TFT_HEIGHT - 64, DECREASE, imgDecrease); + add_control(796, TFT_HEIGHT - 64, INCREASE, imgIncrease); + add_control(480, TFT_HEIGHT - 64, CLICK, imgConfirm); #endif } @@ -755,7 +760,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); queue.inject_P(G28_STR); // Disable touch until home is done - TERN_(HAS_TFT_XPT2046, touch.disable()); + TERN_(TOUCH_SCREEN, touch.disable()); drawAxisValue(E_AXIS); drawAxisValue(X_AXIS); drawAxisValue(Y_AXIS); @@ -804,14 +809,14 @@ static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); } - TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); + TERN_(TOUCH_SCREEN, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); } void MarlinUI::move_axis_screen() { // Reset defer_status_screen(true); motionAxisState.blocked = false; - TERN_(HAS_TFT_XPT2046, touch.enable()); + TERN_(TOUCH_SCREEN, touch.enable()); ui.clear_lcd(); @@ -849,13 +854,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.eNamePos.x = x; motionAxisState.eNamePos.y = y; drawCurESelection(); - TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + TERN_(TOUCH_SCREEN, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); x += BTN_WIDTH + spacing; drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy); x += BTN_WIDTH + spacing; //imgHome is 64x64 - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); x += BTN_WIDTH + spacing; uint16_t xplus_x = x; @@ -904,13 +909,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.stepValuePos.y = y; if (!busy) { drawCurStepValue(); - TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + TERN_(TOUCH_SCREEN, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); } // aligned with x+ drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); } #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 975de58211..c9476bd2bb 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -24,8 +24,15 @@ #include "touch_buttons.h" #include "../scaled_tft.h" -#include HAL_PATH(../../HAL, tft/xpt2046.h) -XPT2046 touchIO; +#if ENABLED(TFT_TOUCH_DEVICE_GT911) + #include HAL_PATH(../../HAL, tft/gt911.h) + GT911 touchIO; +#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #include HAL_PATH(../../HAL, tft/xpt2046.h) + XPT2046 touchIO; +#else + #error "Unknown Touch Screen Type." +#endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) #include "../tft_io/touch_calibration.h" diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h index 320d04e0b1..c4349d182b 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h @@ -207,11 +207,21 @@ #define LCD_B4_PIN PI4 #define LCD_B3_PIN PG11 + // GT911 Capacitive Touch Sensor + #if ENABLED(TFT_TOUCH_DEVICE_GT911) + #define GT911_RST_PIN PE4 + #define GT911_INT_PIN PE3 + #define GT911_SW_I2C_SCL_PIN PE2 + #define GT911_SW_I2C_SDA_PIN PE6 + #endif + #endif -#define BTN_EN1 PH6 -#define BTN_EN2 PH7 -#define BTN_ENC PH8 +#if IS_NEWPANEL + #define BTN_EN1 PH6 + #define BTN_EN2 PH7 + #define BTN_ENC PH8 +#endif #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD From 4335f4e41f694a92bf79e1fe0e9bfc3491fa1bd9 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sat, 8 May 2021 23:05:47 -0300 Subject: [PATCH 0078/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Lerdge=20USB=20F?= =?UTF-8?q?lash=20Drive=20envs=20(#21847)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f4.ini | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 325dc4b502..62038332b3 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -282,7 +282,7 @@ board_build.firmware = Lerdge_X_firmware_force.bin platform = ${env:LERDGEX.platform} extends = env:LERDGEX platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} +build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # # Lerdge S @@ -299,7 +299,7 @@ board_build.firmware = Lerdge_firmware_force.bin platform = ${env:LERDGES.platform} extends = env:LERDGES platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} +build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # # Lerdge K @@ -317,7 +317,7 @@ build_flags = ${lerdge_common.build_flags} -DLERDGEK platform = ${env:LERDGEK.platform} extends = env:LERDGEK platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} +build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # # RUMBA32 From 4588d836a3b6fa7560c6f1bc5c23aa93a1609d71 Mon Sep 17 00:00:00 2001 From: charlespick Date: Sat, 8 May 2021 20:46:35 -0700 Subject: [PATCH 0079/2168] Update Advanced Pause description (#21829) Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7d89cf5205..3ec45f3f46 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2301,14 +2301,15 @@ #endif // HAS_MULTI_EXTRUDER /** - * Advanced Pause - * Experimental feature for filament change support and for parking the nozzle when paused. - * Adds the GCode M600 for initiating filament change. - * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. + * Advanced Pause for Filament Change + * - Adds the G-code M600 Filament Change to initiate a filament change. + * - This feature is required for the default FILAMENT_RUNOUT_SCRIPT. * - * Requires an LCD display. - * Requires NOZZLE_PARK_FEATURE. - * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. + * Requirements: + * - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE. + * - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER. + * + * Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park. */ //#define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -3484,7 +3485,7 @@ #define PROPORTIONAL_FONT_RATIO 1.0 /** - * Spend 28 bytes of SRAM to optimize the GCode parser + * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER From 49548c343deb1e7f38f6027af20c02a79dbe5031 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 May 2021 03:50:51 -0500 Subject: [PATCH 0080/2168] Optimize G-code flag parameters (#21849) --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 40 ++++++++++---------- Marlin/src/feature/encoder_i2c.cpp | 14 +++---- Marlin/src/feature/fwretract.cpp | 14 +++---- Marlin/src/gcode/bedlevel/G26.cpp | 8 ++-- Marlin/src/gcode/bedlevel/M420.cpp | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 12 +++--- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/bedlevel/ubl/M421.cpp | 25 ++++++------ Marlin/src/gcode/calibrate/G28.cpp | 6 +-- Marlin/src/gcode/calibrate/G33.cpp | 4 +- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 14 +++---- Marlin/src/gcode/feature/powerloss/M1000.cpp | 4 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 12 +++--- Marlin/src/gcode/feature/runout/M412.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M122.cpp | 2 +- Marlin/src/gcode/gcode_d.cpp | 2 +- Marlin/src/gcode/host/M114.cpp | 6 +-- Marlin/src/gcode/motion/G0_G1.cpp | 6 +-- Marlin/src/gcode/motion/M290.cpp | 2 +- Marlin/src/gcode/parser.h | 2 + Marlin/src/gcode/sd/M27.cpp | 2 +- Marlin/src/gcode/sd/M808.cpp | 2 +- Marlin/src/gcode/temp/M106_M107.cpp | 2 +- Marlin/src/gcode/temp/M303.cpp | 2 +- 25 files changed, 95 insertions(+), 94 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 6130123f7a..6f1425b60c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -306,7 +306,7 @@ void unified_bed_leveling::G29() { if (G29_parse_parameters()) return; // Abort on parameter error const int8_t p_val = parser.intval('P', -1); - const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'); + const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); #if ENABLED(HAS_MULTI_HOTEND) const uint8_t old_tool_index = active_extruder; #endif @@ -315,7 +315,7 @@ void unified_bed_leveling::G29() { if (may_move) { planner.synchronize(); // Send 'N' to force homing before G29 (internal only) - if (axes_should_home() || parser.seen('N')) gcode.home_all_axes(); + if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes(); TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); } @@ -380,7 +380,7 @@ void unified_bed_leveling::G29() { // Allow the user to specify the height because 10mm is a little extreme in some cases. for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed - z_values[x][y] += parser.seen('C') ? param.C_constant : 9.99f; + z_values[x][y] += parser.seen_test('C') ? param.C_constant : 9.99f; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); } break; @@ -389,7 +389,7 @@ void unified_bed_leveling::G29() { #if HAS_BED_PROBE - if (parser.seen('J')) { + if (parser.seen_test('J')) { save_ubl_active_state_and_disable(); tilt_mesh_based_on_probed_grid(param.J_grid_size == 0); // Zero size does 3-Point restore_ubl_active_state_and_leave(); @@ -402,7 +402,7 @@ void unified_bed_leveling::G29() { #endif // HAS_BED_PROBE - if (parser.seen('P')) { + if (parser.seen_test('P')) { if (WITHIN(param.P_phase, 0, 1) && storage_slot == -1) { storage_slot = 0; SERIAL_ECHOLNPGM("Default storage slot 0 selected."); @@ -423,7 +423,7 @@ void unified_bed_leveling::G29() { // // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe // - if (!parser.seen('C')) { + if (!parser.seen_test('C')) { invalidate(); SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); } @@ -433,7 +433,7 @@ void unified_bed_leveling::G29() { SERIAL_DECIMAL(param.XY_pos.y); SERIAL_ECHOLNPGM(").\n"); } - probe_entire_mesh(param.XY_pos, parser.seen('T'), parser.seen('E'), parser.seen('U')); + probe_entire_mesh(param.XY_pos, parser.seen_test('T'), parser.seen_test('E'), parser.seen_test('U')); report_current_position(); probe_deployed = true; @@ -449,7 +449,7 @@ void unified_bed_leveling::G29() { SERIAL_ECHOLNPGM("Manually probing unreachable points."); do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - if (parser.seen('C') && !param.XY_seen) { + if (parser.seen_test('C') && !param.XY_seen) { /** * Use a good default location for the path. @@ -483,7 +483,7 @@ void unified_bed_leveling::G29() { } const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES); - manually_probe_remaining_mesh(param.XY_pos, height, param.B_shim_thickness, parser.seen('T')); + manually_probe_remaining_mesh(param.XY_pos, height, param.B_shim_thickness, parser.seen_test('T')); SERIAL_ECHOLNPGM("G29 P2 finished."); @@ -555,7 +555,7 @@ void unified_bed_leveling::G29() { case 4: // Fine Tune (i.e., Edit) the Mesh #if HAS_LCD_MENU - fine_tune_mesh(param.XY_pos, parser.seen('T')); + fine_tune_mesh(param.XY_pos, parser.seen_test('T')); #else SERIAL_ECHOLNPGM("?P4 is only available when an LCD is present."); return; @@ -574,14 +574,14 @@ void unified_bed_leveling::G29() { // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is // good to have the extra information. Soon... we prune this to just a few items // - if (parser.seen('W')) g29_what_command(); + if (parser.seen_test('W')) g29_what_command(); // // When we are fully debugged, this may go away. But there are some valid // use cases for the users. So we can wait and see what to do with it. // - if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh + if (parser.seen_test('K')) // Kompare Current Mesh Data to Specified Stored Mesh g29_compare_current_mesh_to_stored_mesh(); #endif // UBL_DEVEL_DEBUGGING @@ -640,7 +640,7 @@ void unified_bed_leveling::G29() { SERIAL_ECHOLNPGM("Done."); } - if (parser.seen('T')) + if (parser.seen_test('T')) display_map(param.T_map_type); LEAVE: @@ -915,7 +915,7 @@ void set_message_with_feedback(PGM_P const msg_P) { if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing - if (parser.seen('B')) { + if (parser.seen_test('B')) { SERIAL_ECHOPGM_P(GET_TEXT(MSG_UBL_BC_INSERT)); LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); } @@ -954,7 +954,7 @@ void set_message_with_feedback(PGM_P const msg_P) { * NOTE: Blocks the G-code queue and captures Marlin UI during use. */ void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) { - if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + if (!parser.seen_test('R')) // fine_tune_mesh() is special. If no repetition count flag is specified param.R_repetition = 1; // do exactly one mesh location. Otherwise use what the parser decided. #if ENABLED(UBL_MESH_EDIT_MOVES_Z) @@ -1091,7 +1091,7 @@ bool unified_bed_leveling::G29_parse_parameters() { } } - param.V_verbosity = parser.seen('V') ? parser.value_int() : 0; + param.V_verbosity = parser.intval('V'); if (!WITHIN(param.V_verbosity, 0, 4)) { SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n"); err_flag = true; @@ -1153,15 +1153,15 @@ bool unified_bed_leveling::G29_parse_parameters() { * Leveling is being enabled here with old data, possibly * none. Error handling should disable for safety... */ - if (parser.seen('A')) { - if (parser.seen('D')) { + if (parser.seen_test('A')) { + if (parser.seen_test('D')) { SERIAL_ECHOLNPGM("?Can't activate and deactivate at the same time.\n"); return UBL_ERR; } set_bed_leveling_enabled(true); report_state(); } - else if (parser.seen('D')) { + else if (parser.seen_test('D')) { set_bed_leveling_enabled(false); report_state(); } @@ -1520,7 +1520,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); - measured_z = probe.probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling + measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling abort_flag = isnan(measured_z); diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index abaa93f767..b3265b2c59 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -819,11 +819,11 @@ int8_t I2CPositionEncodersMgr::parse() { void I2CPositionEncodersMgr::M860() { if (parse()) return; - const bool hasU = parser.seen('U'), hasO = parser.seen('O'); + const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O'); if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); } @@ -956,10 +956,10 @@ void I2CPositionEncodersMgr::M864() { return; } else { - if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X; - else if (parser.seen('Y')) newAddress = I2CPE_PRESET_ADDR_Y; - else if (parser.seen('Z')) newAddress = I2CPE_PRESET_ADDR_Z; - else if (parser.seen('E')) newAddress = I2CPE_PRESET_ADDR_E; + if (parser.seen_test('X')) newAddress = I2CPE_PRESET_ADDR_X; + else if (parser.seen_test('Y')) newAddress = I2CPE_PRESET_ADDR_Y; + else if (parser.seen_test('Z')) newAddress = I2CPE_PRESET_ADDR_Z; + else if (parser.seen_test('E')) newAddress = I2CPE_PRESET_ADDR_E; else return; } @@ -1012,7 +1012,7 @@ void I2CPositionEncodersMgr::M865() { void I2CPositionEncodersMgr::M866() { if (parse()) return; - const bool hasR = parser.seen('R'); + const bool hasR = parser.seen_test('R'); if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index bfcdb8c001..d133d6060c 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -212,10 +212,10 @@ void FWRetract::retract(const bool retracting */ void FWRetract::M207() { if (!parser.seen("FSWZ")) return M207_report(); - if (parser.seen('S')) settings.retract_length = parser.value_axis_units(E_AXIS); - if (parser.seen('F')) settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('Z')) settings.retract_zraise = parser.value_linear_units(); - if (parser.seen('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS); + if (parser.seenval('S')) settings.retract_length = parser.value_axis_units(E_AXIS); + if (parser.seenval('F')) settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seenval('Z')) settings.retract_zraise = parser.value_linear_units(); + if (parser.seenval('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS); } void FWRetract::M207_report(const bool forReplay/*=false*/) { @@ -238,10 +238,10 @@ void FWRetract::M207_report(const bool forReplay/*=false*/) { */ void FWRetract::M208() { if (!parser.seen("FSRW")) return M208_report(); - if (parser.seen('S')) settings.retract_recover_extra = parser.value_axis_units(E_AXIS); - if (parser.seen('F')) settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seen('S')) settings.retract_recover_extra = parser.value_axis_units(E_AXIS); + if (parser.seen('F')) settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); if (parser.seen('R')) settings.swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS); + if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS); } void FWRetract::M208_report(const bool forReplay/*=false*/) { diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index fe039def73..1e70652bdc 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -648,12 +648,12 @@ void GcodeSuite::G26() { #if HAS_LCD_MENU g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1); #else - if (!parser.seen('R')) { + if (parser.seen('R')) + g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + else { SERIAL_ECHOLNPGM("?(R)epeat must be specified when not using an LCD."); return; } - else - g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; #endif if (g26_repeats < 1) { SERIAL_ECHOLNPGM("?(R)epeat value not plausible; must be at least 1."); @@ -671,7 +671,7 @@ void GcodeSuite::G26() { /** * Wait until all parameters are verified before altering the state! */ - set_bed_leveling_enabled(!parser.seen('D')); + set_bed_leveling_enabled(!parser.seen_test('D')); do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index e42a590265..703e73b5a4 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -133,7 +133,7 @@ void GcodeSuite::M420() { #endif // AUTO_BED_LEVELING_UBL - const bool seenV = parser.seen('V'); + const bool seenV = parser.seen_test('V'); #if HAS_MESH diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 3bd96ef495..a8c3f45cdc 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -223,7 +223,7 @@ G29_TYPE GcodeSuite::G29() { reset_stepper_timeout(); - const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen('Q'); + const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -235,7 +235,7 @@ G29_TYPE GcodeSuite::G29() { if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false); #endif - const bool seenA = TERN0(PROBE_MANUALLY, parser.seen('A')), + const bool seenA = TERN0(PROBE_MANUALLY, parser.seen_test('A')), no_action = seenA || seenQ, faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action; @@ -245,7 +245,7 @@ G29_TYPE GcodeSuite::G29() { } // Send 'N' to force homing before G29 (internal only) - if (parser.seen('N')) + if (parser.seen_test('N')) process_subcommands_now_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); // Don't allow auto-leveling without homing first @@ -275,7 +275,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - const bool seen_w = parser.seen('W'); + const bool seen_w = parser.seen_test('W'); if (seen_w) { if (!leveling_is_valid()) { SERIAL_ERROR_MSG("No bilinear grid"); @@ -308,7 +308,7 @@ G29_TYPE GcodeSuite::G29() { if (abl.reenable) report_current_position(); } G29_RETURN(false); - } // parser.seen('W') + } // parser.seen_test('W') #else @@ -317,7 +317,7 @@ G29_TYPE GcodeSuite::G29() { #endif // Jettison bed leveling data - if (!seen_w && parser.seen('J')) { + if (!seen_w && parser.seen_test('J')) { reset_bed_level(); G29_RETURN(false); } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index afc6aad32c..07721330ba 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -87,7 +87,7 @@ void GcodeSuite::G29() { mbl.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject_P(parser.seen('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2")); + queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2")); return; } state = MeshNext; diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index 45c203aaca..f1e1b76126 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -21,7 +21,7 @@ */ /** - * unified.cpp - Unified Bed Leveling + * M421.cpp - Unified Bed Leveling */ #include "../../../inc/MarlinConfig.h" @@ -39,31 +39,34 @@ * M421: Set a single Mesh Bed Leveling Z coordinate * * Usage: - * M421 I J Z - * M421 I J Q - * M421 I J N - * M421 C Z - * M421 C Q + * M421 I J Z : Set the Mesh Point IJ to the Z value + * M421 I J Q : Add the Q value to the Mesh Point IJ + * M421 I J N : Set the Mesh Point IJ to NAN (not set) + * M421 C Z : Set the closest Mesh Point to the Z value + * M421 C Q : Add the Q value to the closest Mesh Point */ void GcodeSuite::M421() { xy_int8_t ij = { int8_t(parser.intval('I', -1)), int8_t(parser.intval('J', -1)) }; const bool hasI = ij.x >= 0, hasJ = ij.y >= 0, - hasC = parser.seen('C'), - hasN = parser.seen('N'), + hasC = parser.seen_test('C'), + hasN = parser.seen_test('N'), hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position); + // Test for bad parameter combinations if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN)) SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS); + + // Test for I J out of range else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { - float &zval = ubl.z_values[ij.x][ij.y]; - zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); + float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point + zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 10e094cba7..92bbb8e6c5 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -219,7 +219,7 @@ void GcodeSuite::G28() { #endif #if ENABLED(MARLIN_DEV_MODE) - if (parser.seen('S')) { + if (parser.seen_test('S')) { LOOP_XYZ(a) set_axis_is_at_home((AxisEnum)a); sync_plan_position(); SERIAL_ECHOLNPGM("Simulated Homing"); @@ -321,10 +321,10 @@ void GcodeSuite::G28() { #else - const bool homeZ = parser.seen('Z'), + const bool homeZ = parser.seen_test('Z'), needX = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(X_AXIS))), needY = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(Y_AXIS))), - homeX = needX || parser.seen('X'), homeY = needY || parser.seen('Y'), + homeX = needX || parser.seen_test('X'), homeY = needY || parser.seen_test('Y'), home_all = homeX == homeY && homeX == homeZ, // All or None doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index d60099a330..a8de519335 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -395,7 +395,7 @@ void GcodeSuite::G33() { return; } - const bool towers_set = !parser.seen('T'); + const bool towers_set = !parser.seen_test('T'); const float calibration_precision = parser.floatval('C', 0.0f); if (calibration_precision < 0) { @@ -415,7 +415,7 @@ void GcodeSuite::G33() { return; } - const bool stow_after_each = parser.seen('E'); + const bool stow_after_each = parser.seen_test('E'); const bool _0p_calibration = probe_points == 0, _1p_calibration = probe_points == 1 || probe_points == -1, diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 3e495eb9d3..351ef01f34 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -56,7 +56,7 @@ */ void GcodeSuite::M125() { // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); + const float retract = -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH)); xyz_pos_t park_point = NOZZLE_PARK_POINT; diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 6cab3ad352..2daa7d999a 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -81,8 +81,8 @@ void GcodeSuite::M600() { #if ENABLED(DUAL_X_CARRIAGE) int8_t DXC_ext = target_extruder; - if (!parser.seen('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout. - // In this case, for duplicating modes set DXC_ext to the extruder that ran out. + if (!parser.seen_test('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout. + // In this case, for duplicating modes set DXC_ext to the extruder that ran out. #if MULTI_FILAMENT_SENSOR if (idex_is_duplicating()) DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT2_STATE) ? 1 : 0; @@ -110,7 +110,7 @@ void GcodeSuite::M600() { #endif // Initial retract before move to filament change position - const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH)); + const float retract = -ABS(parser.axisunitsval('E', E_AXIS, PAUSE_PARK_RETRACT_LENGTH)); xyz_pos_t park_point NOZZLE_PARK_POINT; @@ -132,15 +132,11 @@ void GcodeSuite::M600() { fast_load_length = 0.0f; #else // Unload filament - const float unload_length = -ABS(parser.seen('U') ? parser.value_axis_units(E_AXIS) - : fc_settings[active_extruder].unload_length); - + const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)); // Slow load filament constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH; - // Fast load filament - const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) - : fc_settings[active_extruder].load_length); + const float fast_load_length = ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length)); #endif const int beep_count = parser.intval('B', -1 diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index a31b7732f4..ea92dc66b3 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -59,7 +59,7 @@ inline void plr_error(PGM_P const prefix) { void GcodeSuite::M1000() { if (recovery.valid()) { - if (parser.seen('S')) { + if (parser.seen_test('S')) { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(DWIN_CREALITY_LCD) @@ -70,7 +70,7 @@ void GcodeSuite::M1000() { SERIAL_ECHO_MSG("Resume requires LCD."); #endif } - else if (parser.seen('C')) { + else if (parser.seen_test('C')) { #if HAS_LCD_MENU lcd_power_loss_recovery_cancel(); #else diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index e6e3ac3b3c..18aeb507b1 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -48,14 +48,14 @@ void GcodeSuite::M413() { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) if (parser.seen("RL")) recovery.load(); - if (parser.seen('W')) recovery.save(true); - if (parser.seen('P')) recovery.purge(); - if (parser.seen('D')) recovery.debug(PSTR("M413")); + if (parser.seen_test('W')) recovery.save(true); + if (parser.seen_test('P')) recovery.purge(); + if (parser.seen_test('D')) recovery.debug(PSTR("M413")); #if PIN_EXISTS(POWER_LOSS) - if (parser.seen('O')) recovery._outage(); + if (parser.seen_test('O')) recovery._outage(); #endif - if (parser.seen('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n")); - if (parser.seen('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n")); + if (parser.seen_test('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n")); + if (parser.seen_test('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n")); #endif } diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 130f9c83e3..540a160623 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M412() { #if ENABLED(HOST_ACTION_COMMANDS) if (parser.seen('H')) runout.host_handling = parser.value_bool(); #endif - const bool seenR = parser.seen('R'), seenS = parser.seen('S'); + const bool seenR = parser.seen_test('R'), seenS = parser.seen('S'); if (seenR || seenS) runout.reset(); if (seenS) runout.enabled = parser.value_bool(); #if HAS_FILAMENT_RUNOUT_DISTANCE diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 46e4365f38..429638665f 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -48,7 +48,7 @@ void GcodeSuite::M122() { tmc_set_report_interval(interval); #endif - if (parser.seen('V')) + if (parser.seen_test('V')) tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e); else tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e); diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index a8a6bdfc3d..52a273964a 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -52,7 +52,7 @@ break; case 10: - kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen('P')); + kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P')); break; case 1: { diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index dd62f0ad2e..e5dc90fb30 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -193,7 +193,7 @@ void GcodeSuite::M114() { #if ENABLED(M114_DETAIL) - if (parser.seen('D')) { + if (parser.seen_test('D')) { #if DISABLED(M114_LEGACY) planner.synchronize(); #endif @@ -201,14 +201,14 @@ void GcodeSuite::M114() { report_current_position_detail(); return; } - if (parser.seen('E')) { + if (parser.seen_test('E')) { SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); return; } #endif #if ENABLED(M114_REALTIME) - if (parser.seen('R')) { report_real_position(); return; } + if (parser.seen_test('R')) { report_real_position(); return; } #endif TERN_(M114_LEGACY, planner.synchronize()); diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 64c07d1d89..089e00ab95 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -49,9 +49,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (IsRunning() #if ENABLED(NO_MOTION_BEFORE_HOMING) && !homing_needed_error( - (parser.seen('X') ? _BV(X_AXIS) : 0) - | (parser.seen('Y') ? _BV(Y_AXIS) : 0) - | (parser.seen('Z') ? _BV(Z_AXIS) : 0) ) + (parser.seen_test('X') ? _BV(X_AXIS) : 0) + | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0) + | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0) ) #endif ) { TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING)); diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 7dd89a6fac..7cfab8d2db 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -74,7 +74,7 @@ void GcodeSuite::M290() { const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2); babystep.add_mm((AxisEnum)a, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_probe_offset(offs); + if (a == Z_AXIS && parser.boolval('P', true)) mod_probe_offset(offs); #endif } #else diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index b3625ec05e..3aec17554b 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -408,6 +408,8 @@ public: static inline int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } static inline uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } + static inline float axisunitsval(const char c, const AxisEnum a, const float dval=0) + { return seenval(c) ? value_axis_units(a) : dval; } static inline celsius_t celsiusval(const char c, const float dval=0) { return seenval(c) ? value_celsius() : dval; } #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/gcode/sd/M27.cpp b/Marlin/src/gcode/sd/M27.cpp index f6e48d4ae8..88238190e2 100644 --- a/Marlin/src/gcode/sd/M27.cpp +++ b/Marlin/src/gcode/sd/M27.cpp @@ -33,7 +33,7 @@ * OR, with 'C' get the current filename. */ void GcodeSuite::M27() { - if (parser.seen('C')) { + if (parser.seen_test('C')) { SERIAL_ECHOPGM("Current file: "); card.printSelectedFilename(); return; diff --git a/Marlin/src/gcode/sd/M808.cpp b/Marlin/src/gcode/sd/M808.cpp index 0d11b16f8a..548683430c 100644 --- a/Marlin/src/gcode/sd/M808.cpp +++ b/Marlin/src/gcode/sd/M808.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M808() { // Allowed to go into the queue for logging purposes. // M808 K sent from the host to cancel all loops - if (parser.seen('K')) repeat.cancel(); + if (parser.seen_test('K')) repeat.cancel(); } diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 3ce08aafb6..73dc82b8df 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -68,7 +68,7 @@ void GcodeSuite::M106() { if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); #endif - const uint16_t dspeed = parser.seen('A') ? thermalManager.fan_speed[active_extruder] : 255; + const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; uint16_t speed = dspeed; diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index e49381cdf6..ad3afe6e46 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -47,7 +47,7 @@ void GcodeSuite::M303() { #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) - if (parser.seen('D')) { + if (parser.seen_test('D')) { thermalManager.pid_debug_flag ^= true; SERIAL_ECHO_START(); SERIAL_ECHOPGM("PID Debug "); From b12d0d06ebaac1db5a87750dd96b9dcbaf2ecf72 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sun, 9 May 2021 01:52:53 -0700 Subject: [PATCH 0081/2168] Unify BTT Motor Expansion Options (#21823) --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 27 +++--- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 72 +++++++++------ .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 89 ++++++++++++------- 4 files changed, 114 insertions(+), 76 deletions(-) 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 aa94bc935d..ba60db472e 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -279,7 +279,7 @@ #undef SPEAKER #endif -#elif HAS_WIRED_LCD && !HAS_BTT_EXP_MOT +#elif HAS_WIRED_LCD && !BTT_MOTOR_EXPANSION #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) #error "CAUTION! ANET_FULL_GRAPHICS_LCD_ALT_WIRING requires wiring modifications. See 'pins_BTT_SKR_V1_4.h' for details. Comment out this line to continue." diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index eadb91a8b3..01f2303a35 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -23,11 +23,11 @@ #include "env_validate.h" -// If you have the Big tree tech driver expansion module, enable HAS_BTT_EXP_MOT +// If you have the BigTreeTech driver expansion module, enable BTT_MOTOR_EXPANSION // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT -//#define HAS_BTT_EXP_MOT 1 +//#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, HAS_BTT_EXP_MOT) +#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else @@ -138,16 +138,15 @@ #error "No custom SD drive cable defined for this board." #endif -#if HAS_BTT_EXP_MOT - - /** _____ _____ - * NC | · · | GND NC | · · | GND - * NC | · · | 1.31 (M1EN) (M2EN) 1.23 | · · | 1.22 (M3EN) - * (M1STP) 0.18 | · · 3.25 (M1DIR) (M1RX) 1.21 | · · 1.20 (M1DIAG) - * (M2DIR) 0.16 | · · | 3.26 (M2STP) (M2RX) 1.19 | · · | 1.18 (M2DIAG) - * (M3DIR) 0.15 | · · | 0.17 (M3STP) (M3RX) 0.28 | · · | 1.30 (M3DIAG) - * ----- ----- - * EXP2 EXP1 +#if ENABLED(BTT_MOTOR_EXPANSION) + /** _____ _____ + * NC | . . | GND NC | . . | GND + * NC | . . | M1EN M2EN | . . | M3EN + * M1STP | . . M1DIR M1RX | . . M1DIAG + * M2DIR | . . | M2STP M2RX | . . | M2DIAG + * M3DIR | . . | M3STP M3RX | . . | M3DIAG + * ----- ----- + * EXP2 EXP1 * * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ @@ -195,4 +194,4 @@ #define E4_ENABLE_PIN EXP2_04_PIN #endif -#endif // HAS_BTT_EXP_MOT +#endif // BTT_MOTOR_EXPANSION diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 01ba3d72f6..67907affa7 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -23,11 +23,16 @@ #include "env_validate.h" -// BigTreeTech driver expansion module https://bit.ly/3ptRRoj +// If you have the BigTreeTech driver expansion module, enable BTT_MOTOR_EXPANSION +// https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION #if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #error "It's not possible to have both LCD and motor expansion module on EXP1/EXP2." + #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) + #define EXP_MOT_USE_EXP2_ONLY 1 + #else + #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." + #endif #endif // Use one of these or SDCard-based Emulation will be used @@ -311,48 +316,59 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** - * _____ _____ - * NC | · · | GND NC | · · | GND - * NC | · · | PF12 (M1EN) (M2EN) PG7 | · · | PG6 (M3EN) - * (M1STP) PB15 | · · PF11 (M1DIR) (M1RX) PG3 | · · PG2 (M1DIAG) - * (M2DIR) PB12 | · · | PG10 (M2STP) (M2RX) PD10 | · · | PD11 (M2DIAG) - * (M3DIR) PB13 | · · | PB14 (M3STP) (M3RX) PA8 | · · | PG4 (M3DIAG) - * ----- ----- - * EXP2 EXP1 + /** _____ _____ + * NC | . . | GND NC | . . | GND + * NC | . . | M1EN M2EN | . . | M3EN + * M1STP | . . M1DIR M1RX | . . M1DIAG + * M2DIR | . . | M2STP M2RX | . . | M2DIAG + * M3DIR | . . | M3STP M3RX | . . | M3DIAG + * ----- ----- + * EXP2 EXP1 + * + * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ // M1 on Driver Expansion Module #define E3_STEP_PIN EXP2_05_PIN #define E3_DIR_PIN EXP2_06_PIN #define E3_ENABLE_PIN EXP2_04_PIN - #define E3_DIAG_PIN EXP1_06_PIN - #define E3_CS_PIN EXP1_05_PIN - #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_05_PIN - #define E3_SERIAL_RX_PIN EXP1_05_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E3_DIAG_PIN EXP1_06_PIN + #define E3_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E3_SERIAL_TX_PIN EXP1_05_PIN + #define E3_SERIAL_RX_PIN EXP1_05_PIN + #endif #endif // M2 on Driver Expansion Module #define E4_STEP_PIN EXP2_08_PIN #define E4_DIR_PIN EXP2_07_PIN - #define E4_ENABLE_PIN EXP1_03_PIN - #define E4_DIAG_PIN EXP1_08_PIN - #define E4_CS_PIN EXP1_07_PIN - #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_07_PIN - #define E4_SERIAL_RX_PIN EXP1_07_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E4_ENABLE_PIN EXP1_03_PIN + #define E4_DIAG_PIN EXP1_08_PIN + #define E4_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_07_PIN + #define E4_SERIAL_RX_PIN EXP1_07_PIN + #endif + #else + #define E4_ENABLE_PIN EXP2_04_PIN #endif // M3 on Driver Expansion Module #define E5_STEP_PIN EXP2_10_PIN #define E5_DIR_PIN EXP2_09_PIN - #define E5_ENABLE_PIN EXP1_04_PIN - #define E5_DIAG_PIN EXP1_10_PIN - #define E5_CS_PIN EXP1_09_PIN - #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_09_PIN - #define E5_SERIAL_RX_PIN EXP1_09_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E5_ENABLE_PIN EXP1_04_PIN + #define E5_DIAG_PIN EXP1_10_PIN + #define E5_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_09_PIN + #define E5_SERIAL_RX_PIN EXP1_09_PIN + #endif + #else + #define E5_ENABLE_PIN EXP2_04_PIN #endif #endif // BTT_MOTOR_EXPANSION diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 14cc047649..a69041e2d4 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -23,6 +23,18 @@ #include "env_validate.h" +// If you have the BigTreeTech driver expansion module, enable BTT_MOTOR_EXPANSION +// https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT +//#define BTT_MOTOR_EXPANSION + +#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) + #define EXP_MOT_USE_EXP2_ONLY 1 + #else + #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." + #endif +#endif + // Use one of these or SDCard-based Emulation will be used #if NO_EEPROM_SELECTED //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation @@ -349,48 +361,59 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** - * _____ _____ - * NC | · · | GND NC | · · | GND - * NC | · · | PF12 (M1EN) (M2EN) PG7 | · · | PG6 (M3EN) - * (M1STP) PB15 | · · PF11 (M1DIR) (M1RX) PG3 | · · PG2 (M1DIAG) - * (M2DIR) PB12 | · · | PG10 (M2STP) (M2RX) PD10 | · · | PD11 (M2DIAG) - * (M3DIR) PB13 | · · | PB14 (M3STP) (M3RX) PA8 | · · | PG4 (M3DIAG) - * ----- ----- - * EXP2 EXP1 + /** _____ _____ + * NC | . . | GND NC | . . | GND + * NC | . . | M1EN M2EN | . . | M3EN + * M1STP | . . M1DIR M1RX | . . M1DIAG + * M2DIR | . . | M2STP M2RX | . . | M2DIAG + * M3DIR | . . | M3STP M3RX | . . | M3DIAG + * ----- ----- + * EXP2 EXP1 + * + * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ // M1 on Driver Expansion Module - #define E3_STEP_PIN EXP2_05_PIN - #define E3_DIR_PIN EXP2_06_PIN - #define E3_ENABLE_PIN EXP2_04_PIN - #define E3_DIAG_PIN EXP1_06_PIN - #define E3_CS_PIN EXP1_05_PIN - #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_05_PIN - #define E3_SERIAL_RX_PIN EXP1_05_PIN + #define E2_STEP_PIN EXP2_05_PIN + #define E2_DIR_PIN EXP2_06_PIN + #define E2_ENABLE_PIN EXP2_04_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E2_DIAG_PIN EXP1_06_PIN + #define E2_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E2_SERIAL_TX_PIN EXP1_05_PIN + #define E2_SERIAL_RX_PIN EXP1_05_PIN + #endif #endif // M2 on Driver Expansion Module - #define E4_STEP_PIN EXP2_08_PIN - #define E4_DIR_PIN EXP2_07_PIN - #define E4_ENABLE_PIN EXP1_03_PIN - #define E4_DIAG_PIN EXP1_08_PIN - #define E4_CS_PIN EXP1_07_PIN - #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_07_PIN - #define E4_SERIAL_RX_PIN EXP1_07_PIN + #define E3_STEP_PIN EXP2_08_PIN + #define E3_DIR_PIN EXP2_07_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E3_ENABLE_PIN EXP1_03_PIN + #define E3_DIAG_PIN EXP1_08_PIN + #define E3_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E3_SERIAL_TX_PIN EXP1_07_PIN + #define E3_SERIAL_RX_PIN EXP1_07_PIN + #endif + #else + #define E3_ENABLE_PIN EXP2_04_PIN #endif // M3 on Driver Expansion Module - #define E5_STEP_PIN EXP2_10_PIN - #define E5_DIR_PIN EXP2_09_PIN - #define E5_ENABLE_PIN EXP1_04_PIN - #define E5_DIAG_PIN EXP1_10_PIN - #define E5_CS_PIN EXP1_09_PIN - #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_09_PIN - #define E5_SERIAL_RX_PIN EXP1_09_PIN + #define E4_STEP_PIN EXP2_10_PIN + #define E4_DIR_PIN EXP2_09_PIN + #if !EXP_MOT_USE_EXP2_ONLY + #define E4_ENABLE_PIN EXP1_04_PIN + #define E4_DIAG_PIN EXP1_10_PIN + #define E4_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_09_PIN + #define E4_SERIAL_RX_PIN EXP1_09_PIN + #endif + #else + #define E4_ENABLE_PIN EXP2_04_PIN #endif #endif // BTT_MOTOR_EXPANSION From fff5e9ba4a45bbb9c4c99da9b2c5998548f925a7 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sun, 9 May 2021 22:58:36 +0200 Subject: [PATCH 0082/2168] Fix insane mmu2 timeout (#21855) * Fix insane mmu2 timeout Fix insane timeout value. Now match original Prusa firmware. * Update mmu2.cpp Co-authored-by: Luu Lac <45380455+shitcreek@users.noreply.github.com> --- Marlin/src/feature/mmu/mmu2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index c1c34f8eee..8a4f5ae071 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -159,7 +159,7 @@ void MMU2::mmu_loop() { MMU2_COMMAND("S1"); // Read Version state = -2; } - else if (millis() > 3000000) { + else if (millis() > 30000) { // 30sec after reset disable MMU SERIAL_ECHOLNPGM("MMU not responding - DISABLED"); state = 0; } From 4a7f5603de04f89aeb47cd68803b810517136acf Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 10 May 2021 01:00:29 +0000 Subject: [PATCH 0083/2168] [cron] Bump distribution date (2021-05-10) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9991da493f..ad4f39ab70 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 "2021-05-09" + #define STRING_DISTRIBUTION_DATE "2021-05-10" #endif /** From 8e56f9366de1b0d78600064aca3f905b4d1d7300 Mon Sep 17 00:00:00 2001 From: tobuh <32395668+tobuh@users.noreply.github.com> Date: Mon, 10 May 2021 14:24:35 +0200 Subject: [PATCH 0084/2168] Fix and improve Power-Loss Recovery (#21779) Co-authored-by: Scott Lahteine --- Marlin/src/feature/pause.cpp | 17 +- Marlin/src/feature/powerloss.cpp | 172 ++++++++++++------ Marlin/src/feature/powerloss.h | 3 +- Marlin/src/gcode/feature/pause/M125.cpp | 2 - Marlin/src/gcode/sd/M24_M25.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 2 + .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 10 + buildroot/tests/rambo | 8 +- 8 files changed, 151 insertions(+), 65 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 58e0c3df0d..2bd3033808 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -406,6 +406,15 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Save current position resume_position = current_position; + // Will the nozzle be parking? + const bool do_park = !axes_should_home(); + + #if ENABLED(POWER_LOSS_RECOVERY) + // Save PLR info in case the power goes out while parked + const float park_raise = do_park ? nozzle.park_mode_0_height(park_point.z) - current_position.z : POWER_LOSS_ZRAISE; + if (was_sd_printing && recovery.enabled) recovery.save(true, park_raise, do_park); + #endif + // Wait for buffered blocks to complete planner.synchronize(); @@ -419,9 +428,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); } - // Park the nozzle by doing a Minimum Z Raise followed by an XY Move - if (!axes_should_home()) - nozzle.park(0, park_point); + // If axes don't need to home then the nozzle can park + if (do_park) nozzle.park(0, park_point); // Park the nozzle by doing a Minimum Z Raise followed by an XY Move #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; @@ -429,7 +437,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool set_duplication_enabled(false, DXC_ext); #endif - if (unload_length) // Unload the filament + // Unload the filament, if specified + if (unload_length) unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT); #if ENABLED(DUAL_X_CARRIAGE) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 9d6e0b42f5..552f1d9009 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -144,7 +144,7 @@ void PrintJobRecovery::prepare() { /** * Save the current machine state to the power-loss recovery file */ -void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) { +void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POWER_LOSS_ZRAISE*/, const bool raised/*=false*/) { // We don't check IS_SD_PRINTING here so a save may occur during a pause @@ -181,14 +181,12 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ info.current_position = current_position; info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s)); info.zraise = zraise; + info.flag.raised = raised; // Was Z raised before power-off? TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat); TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); - - #if HAS_MULTI_EXTRUDER - info.active_extruder = active_extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, info.active_extruder = active_extruder); #if DISABLED(NO_VOLUMETRICS) info.flag.volumetric_enabled = parser.volumetric_enabled; @@ -289,8 +287,9 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ constexpr float zraise = 0; #endif - // Save, including the limited Z raise - if (IS_SD_PRINTING()) save(true, zraise); + // Save the current position, distance that Z was (or should be) raised, + // and a flag whether the raise was already done here. + if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY)); // Disable all heaters to reduce power loss thermalManager.disable_all_heaters(); @@ -350,10 +349,10 @@ void PrintJobRecovery::resume() { } #endif - // Restore all hotend temperatures + // Heat hotend enough to soften material #if HAS_HOTEND HOTEND_LOOP() { - const celsius_t et = info.target_temperature[e]; + const celsius_t et = _MAX(info.target_temperature[e], 180); if (et) { #if HAS_MULTI_HOTEND sprintf_P(cmd, PSTR("T%iS"), e); @@ -365,37 +364,59 @@ void PrintJobRecovery::resume() { } #endif + // Interpret the saved Z according to flags + const float z_print = info.current_position.z, + z_raised = z_print + info.zraise; + // // Home the axes that can safely be homed, and // establish the current position as best we can. // + + gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0 + #if Z_HOME_DIR > 0 - // If Z homing goes to max... + float z_now = z_raised; + + // If Z homing goes to max then just move back to the "raised" position gcode.process_subcommands_now_P(PSTR( - "G92.9 E0\n" // Reset E to 0 - "G28R0" // Home all axes (no raise) - )); + "G28R0\n" // Home all axes (no raise) + "G1Z%sF1200" // Move Z down to (raised) height + ), + dtostrf(z_now, 1, 3, str_1) + ); #else - // If a Z raise occurred at outage restore Z, otherwise raise Z now - sprintf_P(cmd, PSTR("G92.9 E0 " TERN(BACKUP_POWER_SUPPLY, "Z%s", "Z0\nG1Z%s")), dtostrf(info.zraise, 1, 3, str_1)); - gcode.process_subcommands_now(cmd); + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) + #define HOMING_Z_DOWN 1 + #else + #define HOME_XY_ONLY 1 + #endif - // Home safely with no Z raise - gcode.process_subcommands_now_P(PSTR( - "G28R0" // No raise during G28 - #if IS_CARTESIAN && (DISABLED(POWER_LOSS_RECOVER_ZHOME) || defined(POWER_LOSS_ZHOME_POS)) - "XY" // Don't home Z on Cartesian unless overridden - #endif - )); + float z_now = info.flag.raised ? z_raised : z_print; + + // Reset E to 0 and set Z to the real position + #if HOME_XY_ONLY + sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + #endif + + // Does Z need to be raised now? It should be raised before homing XY. + if (z_raised > z_now) { + z_now = z_raised; + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + } + + // Home XY with no Z raise, and also home Z here if Z isn't homing down below. + gcode.process_subcommands_now_P(PSTR("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28 #endif - #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) - // Move to a safe XY position where Z can home while avoiding the print. - // If Z_SAFE_HOMING is enabled, its position must also be outside the print area! + #if HOMING_Z_DOWN + // Move to a safe XY position and home Z while avoiding the print. constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS; sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); gcode.process_subcommands_now(cmd); @@ -404,9 +425,24 @@ void PrintJobRecovery::resume() { // Mark all axes as having been homed (no effect on current_position) set_all_homed(); + #if HAS_LEVELING + // Restore Z fade and possibly re-enable bed leveling compensation. + // Leveling may already be enabled due to the ENABLE_LEVELING_AFTER_G28 option. + // TODO: Add a G28 parameter to leave leveling disabled. + sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); + gcode.process_subcommands_now(cmd); + + #if HOME_XY_ONLY + // The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9. + sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1)); + gcode.process_subcommands_now(cmd); + #endif + #endif + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) - // Z was homed. Now move Z back up to the saved Z height, plus the POWER_LOSS_ZRAISE. - sprintf_P(cmd, PSTR("G1Z%sF500"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1)); + // Z was homed down to the bed, so move up to the raised height. + z_now = z_raised; + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1)); gcode.process_subcommands_now(cmd); #endif @@ -429,8 +465,23 @@ void PrintJobRecovery::resume() { #endif #endif - // Select the previously active tool (with no_move) - #if HAS_MULTI_EXTRUDER + // Restore all hotend temperatures + #if HAS_HOTEND + HOTEND_LOOP() { + const celsius_t et = info.target_temperature[e]; + if (et) { + #if HAS_MULTI_HOTEND + sprintf_P(cmd, PSTR("T%iS"), e); + gcode.process_subcommands_now(cmd); + #endif + sprintf_P(cmd, PSTR("M109S%i"), et); + gcode.process_subcommands_now(cmd); + } + } + #endif + + // Restore the previously active tool (with no_move) + #if HAS_MULTI_EXTRUDER || HAS_MULTI_HOTEND sprintf_P(cmd, PSTR("T%i S"), info.active_extruder); gcode.process_subcommands_now(cmd); #endif @@ -457,15 +508,6 @@ void PrintJobRecovery::resume() { fwretract.current_hop = info.retract_hop; #endif - #if HAS_LEVELING - // Restore leveling state before 'G92 Z' to ensure - // the Z stepper count corresponds to the native Z. - if (info.fade || info.flag.leveling) { - sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); - gcode.process_subcommands_now(cmd); - } - #endif - #if ENABLED(GRADIENT_MIX) memcpy(&mixer.gradient, &info.gradient, sizeof(info.gradient)); #endif @@ -492,14 +534,8 @@ void PrintJobRecovery::resume() { ); gcode.process_subcommands_now(cmd); - // Move back to the saved Z - dtostrf(info.current_position.z, 1, 3, str_1); - #if Z_HOME_DIR > 0 || ENABLED(POWER_LOSS_RECOVER_ZHOME) - sprintf_P(cmd, PSTR("G1 Z%s F500"), str_1); - #else - gcode.process_subcommands_now_P(PSTR("G1 Z0 F200")); - sprintf_P(cmd, PSTR("G92.9 Z%s"), str_1); - #endif + // Move back down to the saved Z for printing + sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_print, 1, 3, str_1)); gcode.process_subcommands_now(cmd); // Restore the feedrate @@ -552,7 +588,15 @@ void PrintJobRecovery::resume() { } DEBUG_EOL(); - DEBUG_ECHOLNPAIR("zraise: ", info.zraise); + DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); + + DEBUG_ECHOLNPAIR("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : ""); + + #if ENABLED(GCODE_REPEAT_MARKERS) + DEBUG_ECHOLNPAIR("repeat index: ", info.stored_repeat.index); + LOOP_L_N(i, info.stored_repeat.index) + DEBUG_ECHOLNPAIR("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); + #endif #if HAS_HOME_OFFSET DEBUG_ECHOPGM("home_offset: "); @@ -572,12 +616,16 @@ void PrintJobRecovery::resume() { DEBUG_EOL(); #endif - DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); - #if HAS_MULTI_EXTRUDER DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder); #endif + #if DISABLED(NO_VOLUMETRICS) + DEBUG_ECHOPGM("filament_size:"); + LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPAIR(" ", info.filament_size[i]); + DEBUG_EOL(); + #endif + #if HAS_HOTEND DEBUG_ECHOPGM("target_temperature: "); HOTEND_LOOP() { @@ -601,8 +649,9 @@ void PrintJobRecovery::resume() { #endif #if HAS_LEVELING - DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling, " fade: ", info.fade); + DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade); #endif + #if ENABLED(FWRETRACT) DEBUG_ECHOPGM("retract: "); for (int8_t e = 0; e < EXTRUDERS; e++) { @@ -612,11 +661,28 @@ void PrintJobRecovery::resume() { DEBUG_EOL(); DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop); #endif + + // Mixing extruder and gradient + #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) + DEBUG_ECHOLNPAIR("gradient: ", info.gradient.enabled ? "ON" : "OFF"); + #endif + DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename); DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos); DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed); - DEBUG_ECHOLNPAIR("dryrun: ", AS_DIGIT(info.flag.dryrun)); - DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", info.flag.allow_cold_extrusion); + + DEBUG_ECHOPGM("axis_relative:"); + if (TEST(info.axis_relative, REL_X)) DEBUG_ECHOPGM(" REL_X"); + if (TEST(info.axis_relative, REL_Y)) DEBUG_ECHOPGM(" REL_Y"); + if (TEST(info.axis_relative, REL_Z)) DEBUG_ECHOPGM(" REL_Z"); + if (TEST(info.axis_relative, REL_E)) DEBUG_ECHOPGM(" REL_E"); + if (TEST(info.axis_relative, E_MODE_ABS)) DEBUG_ECHOPGM(" E_MODE_ABS"); + if (TEST(info.axis_relative, E_MODE_REL)) DEBUG_ECHOPGM(" E_MODE_REL"); + DEBUG_EOL(); + + DEBUG_ECHOLNPAIR("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); + DEBUG_ECHOLNPAIR("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); + DEBUG_ECHOLNPAIR("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index df3ae222a2..0fa9172fcf 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -117,6 +117,7 @@ typedef struct { // Misc. Marlin flags struct { + bool raised:1; // Raised before saved bool dryrun:1; // M111 S8 bool allow_cold_extrusion:1; // M302 P1 #if ENABLED(HAS_LEVELING) @@ -182,7 +183,7 @@ class PrintJobRecovery { static inline void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); } static void load(); - static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=0); + static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false); #if PIN_EXISTS(POWER_LOSS) static inline void outage() { diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 351ef01f34..2eb4ceea41 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -78,8 +78,6 @@ void GcodeSuite::M125() { // If possible, show an LCD prompt with the 'P' flag const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P')); - TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); - if (pause_print(retract, park_point, show_lcd, 0)) { if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index f46a964af0..4cb040feb3 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -105,7 +105,7 @@ void GcodeSuite::M25() { if (IS_SD_PRINTING()) card.pauseSDPrint(); #endif - #if ENABLED(POWER_LOSS_RECOVERY) + #if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS) if (recovery.enabled) recovery.save(true); #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bbd646a30d..c9aebe89ad 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2903,6 +2903,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING." #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." + #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR > 0 + #error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX." #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR < 0 && !defined(POWER_LOSS_ZHOME_POS) #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." #endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 7d98b64991..525b781599 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -39,6 +39,10 @@ #include "../../../../module/stepper/trinamic.h" #endif +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../../feature/powerloss.h" +#endif + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 10; #endif @@ -78,8 +82,13 @@ constexpr feedRate_t park_speed_xy = TERN(NOZZLE_PARK_FEATURE, NOZZLE_PARK_XY_FE void MKS_pause_print_move() { queue.exhaust(); position_before_pause = current_position; + + // Save the current position, the raise amount, and 'already raised' + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true, mks_park_pos.z, true)); + destination.z = _MIN(current_position.z + mks_park_pos.z, Z_MAX_POS); prepare_internal_move_to_destination(park_speed_z); + destination.set(X_MIN_POS + mks_park_pos.x, Y_MIN_POS + mks_park_pos.y); prepare_internal_move_to_destination(park_speed_xy); } @@ -89,6 +98,7 @@ void MKS_resume_print_move() { prepare_internal_move_to_destination(park_speed_xy); destination.z = position_before_pause.z; prepare_internal_move_to_destination(park_speed_z); + TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); } float z_offset_add = 0; diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 95260e58b4..87772a988b 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -14,9 +14,9 @@ opt_set MOTHERBOARD BOARD_RAMBO \ EXTRUDERS 2 TEMP_SENSOR_0 -2 TEMP_SENSOR_1 1 TEMP_SENSOR_BED 2 \ TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \ TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 3 HEATER_CHAMBER_PIN 45 \ - Z_HOME_DIR 1 GRID_MAX_POINTS_X 16 \ + GRID_MAX_POINTS_X 16 \ FANMUX0_PIN 53 -opt_disable USE_ZMIN_PLUG Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG +opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ FIX_MOUNTED_PROBE CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ @@ -32,7 +32,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME \ + PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL opt_add DEBUG_POWER_LOSS_RECOVERY @@ -43,7 +43,7 @@ exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | # restore_configs opt_set MOTHERBOARD BOARD_RAMBO \ - EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 \ + EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 Z_HOME_DIR 1 \ DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' \ LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ From 61ac1ed2f61e7d699354dbeb5f9fac5d75d7f7a6 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 11 May 2021 09:33:43 +1200 Subject: [PATCH 0085/2168] update FLSUN_HISPEED env to flsun_hispeedv1 (#21510) --- Marlin/src/pins/pins.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 70e6836a32..d38dc595f2 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -557,7 +557,7 @@ #elif MB(FLY_MINI) #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI #elif MB(FLSUN_HISPEED) - #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeed + #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103RE #elif MB(MINGDA_MPX_ARM_MINI) From 782ced6ff728b05b0a1bf668c5bae628340a9018 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 11 May 2021 01:00:06 +0000 Subject: [PATCH 0086/2168] [cron] Bump distribution date (2021-05-11) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ad4f39ab70..7e63f30775 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 "2021-05-10" + #define STRING_DISTRIBUTION_DATE "2021-05-11" #endif /** From dd16d6ad6e4857a4ead1e7791cfe6df3974ba87b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 May 2021 22:47:34 -0500 Subject: [PATCH 0087/2168] Update Chart.js to 2.9.4 Addressing CVE-2020-7746 --- buildroot/web-ui/data/www/chart.min.js | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) mode change 100644 => 100755 buildroot/web-ui/data/www/chart.min.js diff --git a/buildroot/web-ui/data/www/chart.min.js b/buildroot/web-ui/data/www/chart.min.js old mode 100644 new mode 100755 index 7c16b0d128..a87f61443e --- a/buildroot/web-ui/data/www/chart.min.js +++ b/buildroot/web-ui/data/www/chart.min.js @@ -1,7 +1,7 @@ /*! - * Chart.js v2.9.3 + * Chart.js v2.9.4 * https://www.chartjs.org - * (c) 2019 Chart.js Contributors + * (c) 2020 Chart.js Contributors * Released under the MIT License */ -!function(t,e){"object"==typeof exports&&"undefined"!=typeof module?module.exports=e(function(){try{return require("moment")}catch(t){}}()):"function"==typeof define&&define.amd?define(["require"],(function(t){return e(function(){try{return t("moment")}catch(t){}}())})):(t=t||self).Chart=e(t.moment)}(this,(function(t){"use strict";t=t&&t.hasOwnProperty("default")?t.default:t;var e={aliceblue:[240,248,255],antiquewhite:[250,235,215],aqua:[0,255,255],aquamarine:[127,255,212],azure:[240,255,255],beige:[245,245,220],bisque:[255,228,196],black:[0,0,0],blanchedalmond:[255,235,205],blue:[0,0,255],blueviolet:[138,43,226],brown:[165,42,42],burlywood:[222,184,135],cadetblue:[95,158,160],chartreuse:[127,255,0],chocolate:[210,105,30],coral:[255,127,80],cornflowerblue:[100,149,237],cornsilk:[255,248,220],crimson:[220,20,60],cyan:[0,255,255],darkblue:[0,0,139],darkcyan:[0,139,139],darkgoldenrod:[184,134,11],darkgray:[169,169,169],darkgreen:[0,100,0],darkgrey:[169,169,169],darkkhaki:[189,183,107],darkmagenta:[139,0,139],darkolivegreen:[85,107,47],darkorange:[255,140,0],darkorchid:[153,50,204],darkred:[139,0,0],darksalmon:[233,150,122],darkseagreen:[143,188,143],darkslateblue:[72,61,139],darkslategray:[47,79,79],darkslategrey:[47,79,79],darkturquoise:[0,206,209],darkviolet:[148,0,211],deeppink:[255,20,147],deepskyblue:[0,191,255],dimgray:[105,105,105],dimgrey:[105,105,105],dodgerblue:[30,144,255],firebrick:[178,34,34],floralwhite:[255,250,240],forestgreen:[34,139,34],fuchsia:[255,0,255],gainsboro:[220,220,220],ghostwhite:[248,248,255],gold:[255,215,0],goldenrod:[218,165,32],gray:[128,128,128],green:[0,128,0],greenyellow:[173,255,47],grey:[128,128,128],honeydew:[240,255,240],hotpink:[255,105,180],indianred:[205,92,92],indigo:[75,0,130],ivory:[255,255,240],khaki:[240,230,140],lavender:[230,230,250],lavenderblush:[255,240,245],lawngreen:[124,252,0],lemonchiffon:[255,250,205],lightblue:[173,216,230],lightcoral:[240,128,128],lightcyan:[224,255,255],lightgoldenrodyellow:[250,250,210],lightgray:[211,211,211],lightgreen:[144,238,144],lightgrey:[211,211,211],lightpink:[255,182,193],lightsalmon:[255,160,122],lightseagreen:[32,178,170],lightskyblue:[135,206,250],lightslategray:[119,136,153],lightslategrey:[119,136,153],lightsteelblue:[176,196,222],lightyellow:[255,255,224],lime:[0,255,0],limegreen:[50,205,50],linen:[250,240,230],magenta:[255,0,255],maroon:[128,0,0],mediumaquamarine:[102,205,170],mediumblue:[0,0,205],mediumorchid:[186,85,211],mediumpurple:[147,112,219],mediumseagreen:[60,179,113],mediumslateblue:[123,104,238],mediumspringgreen:[0,250,154],mediumturquoise:[72,209,204],mediumvioletred:[199,21,133],midnightblue:[25,25,112],mintcream:[245,255,250],mistyrose:[255,228,225],moccasin:[255,228,181],navajowhite:[255,222,173],navy:[0,0,128],oldlace:[253,245,230],olive:[128,128,0],olivedrab:[107,142,35],orange:[255,165,0],orangered:[255,69,0],orchid:[218,112,214],palegoldenrod:[238,232,170],palegreen:[152,251,152],paleturquoise:[175,238,238],palevioletred:[219,112,147],papayawhip:[255,239,213],peachpuff:[255,218,185],peru:[205,133,63],pink:[255,192,203],plum:[221,160,221],powderblue:[176,224,230],purple:[128,0,128],rebeccapurple:[102,51,153],red:[255,0,0],rosybrown:[188,143,143],royalblue:[65,105,225],saddlebrown:[139,69,19],salmon:[250,128,114],sandybrown:[244,164,96],seagreen:[46,139,87],seashell:[255,245,238],sienna:[160,82,45],silver:[192,192,192],skyblue:[135,206,235],slateblue:[106,90,205],slategray:[112,128,144],slategrey:[112,128,144],snow:[255,250,250],springgreen:[0,255,127],steelblue:[70,130,180],tan:[210,180,140],teal:[0,128,128],thistle:[216,191,216],tomato:[255,99,71],turquoise:[64,224,208],violet:[238,130,238],wheat:[245,222,179],white:[255,255,255],whitesmoke:[245,245,245],yellow:[255,255,0],yellowgreen:[154,205,50]},n=function(t,e){return t(e={exports:{}},e.exports),e.exports}((function(t){var n={};for(var i in e)e.hasOwnProperty(i)&&(n[e[i]]=i);var a=t.exports={rgb:{channels:3,labels:"rgb"},hsl:{channels:3,labels:"hsl"},hsv:{channels:3,labels:"hsv"},hwb:{channels:3,labels:"hwb"},cmyk:{channels:4,labels:"cmyk"},xyz:{channels:3,labels:"xyz"},lab:{channels:3,labels:"lab"},lch:{channels:3,labels:"lch"},hex:{channels:1,labels:["hex"]},keyword:{channels:1,labels:["keyword"]},ansi16:{channels:1,labels:["ansi16"]},ansi256:{channels:1,labels:["ansi256"]},hcg:{channels:3,labels:["h","c","g"]},apple:{channels:3,labels:["r16","g16","b16"]},gray:{channels:1,labels:["gray"]}};for(var r in a)if(a.hasOwnProperty(r)){if(!("channels"in a[r]))throw new Error("missing channels property: "+r);if(!("labels"in a[r]))throw new Error("missing channel labels property: "+r);if(a[r].labels.length!==a[r].channels)throw new Error("channel and label counts mismatch: "+r);var o=a[r].channels,s=a[r].labels;delete a[r].channels,delete a[r].labels,Object.defineProperty(a[r],"channels",{value:o}),Object.defineProperty(a[r],"labels",{value:s})}a.rgb.hsl=function(t){var e,n,i=t[0]/255,a=t[1]/255,r=t[2]/255,o=Math.min(i,a,r),s=Math.max(i,a,r),l=s-o;return s===o?e=0:i===s?e=(a-r)/l:a===s?e=2+(r-i)/l:r===s&&(e=4+(i-a)/l),(e=Math.min(60*e,360))<0&&(e+=360),n=(o+s)/2,[e,100*(s===o?0:n<=.5?l/(s+o):l/(2-s-o)),100*n]},a.rgb.hsv=function(t){var e,n,i,a,r,o=t[0]/255,s=t[1]/255,l=t[2]/255,u=Math.max(o,s,l),d=u-Math.min(o,s,l),h=function(t){return(u-t)/6/d+.5};return 0===d?a=r=0:(r=d/u,e=h(o),n=h(s),i=h(l),o===u?a=i-n:s===u?a=1/3+e-i:l===u&&(a=2/3+n-e),a<0?a+=1:a>1&&(a-=1)),[360*a,100*r,100*u]},a.rgb.hwb=function(t){var e=t[0],n=t[1],i=t[2];return[a.rgb.hsl(t)[0],100*(1/255*Math.min(e,Math.min(n,i))),100*(i=1-1/255*Math.max(e,Math.max(n,i)))]},a.rgb.cmyk=function(t){var e,n=t[0]/255,i=t[1]/255,a=t[2]/255;return[100*((1-n-(e=Math.min(1-n,1-i,1-a)))/(1-e)||0),100*((1-i-e)/(1-e)||0),100*((1-a-e)/(1-e)||0),100*e]},a.rgb.keyword=function(t){var i=n[t];if(i)return i;var a,r,o,s=1/0;for(var l in e)if(e.hasOwnProperty(l)){var u=e[l],d=(r=t,o=u,Math.pow(r[0]-o[0],2)+Math.pow(r[1]-o[1],2)+Math.pow(r[2]-o[2],2));d.04045?Math.pow((e+.055)/1.055,2.4):e/12.92)+.3576*(n=n>.04045?Math.pow((n+.055)/1.055,2.4):n/12.92)+.1805*(i=i>.04045?Math.pow((i+.055)/1.055,2.4):i/12.92)),100*(.2126*e+.7152*n+.0722*i),100*(.0193*e+.1192*n+.9505*i)]},a.rgb.lab=function(t){var e=a.rgb.xyz(t),n=e[0],i=e[1],r=e[2];return i/=100,r/=108.883,n=(n/=95.047)>.008856?Math.pow(n,1/3):7.787*n+16/116,[116*(i=i>.008856?Math.pow(i,1/3):7.787*i+16/116)-16,500*(n-i),200*(i-(r=r>.008856?Math.pow(r,1/3):7.787*r+16/116))]},a.hsl.rgb=function(t){var e,n,i,a,r,o=t[0]/360,s=t[1]/100,l=t[2]/100;if(0===s)return[r=255*l,r,r];e=2*l-(n=l<.5?l*(1+s):l+s-l*s),a=[0,0,0];for(var u=0;u<3;u++)(i=o+1/3*-(u-1))<0&&i++,i>1&&i--,r=6*i<1?e+6*(n-e)*i:2*i<1?n:3*i<2?e+(n-e)*(2/3-i)*6:e,a[u]=255*r;return a},a.hsl.hsv=function(t){var e=t[0],n=t[1]/100,i=t[2]/100,a=n,r=Math.max(i,.01);return n*=(i*=2)<=1?i:2-i,a*=r<=1?r:2-r,[e,100*(0===i?2*a/(r+a):2*n/(i+n)),100*((i+n)/2)]},a.hsv.rgb=function(t){var e=t[0]/60,n=t[1]/100,i=t[2]/100,a=Math.floor(e)%6,r=e-Math.floor(e),o=255*i*(1-n),s=255*i*(1-n*r),l=255*i*(1-n*(1-r));switch(i*=255,a){case 0:return[i,l,o];case 1:return[s,i,o];case 2:return[o,i,l];case 3:return[o,s,i];case 4:return[l,o,i];case 5:return[i,o,s]}},a.hsv.hsl=function(t){var e,n,i,a=t[0],r=t[1]/100,o=t[2]/100,s=Math.max(o,.01);return i=(2-r)*o,n=r*s,[a,100*(n=(n/=(e=(2-r)*s)<=1?e:2-e)||0),100*(i/=2)]},a.hwb.rgb=function(t){var e,n,i,a,r,o,s,l=t[0]/360,u=t[1]/100,d=t[2]/100,h=u+d;switch(h>1&&(u/=h,d/=h),i=6*l-(e=Math.floor(6*l)),0!=(1&e)&&(i=1-i),a=u+i*((n=1-d)-u),e){default:case 6:case 0:r=n,o=a,s=u;break;case 1:r=a,o=n,s=u;break;case 2:r=u,o=n,s=a;break;case 3:r=u,o=a,s=n;break;case 4:r=a,o=u,s=n;break;case 5:r=n,o=u,s=a}return[255*r,255*o,255*s]},a.cmyk.rgb=function(t){var e=t[0]/100,n=t[1]/100,i=t[2]/100,a=t[3]/100;return[255*(1-Math.min(1,e*(1-a)+a)),255*(1-Math.min(1,n*(1-a)+a)),255*(1-Math.min(1,i*(1-a)+a))]},a.xyz.rgb=function(t){var e,n,i,a=t[0]/100,r=t[1]/100,o=t[2]/100;return n=-.9689*a+1.8758*r+.0415*o,i=.0557*a+-.204*r+1.057*o,e=(e=3.2406*a+-1.5372*r+-.4986*o)>.0031308?1.055*Math.pow(e,1/2.4)-.055:12.92*e,n=n>.0031308?1.055*Math.pow(n,1/2.4)-.055:12.92*n,i=i>.0031308?1.055*Math.pow(i,1/2.4)-.055:12.92*i,[255*(e=Math.min(Math.max(0,e),1)),255*(n=Math.min(Math.max(0,n),1)),255*(i=Math.min(Math.max(0,i),1))]},a.xyz.lab=function(t){var e=t[0],n=t[1],i=t[2];return n/=100,i/=108.883,e=(e/=95.047)>.008856?Math.pow(e,1/3):7.787*e+16/116,[116*(n=n>.008856?Math.pow(n,1/3):7.787*n+16/116)-16,500*(e-n),200*(n-(i=i>.008856?Math.pow(i,1/3):7.787*i+16/116))]},a.lab.xyz=function(t){var e,n,i,a=t[0];e=t[1]/500+(n=(a+16)/116),i=n-t[2]/200;var r=Math.pow(n,3),o=Math.pow(e,3),s=Math.pow(i,3);return n=r>.008856?r:(n-16/116)/7.787,e=o>.008856?o:(e-16/116)/7.787,i=s>.008856?s:(i-16/116)/7.787,[e*=95.047,n*=100,i*=108.883]},a.lab.lch=function(t){var e,n=t[0],i=t[1],a=t[2];return(e=360*Math.atan2(a,i)/2/Math.PI)<0&&(e+=360),[n,Math.sqrt(i*i+a*a),e]},a.lch.lab=function(t){var e,n=t[0],i=t[1];return e=t[2]/360*2*Math.PI,[n,i*Math.cos(e),i*Math.sin(e)]},a.rgb.ansi16=function(t){var e=t[0],n=t[1],i=t[2],r=1 in arguments?arguments[1]:a.rgb.hsv(t)[2];if(0===(r=Math.round(r/50)))return 30;var o=30+(Math.round(i/255)<<2|Math.round(n/255)<<1|Math.round(e/255));return 2===r&&(o+=60),o},a.hsv.ansi16=function(t){return a.rgb.ansi16(a.hsv.rgb(t),t[2])},a.rgb.ansi256=function(t){var e=t[0],n=t[1],i=t[2];return e===n&&n===i?e<8?16:e>248?231:Math.round((e-8)/247*24)+232:16+36*Math.round(e/255*5)+6*Math.round(n/255*5)+Math.round(i/255*5)},a.ansi16.rgb=function(t){var e=t%10;if(0===e||7===e)return t>50&&(e+=3.5),[e=e/10.5*255,e,e];var n=.5*(1+~~(t>50));return[(1&e)*n*255,(e>>1&1)*n*255,(e>>2&1)*n*255]},a.ansi256.rgb=function(t){if(t>=232){var e=10*(t-232)+8;return[e,e,e]}var n;return t-=16,[Math.floor(t/36)/5*255,Math.floor((n=t%36)/6)/5*255,n%6/5*255]},a.rgb.hex=function(t){var e=(((255&Math.round(t[0]))<<16)+((255&Math.round(t[1]))<<8)+(255&Math.round(t[2]))).toString(16).toUpperCase();return"000000".substring(e.length)+e},a.hex.rgb=function(t){var e=t.toString(16).match(/[a-f0-9]{6}|[a-f0-9]{3}/i);if(!e)return[0,0,0];var n=e[0];3===e[0].length&&(n=n.split("").map((function(t){return t+t})).join(""));var i=parseInt(n,16);return[i>>16&255,i>>8&255,255&i]},a.rgb.hcg=function(t){var e,n=t[0]/255,i=t[1]/255,a=t[2]/255,r=Math.max(Math.max(n,i),a),o=Math.min(Math.min(n,i),a),s=r-o;return e=s<=0?0:r===n?(i-a)/s%6:r===i?2+(a-n)/s:4+(n-i)/s+4,e/=6,[360*(e%=1),100*s,100*(s<1?o/(1-s):0)]},a.hsl.hcg=function(t){var e=t[1]/100,n=t[2]/100,i=1,a=0;return(i=n<.5?2*e*n:2*e*(1-n))<1&&(a=(n-.5*i)/(1-i)),[t[0],100*i,100*a]},a.hsv.hcg=function(t){var e=t[1]/100,n=t[2]/100,i=e*n,a=0;return i<1&&(a=(n-i)/(1-i)),[t[0],100*i,100*a]},a.hcg.rgb=function(t){var e=t[0]/360,n=t[1]/100,i=t[2]/100;if(0===n)return[255*i,255*i,255*i];var a,r=[0,0,0],o=e%1*6,s=o%1,l=1-s;switch(Math.floor(o)){case 0:r[0]=1,r[1]=s,r[2]=0;break;case 1:r[0]=l,r[1]=1,r[2]=0;break;case 2:r[0]=0,r[1]=1,r[2]=s;break;case 3:r[0]=0,r[1]=l,r[2]=1;break;case 4:r[0]=s,r[1]=0,r[2]=1;break;default:r[0]=1,r[1]=0,r[2]=l}return a=(1-n)*i,[255*(n*r[0]+a),255*(n*r[1]+a),255*(n*r[2]+a)]},a.hcg.hsv=function(t){var e=t[1]/100,n=e+t[2]/100*(1-e),i=0;return n>0&&(i=e/n),[t[0],100*i,100*n]},a.hcg.hsl=function(t){var e=t[1]/100,n=t[2]/100*(1-e)+.5*e,i=0;return n>0&&n<.5?i=e/(2*n):n>=.5&&n<1&&(i=e/(2*(1-n))),[t[0],100*i,100*n]},a.hcg.hwb=function(t){var e=t[1]/100,n=e+t[2]/100*(1-e);return[t[0],100*(n-e),100*(1-n)]},a.hwb.hcg=function(t){var e=t[1]/100,n=1-t[2]/100,i=n-e,a=0;return i<1&&(a=(n-i)/(1-i)),[t[0],100*i,100*a]},a.apple.rgb=function(t){return[t[0]/65535*255,t[1]/65535*255,t[2]/65535*255]},a.rgb.apple=function(t){return[t[0]/255*65535,t[1]/255*65535,t[2]/255*65535]},a.gray.rgb=function(t){return[t[0]/100*255,t[0]/100*255,t[0]/100*255]},a.gray.hsl=a.gray.hsv=function(t){return[0,0,t[0]]},a.gray.hwb=function(t){return[0,100,t[0]]},a.gray.cmyk=function(t){return[0,0,0,t[0]]},a.gray.lab=function(t){return[t[0],0,0]},a.gray.hex=function(t){var e=255&Math.round(t[0]/100*255),n=((e<<16)+(e<<8)+e).toString(16).toUpperCase();return"000000".substring(n.length)+n},a.rgb.gray=function(t){return[(t[0]+t[1]+t[2])/3/255*100]}}));n.rgb,n.hsl,n.hsv,n.hwb,n.cmyk,n.xyz,n.lab,n.lch,n.hex,n.keyword,n.ansi16,n.ansi256,n.hcg,n.apple,n.gray;function i(t){var e=function(){for(var t={},e=Object.keys(n),i=e.length,a=0;a1&&(e=Array.prototype.slice.call(arguments));var n=t(e);if("object"==typeof n)for(var i=n.length,a=0;a1&&(e=Array.prototype.slice.call(arguments)),t(e))};return"conversion"in t&&(e.conversion=t.conversion),e}(i)}))}));var s=o,l={aliceblue:[240,248,255],antiquewhite:[250,235,215],aqua:[0,255,255],aquamarine:[127,255,212],azure:[240,255,255],beige:[245,245,220],bisque:[255,228,196],black:[0,0,0],blanchedalmond:[255,235,205],blue:[0,0,255],blueviolet:[138,43,226],brown:[165,42,42],burlywood:[222,184,135],cadetblue:[95,158,160],chartreuse:[127,255,0],chocolate:[210,105,30],coral:[255,127,80],cornflowerblue:[100,149,237],cornsilk:[255,248,220],crimson:[220,20,60],cyan:[0,255,255],darkblue:[0,0,139],darkcyan:[0,139,139],darkgoldenrod:[184,134,11],darkgray:[169,169,169],darkgreen:[0,100,0],darkgrey:[169,169,169],darkkhaki:[189,183,107],darkmagenta:[139,0,139],darkolivegreen:[85,107,47],darkorange:[255,140,0],darkorchid:[153,50,204],darkred:[139,0,0],darksalmon:[233,150,122],darkseagreen:[143,188,143],darkslateblue:[72,61,139],darkslategray:[47,79,79],darkslategrey:[47,79,79],darkturquoise:[0,206,209],darkviolet:[148,0,211],deeppink:[255,20,147],deepskyblue:[0,191,255],dimgray:[105,105,105],dimgrey:[105,105,105],dodgerblue:[30,144,255],firebrick:[178,34,34],floralwhite:[255,250,240],forestgreen:[34,139,34],fuchsia:[255,0,255],gainsboro:[220,220,220],ghostwhite:[248,248,255],gold:[255,215,0],goldenrod:[218,165,32],gray:[128,128,128],green:[0,128,0],greenyellow:[173,255,47],grey:[128,128,128],honeydew:[240,255,240],hotpink:[255,105,180],indianred:[205,92,92],indigo:[75,0,130],ivory:[255,255,240],khaki:[240,230,140],lavender:[230,230,250],lavenderblush:[255,240,245],lawngreen:[124,252,0],lemonchiffon:[255,250,205],lightblue:[173,216,230],lightcoral:[240,128,128],lightcyan:[224,255,255],lightgoldenrodyellow:[250,250,210],lightgray:[211,211,211],lightgreen:[144,238,144],lightgrey:[211,211,211],lightpink:[255,182,193],lightsalmon:[255,160,122],lightseagreen:[32,178,170],lightskyblue:[135,206,250],lightslategray:[119,136,153],lightslategrey:[119,136,153],lightsteelblue:[176,196,222],lightyellow:[255,255,224],lime:[0,255,0],limegreen:[50,205,50],linen:[250,240,230],magenta:[255,0,255],maroon:[128,0,0],mediumaquamarine:[102,205,170],mediumblue:[0,0,205],mediumorchid:[186,85,211],mediumpurple:[147,112,219],mediumseagreen:[60,179,113],mediumslateblue:[123,104,238],mediumspringgreen:[0,250,154],mediumturquoise:[72,209,204],mediumvioletred:[199,21,133],midnightblue:[25,25,112],mintcream:[245,255,250],mistyrose:[255,228,225],moccasin:[255,228,181],navajowhite:[255,222,173],navy:[0,0,128],oldlace:[253,245,230],olive:[128,128,0],olivedrab:[107,142,35],orange:[255,165,0],orangered:[255,69,0],orchid:[218,112,214],palegoldenrod:[238,232,170],palegreen:[152,251,152],paleturquoise:[175,238,238],palevioletred:[219,112,147],papayawhip:[255,239,213],peachpuff:[255,218,185],peru:[205,133,63],pink:[255,192,203],plum:[221,160,221],powderblue:[176,224,230],purple:[128,0,128],rebeccapurple:[102,51,153],red:[255,0,0],rosybrown:[188,143,143],royalblue:[65,105,225],saddlebrown:[139,69,19],salmon:[250,128,114],sandybrown:[244,164,96],seagreen:[46,139,87],seashell:[255,245,238],sienna:[160,82,45],silver:[192,192,192],skyblue:[135,206,235],slateblue:[106,90,205],slategray:[112,128,144],slategrey:[112,128,144],snow:[255,250,250],springgreen:[0,255,127],steelblue:[70,130,180],tan:[210,180,140],teal:[0,128,128],thistle:[216,191,216],tomato:[255,99,71],turquoise:[64,224,208],violet:[238,130,238],wheat:[245,222,179],white:[255,255,255],whitesmoke:[245,245,245],yellow:[255,255,0],yellowgreen:[154,205,50]},u={getRgba:d,getHsla:h,getRgb:function(t){var e=d(t);return e&&e.slice(0,3)},getHsl:function(t){var e=h(t);return e&&e.slice(0,3)},getHwb:c,getAlpha:function(t){var e=d(t);if(e)return e[3];if(e=h(t))return e[3];if(e=c(t))return e[3]},hexString:function(t,e){e=void 0!==e&&3===t.length?e:t[3];return"#"+v(t[0])+v(t[1])+v(t[2])+(e>=0&&e<1?v(Math.round(255*e)):"")},rgbString:function(t,e){if(e<1||t[3]&&t[3]<1)return f(t,e);return"rgb("+t[0]+", "+t[1]+", "+t[2]+")"},rgbaString:f,percentString:function(t,e){if(e<1||t[3]&&t[3]<1)return g(t,e);var n=Math.round(t[0]/255*100),i=Math.round(t[1]/255*100),a=Math.round(t[2]/255*100);return"rgb("+n+"%, "+i+"%, "+a+"%)"},percentaString:g,hslString:function(t,e){if(e<1||t[3]&&t[3]<1)return p(t,e);return"hsl("+t[0]+", "+t[1]+"%, "+t[2]+"%)"},hslaString:p,hwbString:function(t,e){void 0===e&&(e=void 0!==t[3]?t[3]:1);return"hwb("+t[0]+", "+t[1]+"%, "+t[2]+"%"+(void 0!==e&&1!==e?", "+e:"")+")"},keyword:function(t){return b[t.slice(0,3)]}};function d(t){if(t){var e=[0,0,0],n=1,i=t.match(/^#([a-fA-F0-9]{3,4})$/i),a="";if(i){a=(i=i[1])[3];for(var r=0;rn?(e+.05)/(n+.05):(n+.05)/(e+.05)},level:function(t){var e=this.contrast(t);return e>=7.1?"AAA":e>=4.5?"AA":""},dark:function(){var t=this.values.rgb;return(299*t[0]+587*t[1]+114*t[2])/1e3<128},light:function(){return!this.dark()},negate:function(){for(var t=[],e=0;e<3;e++)t[e]=255-this.values.rgb[e];return this.setValues("rgb",t),this},lighten:function(t){var e=this.values.hsl;return e[2]+=e[2]*t,this.setValues("hsl",e),this},darken:function(t){var e=this.values.hsl;return e[2]-=e[2]*t,this.setValues("hsl",e),this},saturate:function(t){var e=this.values.hsl;return e[1]+=e[1]*t,this.setValues("hsl",e),this},desaturate:function(t){var e=this.values.hsl;return e[1]-=e[1]*t,this.setValues("hsl",e),this},whiten:function(t){var e=this.values.hwb;return e[1]+=e[1]*t,this.setValues("hwb",e),this},blacken:function(t){var e=this.values.hwb;return e[2]+=e[2]*t,this.setValues("hwb",e),this},greyscale:function(){var t=this.values.rgb,e=.3*t[0]+.59*t[1]+.11*t[2];return this.setValues("rgb",[e,e,e]),this},clearer:function(t){var e=this.values.alpha;return this.setValues("alpha",e-e*t),this},opaquer:function(t){var e=this.values.alpha;return this.setValues("alpha",e+e*t),this},rotate:function(t){var e=this.values.hsl,n=(e[0]+t)%360;return e[0]=n<0?360+n:n,this.setValues("hsl",e),this},mix:function(t,e){var n=t,i=void 0===e?.5:e,a=2*i-1,r=this.alpha()-n.alpha(),o=((a*r==-1?a:(a+r)/(1+a*r))+1)/2,s=1-o;return this.rgb(o*this.red()+s*n.red(),o*this.green()+s*n.green(),o*this.blue()+s*n.blue()).alpha(this.alpha()*i+n.alpha()*(1-i))},toJSON:function(){return this.rgb()},clone:function(){var t,e,n=new y,i=this.values,a=n.values;for(var r in i)i.hasOwnProperty(r)&&(t=i[r],"[object Array]"===(e={}.toString.call(t))?a[r]=t.slice(0):"[object Number]"===e?a[r]=t:console.error("unexpected color value:",t));return n}},y.prototype.spaces={rgb:["red","green","blue"],hsl:["hue","saturation","lightness"],hsv:["hue","saturation","value"],hwb:["hue","whiteness","blackness"],cmyk:["cyan","magenta","yellow","black"]},y.prototype.maxes={rgb:[255,255,255],hsl:[360,100,100],hsv:[360,100,100],hwb:[360,100,100],cmyk:[100,100,100,100]},y.prototype.getValues=function(t){for(var e=this.values,n={},i=0;i=0;a--)e.call(n,t[a],a);else for(a=0;a=1?t:-(Math.sqrt(1-t*t)-1)},easeOutCirc:function(t){return Math.sqrt(1-(t-=1)*t)},easeInOutCirc:function(t){return(t/=.5)<1?-.5*(Math.sqrt(1-t*t)-1):.5*(Math.sqrt(1-(t-=2)*t)+1)},easeInElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:1===t?1:(n||(n=.3),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),-i*Math.pow(2,10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n))},easeOutElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:1===t?1:(n||(n=.3),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),i*Math.pow(2,-10*t)*Math.sin((t-e)*(2*Math.PI)/n)+1)},easeInOutElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:2==(t/=.5)?1:(n||(n=.45),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),t<1?i*Math.pow(2,10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n)*-.5:i*Math.pow(2,-10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n)*.5+1)},easeInBack:function(t){var e=1.70158;return t*t*((e+1)*t-e)},easeOutBack:function(t){var e=1.70158;return(t-=1)*t*((e+1)*t+e)+1},easeInOutBack:function(t){var e=1.70158;return(t/=.5)<1?t*t*((1+(e*=1.525))*t-e)*.5:.5*((t-=2)*t*((1+(e*=1.525))*t+e)+2)},easeInBounce:function(t){return 1-S.easeOutBounce(1-t)},easeOutBounce:function(t){return t<1/2.75?7.5625*t*t:t<2/2.75?7.5625*(t-=1.5/2.75)*t+.75:t<2.5/2.75?7.5625*(t-=2.25/2.75)*t+.9375:7.5625*(t-=2.625/2.75)*t+.984375},easeInOutBounce:function(t){return t<.5?.5*S.easeInBounce(2*t):.5*S.easeOutBounce(2*t-1)+.5}},C={effects:S};M.easingEffects=S;var P=Math.PI,A=P/180,D=2*P,T=P/2,I=P/4,F=2*P/3,L={clear:function(t){t.ctx.clearRect(0,0,t.width,t.height)},roundedRect:function(t,e,n,i,a,r){if(r){var o=Math.min(r,a/2,i/2),s=e+o,l=n+o,u=e+i-o,d=n+a-o;t.moveTo(e,l),se.left-1e-6&&t.xe.top-1e-6&&t.y0&&this.requestAnimationFrame()},advance:function(){for(var t,e,n,i,a=this.animations,r=0;r=n?(V.callback(t.onAnimationComplete,[t],e),e.animating=!1,a.splice(r,1)):++r}},J=V.options.resolve,Q=["push","pop","shift","splice","unshift"];function tt(t,e){var n=t._chartjs;if(n){var i=n.listeners,a=i.indexOf(e);-1!==a&&i.splice(a,1),i.length>0||(Q.forEach((function(e){delete t[e]})),delete t._chartjs)}}var et=function(t,e){this.initialize(t,e)};V.extend(et.prototype,{datasetElementType:null,dataElementType:null,_datasetElementOptions:["backgroundColor","borderCapStyle","borderColor","borderDash","borderDashOffset","borderJoinStyle","borderWidth"],_dataElementOptions:["backgroundColor","borderColor","borderWidth","pointStyle"],initialize:function(t,e){var n=this;n.chart=t,n.index=e,n.linkScales(),n.addElements(),n._type=n.getMeta().type},updateIndex:function(t){this.index=t},linkScales:function(){var t=this.getMeta(),e=this.chart,n=e.scales,i=this.getDataset(),a=e.options.scales;null!==t.xAxisID&&t.xAxisID in n&&!i.xAxisID||(t.xAxisID=i.xAxisID||a.xAxes[0].id),null!==t.yAxisID&&t.yAxisID in n&&!i.yAxisID||(t.yAxisID=i.yAxisID||a.yAxes[0].id)},getDataset:function(){return this.chart.data.datasets[this.index]},getMeta:function(){return this.chart.getDatasetMeta(this.index)},getScaleForId:function(t){return this.chart.scales[t]},_getValueScaleId:function(){return this.getMeta().yAxisID},_getIndexScaleId:function(){return this.getMeta().xAxisID},_getValueScale:function(){return this.getScaleForId(this._getValueScaleId())},_getIndexScale:function(){return this.getScaleForId(this._getIndexScaleId())},reset:function(){this._update(!0)},destroy:function(){this._data&&tt(this._data,this)},createMetaDataset:function(){var t=this.datasetElementType;return t&&new t({_chart:this.chart,_datasetIndex:this.index})},createMetaData:function(t){var e=this.dataElementType;return e&&new e({_chart:this.chart,_datasetIndex:this.index,_index:t})},addElements:function(){var t,e,n=this.getMeta(),i=this.getDataset().data||[],a=n.data;for(t=0,e=i.length;tn&&this.insertElements(n,i-n)},insertElements:function(t,e){for(var n=0;na?(r=a/e.innerRadius,t.arc(o,s,e.innerRadius-a,i+r,n-r,!0)):t.arc(o,s,a,i+Math.PI/2,n-Math.PI/2),t.closePath(),t.clip()}function rt(t,e,n){var i="inner"===e.borderAlign;i?(t.lineWidth=2*e.borderWidth,t.lineJoin="round"):(t.lineWidth=e.borderWidth,t.lineJoin="bevel"),n.fullCircles&&function(t,e,n,i){var a,r=n.endAngle;for(i&&(n.endAngle=n.startAngle+it,at(t,n),n.endAngle=r,n.endAngle===n.startAngle&&n.fullCircles&&(n.endAngle+=it,n.fullCircles--)),t.beginPath(),t.arc(n.x,n.y,n.innerRadius,n.startAngle+it,n.startAngle,!0),a=0;as;)a-=it;for(;a=o&&a<=s,u=r>=n.innerRadius&&r<=n.outerRadius;return l&&u}return!1},getCenterPoint:function(){var t=this._view,e=(t.startAngle+t.endAngle)/2,n=(t.innerRadius+t.outerRadius)/2;return{x:t.x+Math.cos(e)*n,y:t.y+Math.sin(e)*n}},getArea:function(){var t=this._view;return Math.PI*((t.endAngle-t.startAngle)/(2*Math.PI))*(Math.pow(t.outerRadius,2)-Math.pow(t.innerRadius,2))},tooltipPosition:function(){var t=this._view,e=t.startAngle+(t.endAngle-t.startAngle)/2,n=(t.outerRadius-t.innerRadius)/2+t.innerRadius;return{x:t.x+Math.cos(e)*n,y:t.y+Math.sin(e)*n}},draw:function(){var t,e=this._chart.ctx,n=this._view,i="inner"===n.borderAlign?.33:0,a={x:n.x,y:n.y,innerRadius:n.innerRadius,outerRadius:Math.max(n.outerRadius-i,0),pixelMargin:i,startAngle:n.startAngle,endAngle:n.endAngle,fullCircles:Math.floor(n.circumference/it)};if(e.save(),e.fillStyle=n.backgroundColor,e.strokeStyle=n.borderColor,a.fullCircles){for(a.endAngle=a.startAngle+it,e.beginPath(),e.arc(a.x,a.y,a.outerRadius,a.startAngle,a.endAngle),e.arc(a.x,a.y,a.innerRadius,a.endAngle,a.startAngle,!0),e.closePath(),t=0;tt.x&&(e=vt(e,"left","right")):t.basen?n:i,r:l.right||a<0?0:a>e?e:a,b:l.bottom||r<0?0:r>n?n:r,l:l.left||o<0?0:o>e?e:o}}function xt(t,e,n){var i=null===e,a=null===n,r=!(!t||i&&a)&&mt(t);return r&&(i||e>=r.left&&e<=r.right)&&(a||n>=r.top&&n<=r.bottom)}z._set("global",{elements:{rectangle:{backgroundColor:gt,borderColor:gt,borderSkipped:"bottom",borderWidth:0}}});var yt=X.extend({_type:"rectangle",draw:function(){var t=this._chart.ctx,e=this._view,n=function(t){var e=mt(t),n=e.right-e.left,i=e.bottom-e.top,a=bt(t,n/2,i/2);return{outer:{x:e.left,y:e.top,w:n,h:i},inner:{x:e.left+a.l,y:e.top+a.t,w:n-a.l-a.r,h:i-a.t-a.b}}}(e),i=n.outer,a=n.inner;t.fillStyle=e.backgroundColor,t.fillRect(i.x,i.y,i.w,i.h),i.w===a.w&&i.h===a.h||(t.save(),t.beginPath(),t.rect(i.x,i.y,i.w,i.h),t.clip(),t.fillStyle=e.borderColor,t.rect(a.x,a.y,a.w,a.h),t.fill("evenodd"),t.restore())},height:function(){var t=this._view;return t.base-t.y},inRange:function(t,e){return xt(this._view,t,e)},inLabelRange:function(t,e){var n=this._view;return pt(n)?xt(n,t,null):xt(n,null,e)},inXRange:function(t){return xt(this._view,t,null)},inYRange:function(t){return xt(this._view,null,t)},getCenterPoint:function(){var t,e,n=this._view;return pt(n)?(t=n.x,e=(n.y+n.base)/2):(t=(n.x+n.base)/2,e=n.y),{x:t,y:e}},getArea:function(){var t=this._view;return pt(t)?t.width*Math.abs(t.y-t.base):t.height*Math.abs(t.x-t.base)},tooltipPosition:function(){var t=this._view;return{x:t.x,y:t.y}}}),_t={},kt=ot,wt=ut,Mt=ft,St=yt;_t.Arc=kt,_t.Line=wt,_t.Point=Mt,_t.Rectangle=St;var Ct=V._deprecated,Pt=V.valueOrDefault;function At(t,e,n){var i,a,r=n.barThickness,o=e.stackCount,s=e.pixels[t],l=V.isNullOrUndef(r)?function(t,e){var n,i,a,r,o=t._length;for(a=1,r=e.length;a0?Math.min(o,Math.abs(i-n)):o,n=i;return o}(e.scale,e.pixels):-1;return V.isNullOrUndef(r)?(i=l*n.categoryPercentage,a=n.barPercentage):(i=r*o,a=1),{chunk:i/o,ratio:a,start:s-i/2}}z._set("bar",{hover:{mode:"label"},scales:{xAxes:[{type:"category",offset:!0,gridLines:{offsetGridLines:!0}}],yAxes:[{type:"linear"}]}}),z._set("global",{datasets:{bar:{categoryPercentage:.8,barPercentage:.9}}});var Dt=nt.extend({dataElementType:_t.Rectangle,_dataElementOptions:["backgroundColor","borderColor","borderSkipped","borderWidth","barPercentage","barThickness","categoryPercentage","maxBarThickness","minBarLength"],initialize:function(){var t,e,n=this;nt.prototype.initialize.apply(n,arguments),(t=n.getMeta()).stack=n.getDataset().stack,t.bar=!0,e=n._getIndexScale().options,Ct("bar chart",e.barPercentage,"scales.[x/y]Axes.barPercentage","dataset.barPercentage"),Ct("bar chart",e.barThickness,"scales.[x/y]Axes.barThickness","dataset.barThickness"),Ct("bar chart",e.categoryPercentage,"scales.[x/y]Axes.categoryPercentage","dataset.categoryPercentage"),Ct("bar chart",n._getValueScale().options.minBarLength,"scales.[x/y]Axes.minBarLength","dataset.minBarLength"),Ct("bar chart",e.maxBarThickness,"scales.[x/y]Axes.maxBarThickness","dataset.maxBarThickness")},update:function(t){var e,n,i=this.getMeta().data;for(this._ruler=this.getRuler(),e=0,n=i.length;e=0&&p.min>=0?p.min:p.max,y=void 0===p.start?p.end:p.max>=0&&p.min>=0?p.max-p.min:p.min-p.max,_=g.length;if(v||void 0===v&&void 0!==b)for(i=0;i<_&&(a=g[i]).index!==t;++i)a.stack===b&&(r=void 0===(u=h._parseValue(f[a.index].data[e])).start?u.end:u.min>=0&&u.max>=0?u.max:u.min,(p.min<0&&r<0||p.max>=0&&r>0)&&(x+=r));return o=h.getPixelForValue(x),l=(s=h.getPixelForValue(x+y))-o,void 0!==m&&Math.abs(l)=0&&!c||y<0&&c?o-m:o+m),{size:l,base:o,head:s,center:s+l/2}},calculateBarIndexPixels:function(t,e,n,i){var a="flex"===i.barThickness?function(t,e,n){var i,a=e.pixels,r=a[t],o=t>0?a[t-1]:null,s=t=Ot?-Rt:b<-Ot?Rt:0)+m,y=Math.cos(b),_=Math.sin(b),k=Math.cos(x),w=Math.sin(x),M=b<=0&&x>=0||x>=Rt,S=b<=zt&&x>=zt||x>=Rt+zt,C=b<=-zt&&x>=-zt||x>=Ot+zt,P=b===-Ot||x>=Ot?-1:Math.min(y,y*p,k,k*p),A=C?-1:Math.min(_,_*p,w,w*p),D=M?1:Math.max(y,y*p,k,k*p),T=S?1:Math.max(_,_*p,w,w*p);u=(D-P)/2,d=(T-A)/2,h=-(D+P)/2,c=-(T+A)/2}for(i=0,a=g.length;i0&&!isNaN(t)?Rt*(Math.abs(t)/e):0},getMaxBorderWidth:function(t){var e,n,i,a,r,o,s,l,u=0,d=this.chart;if(!t)for(e=0,n=d.data.datasets.length;e(u=s>u?s:u)?l:u);return u},setHoverStyle:function(t){var e=t._model,n=t._options,i=V.getHoverColor;t.$previousStyle={backgroundColor:e.backgroundColor,borderColor:e.borderColor,borderWidth:e.borderWidth},e.backgroundColor=Lt(n.hoverBackgroundColor,i(n.backgroundColor)),e.borderColor=Lt(n.hoverBorderColor,i(n.borderColor)),e.borderWidth=Lt(n.hoverBorderWidth,n.borderWidth)},_getRingWeightOffset:function(t){for(var e=0,n=0;n0&&Vt(l[t-1]._model,s)&&(n.controlPointPreviousX=u(n.controlPointPreviousX,s.left,s.right),n.controlPointPreviousY=u(n.controlPointPreviousY,s.top,s.bottom)),t0&&(r=t.getDatasetMeta(r[0]._datasetIndex).data),r},"x-axis":function(t,e){return ie(t,e,{intersect:!1})},point:function(t,e){return te(t,Jt(e,t))},nearest:function(t,e,n){var i=Jt(e,t);n.axis=n.axis||"xy";var a=ne(n.axis);return ee(t,i,n.intersect,a)},x:function(t,e,n){var i=Jt(e,t),a=[],r=!1;return Qt(t,(function(t){t.inXRange(i.x)&&a.push(t),t.inRange(i.x,i.y)&&(r=!0)})),n.intersect&&!r&&(a=[]),a},y:function(t,e,n){var i=Jt(e,t),a=[],r=!1;return Qt(t,(function(t){t.inYRange(i.y)&&a.push(t),t.inRange(i.x,i.y)&&(r=!0)})),n.intersect&&!r&&(a=[]),a}}},re=V.extend;function oe(t,e){return V.where(t,(function(t){return t.pos===e}))}function se(t,e){return t.sort((function(t,n){var i=e?n:t,a=e?t:n;return i.weight===a.weight?i.index-a.index:i.weight-a.weight}))}function le(t,e,n,i){return Math.max(t[n],e[n])+Math.max(t[i],e[i])}function ue(t,e,n){var i,a,r=n.box,o=t.maxPadding;if(n.size&&(t[n.pos]-=n.size),n.size=n.horizontal?r.height:r.width,t[n.pos]+=n.size,r.getPadding){var s=r.getPadding();o.top=Math.max(o.top,s.top),o.left=Math.max(o.left,s.left),o.bottom=Math.max(o.bottom,s.bottom),o.right=Math.max(o.right,s.right)}if(i=e.outerWidth-le(o,t,"left","right"),a=e.outerHeight-le(o,t,"top","bottom"),i!==t.w||a!==t.h)return t.w=i,t.h=a,n.horizontal?i!==t.w:a!==t.h}function de(t,e){var n=e.maxPadding;function i(t){var i={left:0,top:0,right:0,bottom:0};return t.forEach((function(t){i[t]=Math.max(e[t],n[t])})),i}return i(t?["left","right"]:["top","bottom"])}function he(t,e,n){var i,a,r,o,s,l,u=[];for(i=0,a=t.length;idiv{position:absolute;width:1000000px;height:1000000px;left:0;top:0}.chartjs-size-monitor-shrink>div{position:absolute;width:200%;height:200%;left:0;top:0}"}))&&fe.default||fe,me="$chartjs",ve="chartjs-size-monitor",be="chartjs-render-monitor",xe="chartjs-render-animation",ye=["animationstart","webkitAnimationStart"],_e={touchstart:"mousedown",touchmove:"mousemove",touchend:"mouseup",pointerenter:"mouseenter",pointerdown:"mousedown",pointermove:"mousemove",pointerup:"mouseup",pointerleave:"mouseout",pointerout:"mouseout"};function ke(t,e){var n=V.getStyle(t,e),i=n&&n.match(/^(\d+)(\.\d+)?px$/);return i?Number(i[1]):void 0}var we=!!function(){var t=!1;try{var e=Object.defineProperty({},"passive",{get:function(){t=!0}});window.addEventListener("e",null,e)}catch(t){}return t}()&&{passive:!0};function Me(t,e,n){t.addEventListener(e,n,we)}function Se(t,e,n){t.removeEventListener(e,n,we)}function Ce(t,e,n,i,a){return{type:t,chart:e,native:a||null,x:void 0!==n?n:null,y:void 0!==i?i:null}}function Pe(t){var e=document.createElement("div");return e.className=t||"",e}function Ae(t,e,n){var i,a,r,o,s=t[me]||(t[me]={}),l=s.resizer=function(t){var e=Pe(ve),n=Pe(ve+"-expand"),i=Pe(ve+"-shrink");n.appendChild(Pe()),i.appendChild(Pe()),e.appendChild(n),e.appendChild(i),e._reset=function(){n.scrollLeft=1e6,n.scrollTop=1e6,i.scrollLeft=1e6,i.scrollTop=1e6};var a=function(){e._reset(),t()};return Me(n,"scroll",a.bind(n,"expand")),Me(i,"scroll",a.bind(i,"shrink")),e}((i=function(){if(s.resizer){var i=n.options.maintainAspectRatio&&t.parentNode,a=i?i.clientWidth:0;e(Ce("resize",n)),i&&i.clientWidth0){var r=t[0];r.label?n=r.label:r.xLabel?n=r.xLabel:a>0&&r.index-1?t.split("\n"):t}function We(t){var e=z.global;return{xPadding:t.xPadding,yPadding:t.yPadding,xAlign:t.xAlign,yAlign:t.yAlign,rtl:t.rtl,textDirection:t.textDirection,bodyFontColor:t.bodyFontColor,_bodyFontFamily:Re(t.bodyFontFamily,e.defaultFontFamily),_bodyFontStyle:Re(t.bodyFontStyle,e.defaultFontStyle),_bodyAlign:t.bodyAlign,bodyFontSize:Re(t.bodyFontSize,e.defaultFontSize),bodySpacing:t.bodySpacing,titleFontColor:t.titleFontColor,_titleFontFamily:Re(t.titleFontFamily,e.defaultFontFamily),_titleFontStyle:Re(t.titleFontStyle,e.defaultFontStyle),titleFontSize:Re(t.titleFontSize,e.defaultFontSize),_titleAlign:t.titleAlign,titleSpacing:t.titleSpacing,titleMarginBottom:t.titleMarginBottom,footerFontColor:t.footerFontColor,_footerFontFamily:Re(t.footerFontFamily,e.defaultFontFamily),_footerFontStyle:Re(t.footerFontStyle,e.defaultFontStyle),footerFontSize:Re(t.footerFontSize,e.defaultFontSize),_footerAlign:t.footerAlign,footerSpacing:t.footerSpacing,footerMarginTop:t.footerMarginTop,caretSize:t.caretSize,cornerRadius:t.cornerRadius,backgroundColor:t.backgroundColor,opacity:0,legendColorBackground:t.multiKeyBackground,displayColors:t.displayColors,borderColor:t.borderColor,borderWidth:t.borderWidth}}function Ve(t,e){return"center"===e?t.x+t.width/2:"right"===e?t.x+t.width-t.xPadding:t.x+t.xPadding}function He(t){return Be([],Ee(t))}var je=X.extend({initialize:function(){this._model=We(this._options),this._lastActive=[]},getTitle:function(){var t=this,e=t._options,n=e.callbacks,i=n.beforeTitle.apply(t,arguments),a=n.title.apply(t,arguments),r=n.afterTitle.apply(t,arguments),o=[];return o=Be(o,Ee(i)),o=Be(o,Ee(a)),o=Be(o,Ee(r))},getBeforeBody:function(){return He(this._options.callbacks.beforeBody.apply(this,arguments))},getBody:function(t,e){var n=this,i=n._options.callbacks,a=[];return V.each(t,(function(t){var r={before:[],lines:[],after:[]};Be(r.before,Ee(i.beforeLabel.call(n,t,e))),Be(r.lines,i.label.call(n,t,e)),Be(r.after,Ee(i.afterLabel.call(n,t,e))),a.push(r)})),a},getAfterBody:function(){return He(this._options.callbacks.afterBody.apply(this,arguments))},getFooter:function(){var t=this,e=t._options.callbacks,n=e.beforeFooter.apply(t,arguments),i=e.footer.apply(t,arguments),a=e.afterFooter.apply(t,arguments),r=[];return r=Be(r,Ee(n)),r=Be(r,Ee(i)),r=Be(r,Ee(a))},update:function(t){var e,n,i,a,r,o,s,l,u,d,h=this,c=h._options,f=h._model,g=h._model=We(c),p=h._active,m=h._data,v={xAlign:f.xAlign,yAlign:f.yAlign},b={x:f.x,y:f.y},x={width:f.width,height:f.height},y={x:f.caretX,y:f.caretY};if(p.length){g.opacity=1;var _=[],k=[];y=Ne[c.position].call(h,p,h._eventPosition);var w=[];for(e=0,n=p.length;ei.width&&(a=i.width-e.width),a<0&&(a=0)),"top"===d?r+=h:r-="bottom"===d?e.height+h:e.height/2,"center"===d?"left"===u?a+=h:"right"===u&&(a-=h):"left"===u?a-=c:"right"===u&&(a+=c),{x:a,y:r}}(g,x,v=function(t,e){var n,i,a,r,o,s=t._model,l=t._chart,u=t._chart.chartArea,d="center",h="center";s.yl.height-e.height&&(h="bottom");var c=(u.left+u.right)/2,f=(u.top+u.bottom)/2;"center"===h?(n=function(t){return t<=c},i=function(t){return t>c}):(n=function(t){return t<=e.width/2},i=function(t){return t>=l.width-e.width/2}),a=function(t){return t+e.width+s.caretSize+s.caretPadding>l.width},r=function(t){return t-e.width-s.caretSize-s.caretPadding<0},o=function(t){return t<=f?"top":"bottom"},n(s.x)?(d="left",a(s.x)&&(d="center",h=o(s.y))):i(s.x)&&(d="right",r(s.x)&&(d="center",h=o(s.y)));var g=t._options;return{xAlign:g.xAlign?g.xAlign:d,yAlign:g.yAlign?g.yAlign:h}}(this,x),h._chart)}else g.opacity=0;return g.xAlign=v.xAlign,g.yAlign=v.yAlign,g.x=b.x,g.y=b.y,g.width=x.width,g.height=x.height,g.caretX=y.x,g.caretY=y.y,h._model=g,t&&c.custom&&c.custom.call(h,g),h},drawCaret:function(t,e){var n=this._chart.ctx,i=this._view,a=this.getCaretPosition(t,e,i);n.lineTo(a.x1,a.y1),n.lineTo(a.x2,a.y2),n.lineTo(a.x3,a.y3)},getCaretPosition:function(t,e,n){var i,a,r,o,s,l,u=n.caretSize,d=n.cornerRadius,h=n.xAlign,c=n.yAlign,f=t.x,g=t.y,p=e.width,m=e.height;if("center"===c)s=g+m/2,"left"===h?(a=(i=f)-u,r=i,o=s+u,l=s-u):(a=(i=f+p)+u,r=i,o=s-u,l=s+u);else if("left"===h?(i=(a=f+d+u)-u,r=a+u):"right"===h?(i=(a=f+p-d-u)-u,r=a+u):(i=(a=n.caretX)-u,r=a+u),"top"===c)s=(o=g)-u,l=o;else{s=(o=g+m)+u,l=o;var v=r;r=i,i=v}return{x1:i,x2:a,x3:r,y1:o,y2:s,y3:l}},drawTitle:function(t,e,n){var i,a,r,o=e.title,s=o.length;if(s){var l=ze(e.rtl,e.x,e.width);for(t.x=Ve(e,e._titleAlign),n.textAlign=l.textAlign(e._titleAlign),n.textBaseline="middle",i=e.titleFontSize,a=e.titleSpacing,n.fillStyle=e.titleFontColor,n.font=V.fontString(i,e._titleFontStyle,e._titleFontFamily),r=0;r0&&n.stroke()},draw:function(){var t=this._chart.ctx,e=this._view;if(0!==e.opacity){var n={width:e.width,height:e.height},i={x:e.x,y:e.y},a=Math.abs(e.opacity<.001)?0:e.opacity,r=e.title.length||e.beforeBody.length||e.body.length||e.afterBody.length||e.footer.length;this._options.enabled&&r&&(t.save(),t.globalAlpha=a,this.drawBackground(i,e,t,n),i.y+=e.yPadding,V.rtl.overrideTextDirection(t,e.textDirection),this.drawTitle(i,e,t),this.drawBody(i,e,t),this.drawFooter(i,e,t),V.rtl.restoreTextDirection(t,e.textDirection),t.restore())}},handleEvent:function(t){var e,n=this,i=n._options;return n._lastActive=n._lastActive||[],"mouseout"===t.type?n._active=[]:(n._active=n._chart.getElementsAtEventForMode(t,i.mode,i),i.reverse&&n._active.reverse()),(e=!V.arrayEquals(n._active,n._lastActive))&&(n._lastActive=n._active,(i.enabled||i.custom)&&(n._eventPosition={x:t.x,y:t.y},n.update(!0),n.pivot())),e}}),qe=Ne,Ue=je;Ue.positioners=qe;var Ye=V.valueOrDefault;function Ge(){return V.merge({},[].slice.call(arguments),{merger:function(t,e,n,i){if("xAxes"===t||"yAxes"===t){var a,r,o,s=n[t].length;for(e[t]||(e[t]=[]),a=0;a=e[t].length&&e[t].push({}),!e[t][a].type||o.type&&o.type!==e[t][a].type?V.merge(e[t][a],[Oe.getScaleDefaults(r),o]):V.merge(e[t][a],o)}else V._merger(t,e,n,i)}})}function Xe(){return V.merge({},[].slice.call(arguments),{merger:function(t,e,n,i){var a=e[t]||{},r=n[t];"scales"===t?e[t]=Ge(a,r):"scale"===t?e[t]=V.merge(a,[Oe.getScaleDefaults(r.type),r]):V._merger(t,e,n,i)}})}function Ke(t){var e=t.options;V.each(t.scales,(function(e){ge.removeBox(t,e)})),e=Xe(z.global,z[t.config.type],e),t.options=t.config.options=e,t.ensureScalesHaveIDs(),t.buildOrUpdateScales(),t.tooltip._options=e.tooltips,t.tooltip.initialize()}function Ze(t,e,n){var i,a=function(t){return t.id===i};do{i=e+n++}while(V.findIndex(t,a)>=0);return i}function $e(t){return"top"===t||"bottom"===t}function Je(t,e){return function(n,i){return n[t]===i[t]?n[e]-i[e]:n[t]-i[t]}}z._set("global",{elements:{},events:["mousemove","mouseout","click","touchstart","touchmove"],hover:{onHover:null,mode:"nearest",intersect:!0,animationDuration:400},onClick:null,maintainAspectRatio:!0,responsive:!0,responsiveAnimationDuration:0});var Qe=function(t,e){return this.construct(t,e),this};V.extend(Qe.prototype,{construct:function(t,e){var n=this;e=function(t){var e=(t=t||{}).data=t.data||{};return e.datasets=e.datasets||[],e.labels=e.labels||[],t.options=Xe(z.global,z[t.type],t.options||{}),t}(e);var i=Fe.acquireContext(t,e),a=i&&i.canvas,r=a&&a.height,o=a&&a.width;n.id=V.uid(),n.ctx=i,n.canvas=a,n.config=e,n.width=o,n.height=r,n.aspectRatio=r?o/r:null,n.options=e.options,n._bufferedRender=!1,n._layers=[],n.chart=n,n.controller=n,Qe.instances[n.id]=n,Object.defineProperty(n,"data",{get:function(){return n.config.data},set:function(t){n.config.data=t}}),i&&a?(n.initialize(),n.update()):console.error("Failed to create chart: can't acquire context from the given item")},initialize:function(){var t=this;return Le.notify(t,"beforeInit"),V.retinaScale(t,t.options.devicePixelRatio),t.bindEvents(),t.options.responsive&&t.resize(!0),t.initToolTip(),Le.notify(t,"afterInit"),t},clear:function(){return V.canvas.clear(this),this},stop:function(){return $.cancelAnimation(this),this},resize:function(t){var e=this,n=e.options,i=e.canvas,a=n.maintainAspectRatio&&e.aspectRatio||null,r=Math.max(0,Math.floor(V.getMaximumWidth(i))),o=Math.max(0,Math.floor(a?r/a:V.getMaximumHeight(i)));if((e.width!==r||e.height!==o)&&(i.width=e.width=r,i.height=e.height=o,i.style.width=r+"px",i.style.height=o+"px",V.retinaScale(e,n.devicePixelRatio),!t)){var s={width:r,height:o};Le.notify(e,"resize",[s]),n.onResize&&n.onResize(e,s),e.stop(),e.update({duration:n.responsiveAnimationDuration})}},ensureScalesHaveIDs:function(){var t=this.options,e=t.scales||{},n=t.scale;V.each(e.xAxes,(function(t,n){t.id||(t.id=Ze(e.xAxes,"x-axis-",n))})),V.each(e.yAxes,(function(t,n){t.id||(t.id=Ze(e.yAxes,"y-axis-",n))})),n&&(n.id=n.id||"scale")},buildOrUpdateScales:function(){var t=this,e=t.options,n=t.scales||{},i=[],a=Object.keys(n).reduce((function(t,e){return t[e]=!1,t}),{});e.scales&&(i=i.concat((e.scales.xAxes||[]).map((function(t){return{options:t,dtype:"category",dposition:"bottom"}})),(e.scales.yAxes||[]).map((function(t){return{options:t,dtype:"linear",dposition:"left"}})))),e.scale&&i.push({options:e.scale,dtype:"radialLinear",isDefault:!0,dposition:"chartArea"}),V.each(i,(function(e){var i=e.options,r=i.id,o=Ye(i.type,e.dtype);$e(i.position)!==$e(e.dposition)&&(i.position=e.dposition),a[r]=!0;var s=null;if(r in n&&n[r].type===o)(s=n[r]).options=i,s.ctx=t.ctx,s.chart=t;else{var l=Oe.getScaleConstructor(o);if(!l)return;s=new l({id:r,type:o,options:i,ctx:t.ctx,chart:t}),n[s.id]=s}s.mergeTicksOptions(),e.isDefault&&(t.scale=s)})),V.each(a,(function(t,e){t||delete n[e]})),t.scales=n,Oe.addScalesToLayout(this)},buildOrUpdateControllers:function(){var t,e,n=this,i=[],a=n.data.datasets;for(t=0,e=a.length;t=0;--n)this.drawDataset(e[n],t);Le.notify(this,"afterDatasetsDraw",[t])}},drawDataset:function(t,e){var n={meta:t,index:t.index,easingValue:e};!1!==Le.notify(this,"beforeDatasetDraw",[n])&&(t.controller.draw(e),Le.notify(this,"afterDatasetDraw",[n]))},_drawTooltip:function(t){var e=this.tooltip,n={tooltip:e,easingValue:t};!1!==Le.notify(this,"beforeTooltipDraw",[n])&&(e.draw(),Le.notify(this,"afterTooltipDraw",[n]))},getElementAtEvent:function(t){return ae.modes.single(this,t)},getElementsAtEvent:function(t){return ae.modes.label(this,t,{intersect:!0})},getElementsAtXAxis:function(t){return ae.modes["x-axis"](this,t,{intersect:!0})},getElementsAtEventForMode:function(t,e,n){var i=ae.modes[e];return"function"==typeof i?i(this,t,n):[]},getDatasetAtEvent:function(t){return ae.modes.dataset(this,t,{intersect:!0})},getDatasetMeta:function(t){var e=this.data.datasets[t];e._meta||(e._meta={});var n=e._meta[this.id];return n||(n=e._meta[this.id]={type:null,data:[],dataset:null,controller:null,hidden:null,xAxisID:null,yAxisID:null,order:e.order||0,index:t}),n},getVisibleDatasetCount:function(){for(var t=0,e=0,n=this.data.datasets.length;e3?n[2]-n[1]:n[1]-n[0];Math.abs(i)>1&&t!==Math.floor(t)&&(i=t-Math.floor(t));var a=V.log10(Math.abs(i)),r="";if(0!==t)if(Math.max(Math.abs(n[0]),Math.abs(n[n.length-1]))<1e-4){var o=V.log10(Math.abs(t)),s=Math.floor(o)-Math.floor(a);s=Math.max(Math.min(s,20),0),r=t.toExponential(s)}else{var l=-1*Math.floor(a);l=Math.max(Math.min(l,20),0),r=t.toFixed(l)}else r="0";return r},logarithmic:function(t,e,n){var i=t/Math.pow(10,Math.floor(V.log10(t)));return 0===t?"0":1===i||2===i||5===i||0===e||e===n.length-1?t.toExponential():""}}},on=V.isArray,sn=V.isNullOrUndef,ln=V.valueOrDefault,un=V.valueAtIndexOrDefault;function dn(t,e,n){var i,a=t.getTicks().length,r=Math.min(e,a-1),o=t.getPixelForTick(r),s=t._startPixel,l=t._endPixel;if(!(n&&(i=1===a?Math.max(o-s,l-o):0===e?(t.getPixelForTick(1)-o)/2:(o-t.getPixelForTick(r-1))/2,(o+=rl+1e-6)))return o}function hn(t,e,n,i){var a,r,o,s,l,u,d,h,c,f,g,p,m,v=n.length,b=[],x=[],y=[];for(a=0;ae){for(n=0;n=c||d<=1||!s.isHorizontal()?s.labelRotation=h:(e=(t=s._getLabelSizes()).widest.width,n=t.highest.height-t.highest.offset,i=Math.min(s.maxWidth,s.chart.width-e),e+6>(a=l.offset?s.maxWidth/d:i/(d-1))&&(a=i/(d-(l.offset?.5:1)),r=s.maxHeight-cn(l.gridLines)-u.padding-fn(l.scaleLabel),o=Math.sqrt(e*e+n*n),f=V.toDegrees(Math.min(Math.asin(Math.min((t.highest.height+6)/a,1)),Math.asin(Math.min(r/o,1))-Math.asin(n/o))),f=Math.max(h,Math.min(c,f))),s.labelRotation=f)},afterCalculateTickRotation:function(){V.callback(this.options.afterCalculateTickRotation,[this])},beforeFit:function(){V.callback(this.options.beforeFit,[this])},fit:function(){var t=this,e=t.minSize={width:0,height:0},n=t.chart,i=t.options,a=i.ticks,r=i.scaleLabel,o=i.gridLines,s=t._isVisible(),l="bottom"===i.position,u=t.isHorizontal();if(u?e.width=t.maxWidth:s&&(e.width=cn(o)+fn(r)),u?s&&(e.height=cn(o)+fn(r)):e.height=t.maxHeight,a.display&&s){var d=pn(a),h=t._getLabelSizes(),c=h.first,f=h.last,g=h.widest,p=h.highest,m=.4*d.minor.lineHeight,v=a.padding;if(u){var b=0!==t.labelRotation,x=V.toRadians(t.labelRotation),y=Math.cos(x),_=Math.sin(x),k=_*g.width+y*(p.height-(b?p.offset:0))+(b?0:m);e.height=Math.min(t.maxHeight,e.height+k+v);var w,M,S=t.getPixelForTick(0)-t.left,C=t.right-t.getPixelForTick(t.getTicks().length-1);b?(w=l?y*c.width+_*c.offset:_*(c.height-c.offset),M=l?_*(f.height-f.offset):y*f.width+_*f.offset):(w=c.width/2,M=f.width/2),t.paddingLeft=Math.max((w-S)*t.width/(t.width-S),0)+3,t.paddingRight=Math.max((M-C)*t.width/(t.width-C),0)+3}else{var P=a.mirror?0:g.width+v+m;e.width=Math.min(t.maxWidth,e.width+P),t.paddingTop=c.height/2,t.paddingBottom=f.height/2}}t.handleMargins(),u?(t.width=t._length=n.width-t.margins.left-t.margins.right,t.height=e.height):(t.width=e.width,t.height=t._length=n.height-t.margins.top-t.margins.bottom)},handleMargins:function(){var t=this;t.margins&&(t.margins.left=Math.max(t.paddingLeft,t.margins.left),t.margins.top=Math.max(t.paddingTop,t.margins.top),t.margins.right=Math.max(t.paddingRight,t.margins.right),t.margins.bottom=Math.max(t.paddingBottom,t.margins.bottom))},afterFit:function(){V.callback(this.options.afterFit,[this])},isHorizontal:function(){var t=this.options.position;return"top"===t||"bottom"===t},isFullWidth:function(){return this.options.fullWidth},getRightValue:function(t){if(sn(t))return NaN;if(("number"==typeof t||t instanceof Number)&&!isFinite(t))return NaN;if(t)if(this.isHorizontal()){if(void 0!==t.x)return this.getRightValue(t.x)}else if(void 0!==t.y)return this.getRightValue(t.y);return t},_convertTicksToLabels:function(t){var e,n,i,a=this;for(a.ticks=t.map((function(t){return t.value})),a.beforeTickToLabelConversion(),e=a.convertTicksToLabels(t)||a.ticks,a.afterTickToLabelConversion(),n=0,i=t.length;nn-1?null:this.getPixelForDecimal(t*i+(e?i/2:0))},getPixelForDecimal:function(t){return this._reversePixels&&(t=1-t),this._startPixel+t*this._length},getDecimalForPixel:function(t){var e=(t-this._startPixel)/this._length;return this._reversePixels?1-e:e},getBasePixel:function(){return this.getPixelForValue(this.getBaseValue())},getBaseValue:function(){var t=this.min,e=this.max;return this.beginAtZero?0:t<0&&e<0?e:t>0&&e>0?t:0},_autoSkip:function(t){var e,n,i,a,r=this.options.ticks,o=this._length,s=r.maxTicksLimit||o/this._tickSize()+1,l=r.major.enabled?function(t){var e,n,i=[];for(e=0,n=t.length;es)return function(t,e,n){var i,a,r=0,o=e[0];for(n=Math.ceil(n),i=0;iu)return r;return Math.max(u,1)}(l,t,0,s),u>0){for(e=0,n=u-1;e1?(h-d)/(u-1):null,vn(t,i,V.isNullOrUndef(a)?0:d-a,d),vn(t,i,h,V.isNullOrUndef(a)?t.length:h+a),mn(t)}return vn(t,i),mn(t)},_tickSize:function(){var t=this.options.ticks,e=V.toRadians(this.labelRotation),n=Math.abs(Math.cos(e)),i=Math.abs(Math.sin(e)),a=this._getLabelSizes(),r=t.autoSkipPadding||0,o=a?a.widest.width+r:0,s=a?a.highest.height+r:0;return this.isHorizontal()?s*n>o*i?o/n:s/i:s*i=0&&(o=t),void 0!==r&&(t=n.indexOf(r))>=0&&(s=t),e.minIndex=o,e.maxIndex=s,e.min=n[o],e.max=n[s]},buildTicks:function(){var t=this._getLabels(),e=this.minIndex,n=this.maxIndex;this.ticks=0===e&&n===t.length-1?t:t.slice(e,n+1)},getLabelForIndex:function(t,e){var n=this.chart;return n.getDatasetMeta(e).controller._getValueScaleId()===this.id?this.getRightValue(n.data.datasets[e].data[t]):this._getLabels()[t]},_configure:function(){var t=this,e=t.options.offset,n=t.ticks;xn.prototype._configure.call(t),t.isHorizontal()||(t._reversePixels=!t._reversePixels),n&&(t._startValue=t.minIndex-(e?.5:0),t._valueRange=Math.max(n.length-(e?0:1),1))},getPixelForValue:function(t,e,n){var i,a,r,o=this;return yn(e)||yn(n)||(t=o.chart.data.datasets[n].data[e]),yn(t)||(i=o.isHorizontal()?t.x:t.y),(void 0!==i||void 0!==t&&isNaN(e))&&(a=o._getLabels(),t=V.valueOrDefault(i,t),e=-1!==(r=a.indexOf(t))?r:e,isNaN(e)&&(e=t)),o.getPixelForDecimal((e-o._startValue)/o._valueRange)},getPixelForTick:function(t){var e=this.ticks;return t<0||t>e.length-1?null:this.getPixelForValue(e[t],t+this.minIndex)},getValueForPixel:function(t){var e=Math.round(this._startValue+this.getDecimalForPixel(t)*this._valueRange);return Math.min(Math.max(e,0),this.ticks.length-1)},getBasePixel:function(){return this.bottom}}),kn={position:"bottom"};_n._defaults=kn;var wn=V.noop,Mn=V.isNullOrUndef;var Sn=xn.extend({getRightValue:function(t){return"string"==typeof t?+t:xn.prototype.getRightValue.call(this,t)},handleTickRangeOptions:function(){var t=this,e=t.options.ticks;if(e.beginAtZero){var n=V.sign(t.min),i=V.sign(t.max);n<0&&i<0?t.max=0:n>0&&i>0&&(t.min=0)}var a=void 0!==e.min||void 0!==e.suggestedMin,r=void 0!==e.max||void 0!==e.suggestedMax;void 0!==e.min?t.min=e.min:void 0!==e.suggestedMin&&(null===t.min?t.min=e.suggestedMin:t.min=Math.min(t.min,e.suggestedMin)),void 0!==e.max?t.max=e.max:void 0!==e.suggestedMax&&(null===t.max?t.max=e.suggestedMax:t.max=Math.max(t.max,e.suggestedMax)),a!==r&&t.min>=t.max&&(a?t.max=t.min+1:t.min=t.max-1),t.min===t.max&&(t.max++,e.beginAtZero||t.min--)},getTickLimit:function(){var t,e=this.options.ticks,n=e.stepSize,i=e.maxTicksLimit;return n?t=Math.ceil(this.max/n)-Math.floor(this.min/n)+1:(t=this._computeTickLimit(),i=i||11),i&&(t=Math.min(i,t)),t},_computeTickLimit:function(){return Number.POSITIVE_INFINITY},handleDirectionalChanges:wn,buildTicks:function(){var t=this,e=t.options.ticks,n=t.getTickLimit(),i={maxTicks:n=Math.max(2,n),min:e.min,max:e.max,precision:e.precision,stepSize:V.valueOrDefault(e.fixedStepSize,e.stepSize)},a=t.ticks=function(t,e){var n,i,a,r,o=[],s=t.stepSize,l=s||1,u=t.maxTicks-1,d=t.min,h=t.max,c=t.precision,f=e.min,g=e.max,p=V.niceNum((g-f)/u/l)*l;if(p<1e-14&&Mn(d)&&Mn(h))return[f,g];(r=Math.ceil(g/p)-Math.floor(f/p))>u&&(p=V.niceNum(r*p/u/l)*l),s||Mn(c)?n=Math.pow(10,V._decimalPlaces(p)):(n=Math.pow(10,c),p=Math.ceil(p*n)/n),i=Math.floor(f/p)*p,a=Math.ceil(g/p)*p,s&&(!Mn(d)&&V.almostWhole(d/p,p/1e3)&&(i=d),!Mn(h)&&V.almostWhole(h/p,p/1e3)&&(a=h)),r=(a-i)/p,r=V.almostEquals(r,Math.round(r),p/1e3)?Math.round(r):Math.ceil(r),i=Math.round(i*n)/n,a=Math.round(a*n)/n,o.push(Mn(d)?i:d);for(var m=1;me.length-1?null:this.getPixelForValue(e[t])}}),Tn=Cn;Dn._defaults=Tn;var In=V.valueOrDefault,Fn=V.math.log10;var Ln={position:"left",ticks:{callback:rn.formatters.logarithmic}};function On(t,e){return V.isFinite(t)&&t>=0?t:e}var Rn=xn.extend({determineDataLimits:function(){var t,e,n,i,a,r,o=this,s=o.options,l=o.chart,u=l.data.datasets,d=o.isHorizontal();function h(t){return d?t.xAxisID===o.id:t.yAxisID===o.id}o.min=Number.POSITIVE_INFINITY,o.max=Number.NEGATIVE_INFINITY,o.minNotZero=Number.POSITIVE_INFINITY;var c=s.stacked;if(void 0===c)for(t=0;t0){var e=V.min(t),n=V.max(t);o.min=Math.min(o.min,e),o.max=Math.max(o.max,n)}}))}else for(t=0;t0?t.minNotZero=t.min:t.max<1?t.minNotZero=Math.pow(10,Math.floor(Fn(t.max))):t.minNotZero=1)},buildTicks:function(){var t=this,e=t.options.ticks,n=!t.isHorizontal(),i={min:On(e.min),max:On(e.max)},a=t.ticks=function(t,e){var n,i,a=[],r=In(t.min,Math.pow(10,Math.floor(Fn(e.min)))),o=Math.floor(Fn(e.max)),s=Math.ceil(e.max/Math.pow(10,o));0===r?(n=Math.floor(Fn(e.minNotZero)),i=Math.floor(e.minNotZero/Math.pow(10,n)),a.push(r),r=i*Math.pow(10,n)):(n=Math.floor(Fn(r)),i=Math.floor(r/Math.pow(10,n)));var l=n<0?Math.pow(10,Math.abs(n)):1;do{a.push(r),10===++i&&(i=1,l=++n>=0?1:l),r=Math.round(i*Math.pow(10,n)*l)/l}while(ne.length-1?null:this.getPixelForValue(e[t])},_getFirstTickValue:function(t){var e=Math.floor(Fn(t));return Math.floor(t/Math.pow(10,e))*Math.pow(10,e)},_configure:function(){var t=this,e=t.min,n=0;xn.prototype._configure.call(t),0===e&&(e=t._getFirstTickValue(t.minNotZero),n=In(t.options.ticks.fontSize,z.global.defaultFontSize)/t._length),t._startValue=Fn(e),t._valueOffset=n,t._valueRange=(Fn(t.max)-Fn(e))/(1-n)},getPixelForValue:function(t){var e=this,n=0;return(t=+e.getRightValue(t))>e.min&&t>0&&(n=(Fn(t)-e._startValue)/e._valueRange+e._valueOffset),e.getPixelForDecimal(n)},getValueForPixel:function(t){var e=this,n=e.getDecimalForPixel(t);return 0===n&&0===e.min?0:Math.pow(10,e._startValue+(n-e._valueOffset)*e._valueRange)}}),zn=Ln;Rn._defaults=zn;var Nn=V.valueOrDefault,Bn=V.valueAtIndexOrDefault,En=V.options.resolve,Wn={display:!0,animate:!0,position:"chartArea",angleLines:{display:!0,color:"rgba(0,0,0,0.1)",lineWidth:1,borderDash:[],borderDashOffset:0},gridLines:{circular:!1},ticks:{showLabelBackdrop:!0,backdropColor:"rgba(255,255,255,0.75)",backdropPaddingY:2,backdropPaddingX:2,callback:rn.formatters.linear},pointLabels:{display:!0,fontSize:10,callback:function(t){return t}}};function Vn(t){var e=t.ticks;return e.display&&t.display?Nn(e.fontSize,z.global.defaultFontSize)+2*e.backdropPaddingY:0}function Hn(t,e,n,i,a){return t===i||t===a?{start:e-n/2,end:e+n/2}:ta?{start:e-n,end:e}:{start:e,end:e+n}}function jn(t){return 0===t||180===t?"center":t<180?"left":"right"}function qn(t,e,n,i){var a,r,o=n.y+i/2;if(V.isArray(e))for(a=0,r=e.length;a270||t<90)&&(n.y-=e.h)}function Yn(t){return V.isNumber(t)?t:0}var Gn=Sn.extend({setDimensions:function(){var t=this;t.width=t.maxWidth,t.height=t.maxHeight,t.paddingTop=Vn(t.options)/2,t.xCenter=Math.floor(t.width/2),t.yCenter=Math.floor((t.height-t.paddingTop)/2),t.drawingArea=Math.min(t.height-t.paddingTop,t.width)/2},determineDataLimits:function(){var t=this,e=t.chart,n=Number.POSITIVE_INFINITY,i=Number.NEGATIVE_INFINITY;V.each(e.data.datasets,(function(a,r){if(e.isDatasetVisible(r)){var o=e.getDatasetMeta(r);V.each(a.data,(function(e,a){var r=+t.getRightValue(e);isNaN(r)||o.data[a].hidden||(n=Math.min(r,n),i=Math.max(r,i))}))}})),t.min=n===Number.POSITIVE_INFINITY?0:n,t.max=i===Number.NEGATIVE_INFINITY?0:i,t.handleTickRangeOptions()},_computeTickLimit:function(){return Math.ceil(this.drawingArea/Vn(this.options))},convertTicksToLabels:function(){var t=this;Sn.prototype.convertTicksToLabels.call(t),t.pointLabels=t.chart.data.labels.map((function(){var e=V.callback(t.options.pointLabels.callback,arguments,t);return e||0===e?e:""}))},getLabelForIndex:function(t,e){return+this.getRightValue(this.chart.data.datasets[e].data[t])},fit:function(){var t=this.options;t.display&&t.pointLabels.display?function(t){var e,n,i,a=V.options._parseFont(t.options.pointLabels),r={l:0,r:t.width,t:0,b:t.height-t.paddingTop},o={};t.ctx.font=a.string,t._pointLabelSizes=[];var s,l,u,d=t.chart.data.labels.length;for(e=0;er.r&&(r.r=f.end,o.r=h),g.startr.b&&(r.b=g.end,o.b=h)}t.setReductions(t.drawingArea,r,o)}(this):this.setCenterPoint(0,0,0,0)},setReductions:function(t,e,n){var i=this,a=e.l/Math.sin(n.l),r=Math.max(e.r-i.width,0)/Math.sin(n.r),o=-e.t/Math.cos(n.t),s=-Math.max(e.b-(i.height-i.paddingTop),0)/Math.cos(n.b);a=Yn(a),r=Yn(r),o=Yn(o),s=Yn(s),i.drawingArea=Math.min(Math.floor(t-(a+r)/2),Math.floor(t-(o+s)/2)),i.setCenterPoint(a,r,o,s)},setCenterPoint:function(t,e,n,i){var a=this,r=a.width-e-a.drawingArea,o=t+a.drawingArea,s=n+a.drawingArea,l=a.height-a.paddingTop-i-a.drawingArea;a.xCenter=Math.floor((o+r)/2+a.left),a.yCenter=Math.floor((s+l)/2+a.top+a.paddingTop)},getIndexAngle:function(t){var e=this.chart,n=(t*(360/e.data.labels.length)+((e.options||{}).startAngle||0))%360;return(n<0?n+360:n)*Math.PI*2/360},getDistanceFromCenterForValue:function(t){var e=this;if(V.isNullOrUndef(t))return NaN;var n=e.drawingArea/(e.max-e.min);return e.options.ticks.reverse?(e.max-t)*n:(t-e.min)*n},getPointPosition:function(t,e){var n=this.getIndexAngle(t)-Math.PI/2;return{x:Math.cos(n)*e+this.xCenter,y:Math.sin(n)*e+this.yCenter}},getPointPositionForValue:function(t,e){return this.getPointPosition(t,this.getDistanceFromCenterForValue(e))},getBasePosition:function(t){var e=this.min,n=this.max;return this.getPointPositionForValue(t||0,this.beginAtZero?0:e<0&&n<0?n:e>0&&n>0?e:0)},_drawGrid:function(){var t,e,n,i=this,a=i.ctx,r=i.options,o=r.gridLines,s=r.angleLines,l=Nn(s.lineWidth,o.lineWidth),u=Nn(s.color,o.color);if(r.pointLabels.display&&function(t){var e=t.ctx,n=t.options,i=n.pointLabels,a=Vn(n),r=t.getDistanceFromCenterForValue(n.ticks.reverse?t.min:t.max),o=V.options._parseFont(i);e.save(),e.font=o.string,e.textBaseline="middle";for(var s=t.chart.data.labels.length-1;s>=0;s--){var l=0===s?a/2:0,u=t.getPointPosition(s,r+l+5),d=Bn(i.fontColor,s,z.global.defaultFontColor);e.fillStyle=d;var h=t.getIndexAngle(s),c=V.toDegrees(h);e.textAlign=jn(c),Un(c,t._pointLabelSizes[s],u),qn(e,t.pointLabels[s],u,o.lineHeight)}e.restore()}(i),o.display&&V.each(i.ticks,(function(t,n){0!==n&&(e=i.getDistanceFromCenterForValue(i.ticksAsNumbers[n]),function(t,e,n,i){var a,r=t.ctx,o=e.circular,s=t.chart.data.labels.length,l=Bn(e.color,i-1),u=Bn(e.lineWidth,i-1);if((o||s)&&l&&u){if(r.save(),r.strokeStyle=l,r.lineWidth=u,r.setLineDash&&(r.setLineDash(e.borderDash||[]),r.lineDashOffset=e.borderDashOffset||0),r.beginPath(),o)r.arc(t.xCenter,t.yCenter,n,0,2*Math.PI);else{a=t.getPointPosition(0,n),r.moveTo(a.x,a.y);for(var d=1;d=0;t--)e=i.getDistanceFromCenterForValue(r.ticks.reverse?i.min:i.max),n=i.getPointPosition(t,e),a.beginPath(),a.moveTo(i.xCenter,i.yCenter),a.lineTo(n.x,n.y),a.stroke();a.restore()}},_drawLabels:function(){var t=this,e=t.ctx,n=t.options.ticks;if(n.display){var i,a,r=t.getIndexAngle(0),o=V.options._parseFont(n),s=Nn(n.fontColor,z.global.defaultFontColor);e.save(),e.font=o.string,e.translate(t.xCenter,t.yCenter),e.rotate(r),e.textAlign="center",e.textBaseline="middle",V.each(t.ticks,(function(r,l){(0!==l||n.reverse)&&(i=t.getDistanceFromCenterForValue(t.ticksAsNumbers[l]),n.showLabelBackdrop&&(a=e.measureText(r).width,e.fillStyle=n.backdropColor,e.fillRect(-a/2-n.backdropPaddingX,-i-o.size/2-n.backdropPaddingY,a+2*n.backdropPaddingX,o.size+2*n.backdropPaddingY)),e.fillStyle=s,e.fillText(r,0,-i))})),e.restore()}},_drawTitle:V.noop}),Xn=Wn;Gn._defaults=Xn;var Kn=V._deprecated,Zn=V.options.resolve,$n=V.valueOrDefault,Jn=Number.MIN_SAFE_INTEGER||-9007199254740991,Qn=Number.MAX_SAFE_INTEGER||9007199254740991,ti={millisecond:{common:!0,size:1,steps:1e3},second:{common:!0,size:1e3,steps:60},minute:{common:!0,size:6e4,steps:60},hour:{common:!0,size:36e5,steps:24},day:{common:!0,size:864e5,steps:30},week:{common:!1,size:6048e5,steps:4},month:{common:!0,size:2628e6,steps:12},quarter:{common:!1,size:7884e6,steps:4},year:{common:!0,size:3154e7}},ei=Object.keys(ti);function ni(t,e){return t-e}function ii(t){return V.valueOrDefault(t.time.min,t.ticks.min)}function ai(t){return V.valueOrDefault(t.time.max,t.ticks.max)}function ri(t,e,n,i){var a=function(t,e,n){for(var i,a,r,o=0,s=t.length-1;o>=0&&o<=s;){if(a=t[(i=o+s>>1)-1]||null,r=t[i],!a)return{lo:null,hi:r};if(r[e]n))return{lo:a,hi:r};s=i-1}}return{lo:r,hi:null}}(t,e,n),r=a.lo?a.hi?a.lo:t[t.length-2]:t[0],o=a.lo?a.hi?a.hi:t[t.length-1]:t[1],s=o[e]-r[e],l=s?(n-r[e])/s:0,u=(o[i]-r[i])*l;return r[i]+u}function oi(t,e){var n=t._adapter,i=t.options.time,a=i.parser,r=a||i.format,o=e;return"function"==typeof a&&(o=a(o)),V.isFinite(o)||(o="string"==typeof r?n.parse(o,r):n.parse(o)),null!==o?+o:(a||"function"!=typeof r||(o=r(e),V.isFinite(o)||(o=n.parse(o))),o)}function si(t,e){if(V.isNullOrUndef(e))return null;var n=t.options.time,i=oi(t,t.getRightValue(e));return null===i?i:(n.round&&(i=+t._adapter.startOf(i,n.round)),i)}function li(t,e,n,i){var a,r,o,s=ei.length;for(a=ei.indexOf(t);a=0&&(e[r].major=!0);return e}(t,r,o,n):r}var di=xn.extend({initialize:function(){this.mergeTicksOptions(),xn.prototype.initialize.call(this)},update:function(){var t=this,e=t.options,n=e.time||(e.time={}),i=t._adapter=new an._date(e.adapters.date);return Kn("time scale",n.format,"time.format","time.parser"),Kn("time scale",n.min,"time.min","ticks.min"),Kn("time scale",n.max,"time.max","ticks.max"),V.mergeIf(n.displayFormats,i.formats()),xn.prototype.update.apply(t,arguments)},getRightValue:function(t){return t&&void 0!==t.t&&(t=t.t),xn.prototype.getRightValue.call(this,t)},determineDataLimits:function(){var t,e,n,i,a,r,o,s=this,l=s.chart,u=s._adapter,d=s.options,h=d.time.unit||"day",c=Qn,f=Jn,g=[],p=[],m=[],v=s._getLabels();for(t=0,n=v.length;t1?function(t){var e,n,i,a={},r=[];for(e=0,n=t.length;e1e5*u)throw e+" and "+n+" are too far apart with stepSize of "+u+" "+l;for(a=h;a=a&&n<=r&&d.push(n);return i.min=a,i.max=r,i._unit=l.unit||(s.autoSkip?li(l.minUnit,i.min,i.max,h):function(t,e,n,i,a){var r,o;for(r=ei.length-1;r>=ei.indexOf(n);r--)if(o=ei[r],ti[o].common&&t._adapter.diff(a,i,o)>=e-1)return o;return ei[n?ei.indexOf(n):0]}(i,d.length,l.minUnit,i.min,i.max)),i._majorUnit=s.major.enabled&&"year"!==i._unit?function(t){for(var e=ei.indexOf(t)+1,n=ei.length;ee&&s=0&&t0?s:1}}),hi={position:"bottom",distribution:"linear",bounds:"data",adapters:{},time:{parser:!1,unit:!1,round:!1,displayFormat:!1,isoWeekday:!1,minUnit:"millisecond",displayFormats:{}},ticks:{autoSkip:!1,source:"auto",major:{enabled:!1}}};di._defaults=hi;var ci={category:_n,linear:Dn,logarithmic:Rn,radialLinear:Gn,time:di},fi={datetime:"MMM D, YYYY, h:mm:ss a",millisecond:"h:mm:ss.SSS a",second:"h:mm:ss a",minute:"h:mm a",hour:"hA",day:"MMM D",week:"ll",month:"MMM YYYY",quarter:"[Q]Q - YYYY",year:"YYYY"};an._date.override("function"==typeof t?{_id:"moment",formats:function(){return fi},parse:function(e,n){return"string"==typeof e&&"string"==typeof n?e=t(e,n):e instanceof t||(e=t(e)),e.isValid()?e.valueOf():null},format:function(e,n){return t(e).format(n)},add:function(e,n,i){return t(e).add(n,i).valueOf()},diff:function(e,n,i){return t(e).diff(t(n),i)},startOf:function(e,n,i){return e=t(e),"isoWeek"===n?e.isoWeekday(i).valueOf():e.startOf(n).valueOf()},endOf:function(e,n){return t(e).endOf(n).valueOf()},_create:function(e){return t(e)}}:{}),z._set("global",{plugins:{filler:{propagate:!0}}});var gi={dataset:function(t){var e=t.fill,n=t.chart,i=n.getDatasetMeta(e),a=i&&n.isDatasetVisible(e)&&i.dataset._children||[],r=a.length||0;return r?function(t,e){return e=n)&&i;switch(r){case"bottom":return"start";case"top":return"end";case"zero":return"origin";case"origin":case"start":case"end":return r;default:return!1}}function mi(t){return(t.el._scale||{}).getPointPositionForValue?function(t){var e,n,i,a,r,o=t.el._scale,s=o.options,l=o.chart.data.labels.length,u=t.fill,d=[];if(!l)return null;for(e=s.ticks.reverse?o.max:o.min,n=s.ticks.reverse?o.min:o.max,i=o.getPointPositionForValue(0,e),a=0;a0;--r)V.canvas.lineTo(t,n[r],n[r-1],!0);else for(o=n[0].cx,s=n[0].cy,l=Math.sqrt(Math.pow(n[0].x-o,2)+Math.pow(n[0].y-s,2)),r=a-1;r>0;--r)t.arc(o,s,l,n[r].angle,n[r-1].angle,!0)}}function _i(t,e,n,i,a,r){var o,s,l,u,d,h,c,f,g=e.length,p=i.spanGaps,m=[],v=[],b=0,x=0;for(t.beginPath(),o=0,s=g;o=0;--n)(e=l[n].$filler)&&e.visible&&(a=(i=e.el)._view,r=i._children||[],o=e.mapper,s=a.backgroundColor||z.global.defaultColor,o&&s&&r.length&&(V.canvas.clipArea(u,t.chartArea),_i(u,r,o,a,s,i._loop),V.canvas.unclipArea(u)))}},wi=V.rtl.getRtlAdapter,Mi=V.noop,Si=V.valueOrDefault;function Ci(t,e){return t.usePointStyle&&t.boxWidth>e?e:t.boxWidth}z._set("global",{legend:{display:!0,position:"top",align:"center",fullWidth:!0,reverse:!1,weight:1e3,onClick:function(t,e){var n=e.datasetIndex,i=this.chart,a=i.getDatasetMeta(n);a.hidden=null===a.hidden?!i.data.datasets[n].hidden:null,i.update()},onHover:null,onLeave:null,labels:{boxWidth:40,padding:10,generateLabels:function(t){var e=t.data.datasets,n=t.options.legend||{},i=n.labels&&n.labels.usePointStyle;return t._getSortedDatasetMetas().map((function(n){var a=n.controller.getStyle(i?0:void 0);return{text:e[n.index].label,fillStyle:a.backgroundColor,hidden:!t.isDatasetVisible(n.index),lineCap:a.borderCapStyle,lineDash:a.borderDash,lineDashOffset:a.borderDashOffset,lineJoin:a.borderJoinStyle,lineWidth:a.borderWidth,strokeStyle:a.borderColor,pointStyle:a.pointStyle,rotation:a.rotation,datasetIndex:n.index}}),this)}}},legendCallback:function(t){var e,n,i,a=document.createElement("ul"),r=t.data.datasets;for(a.setAttribute("class",t.id+"-legend"),e=0,n=r.length;el.width)&&(h+=o+n.padding,d[d.length-(e>0?0:1)]=0),s[e]={left:0,top:0,width:i,height:o},d[d.length-1]+=i+n.padding})),l.height+=h}else{var c=n.padding,f=t.columnWidths=[],g=t.columnHeights=[],p=n.padding,m=0,v=0;V.each(t.legendItems,(function(t,e){var i=Ci(n,o)+o/2+a.measureText(t.text).width;e>0&&v+o+2*c>l.height&&(p+=m+n.padding,f.push(m),g.push(v),m=0,v=0),m=Math.max(m,i),v+=o+c,s[e]={left:0,top:0,width:i,height:o}})),p+=m,f.push(m),g.push(v),l.width+=p}t.width=l.width,t.height=l.height}else t.width=l.width=t.height=l.height=0},afterFit:Mi,isHorizontal:function(){return"top"===this.options.position||"bottom"===this.options.position},draw:function(){var t=this,e=t.options,n=e.labels,i=z.global,a=i.defaultColor,r=i.elements.line,o=t.height,s=t.columnHeights,l=t.width,u=t.lineWidths;if(e.display){var d,h=wi(e.rtl,t.left,t.minSize.width),c=t.ctx,f=Si(n.fontColor,i.defaultFontColor),g=V.options._parseFont(n),p=g.size;c.textAlign=h.textAlign("left"),c.textBaseline="middle",c.lineWidth=.5,c.strokeStyle=f,c.fillStyle=f,c.font=g.string;var m=Ci(n,p),v=t.legendHitBoxes,b=function(t,i){switch(e.align){case"start":return n.padding;case"end":return t-i;default:return(t-i+n.padding)/2}},x=t.isHorizontal();d=x?{x:t.left+b(l,u[0]),y:t.top+n.padding,line:0}:{x:t.left+n.padding,y:t.top+b(o,s[0]),line:0},V.rtl.overrideTextDirection(t.ctx,e.textDirection);var y=p+n.padding;V.each(t.legendItems,(function(e,i){var f=c.measureText(e.text).width,g=m+p/2+f,_=d.x,k=d.y;h.setWidth(t.minSize.width),x?i>0&&_+g+n.padding>t.left+t.minSize.width&&(k=d.y+=y,d.line++,_=d.x=t.left+b(l,u[d.line])):i>0&&k+y>t.top+t.minSize.height&&(_=d.x=_+t.columnWidths[d.line]+n.padding,d.line++,k=d.y=t.top+b(o,s[d.line]));var w=h.x(_);!function(t,e,i){if(!(isNaN(m)||m<=0)){c.save();var o=Si(i.lineWidth,r.borderWidth);if(c.fillStyle=Si(i.fillStyle,a),c.lineCap=Si(i.lineCap,r.borderCapStyle),c.lineDashOffset=Si(i.lineDashOffset,r.borderDashOffset),c.lineJoin=Si(i.lineJoin,r.borderJoinStyle),c.lineWidth=o,c.strokeStyle=Si(i.strokeStyle,a),c.setLineDash&&c.setLineDash(Si(i.lineDash,r.borderDash)),n&&n.usePointStyle){var s=m*Math.SQRT2/2,l=h.xPlus(t,m/2),u=e+p/2;V.canvas.drawPoint(c,i.pointStyle,s,l,u,i.rotation)}else c.fillRect(h.leftForLtr(t,m),e,m,p),0!==o&&c.strokeRect(h.leftForLtr(t,m),e,m,p);c.restore()}}(w,k,e),v[i].left=h.leftForLtr(w,v[i].width),v[i].top=k,function(t,e,n,i){var a=p/2,r=h.xPlus(t,m+a),o=e+a;c.fillText(n.text,r,o),n.hidden&&(c.beginPath(),c.lineWidth=2,c.moveTo(r,o),c.lineTo(h.xPlus(r,i),o),c.stroke())}(w,k,e,f),x?d.x+=g+n.padding:d.y+=y})),V.rtl.restoreTextDirection(t.ctx,e.textDirection)}},_getLegendItemAt:function(t,e){var n,i,a,r=this;if(t>=r.left&&t<=r.right&&e>=r.top&&e<=r.bottom)for(a=r.legendHitBoxes,n=0;n=(i=a[n]).left&&t<=i.left+i.width&&e>=i.top&&e<=i.top+i.height)return r.legendItems[n];return null},handleEvent:function(t){var e,n=this,i=n.options,a="mouseup"===t.type?"click":t.type;if("mousemove"===a){if(!i.onHover&&!i.onLeave)return}else{if("click"!==a)return;if(!i.onClick)return}e=n._getLegendItemAt(t.x,t.y),"click"===a?e&&i.onClick&&i.onClick.call(n,t.native,e):(i.onLeave&&e!==n._hoveredItem&&(n._hoveredItem&&i.onLeave.call(n,t.native,n._hoveredItem),n._hoveredItem=e),i.onHover&&e&&i.onHover.call(n,t.native,e))}});function Ai(t,e){var n=new Pi({ctx:t.ctx,options:e,chart:t});ge.configure(t,n,e),ge.addBox(t,n),t.legend=n}var Di={id:"legend",_element:Pi,beforeInit:function(t){var e=t.options.legend;e&&Ai(t,e)},beforeUpdate:function(t){var e=t.options.legend,n=t.legend;e?(V.mergeIf(e,z.global.legend),n?(ge.configure(t,n,e),n.options=e):Ai(t,e)):n&&(ge.removeBox(t,n),delete t.legend)},afterEvent:function(t,e){var n=t.legend;n&&n.handleEvent(e)}},Ti=V.noop;z._set("global",{title:{display:!1,fontStyle:"bold",fullWidth:!0,padding:10,position:"top",text:"",weight:2e3}});var Ii=X.extend({initialize:function(t){V.extend(this,t),this.legendHitBoxes=[]},beforeUpdate:Ti,update:function(t,e,n){var i=this;return i.beforeUpdate(),i.maxWidth=t,i.maxHeight=e,i.margins=n,i.beforeSetDimensions(),i.setDimensions(),i.afterSetDimensions(),i.beforeBuildLabels(),i.buildLabels(),i.afterBuildLabels(),i.beforeFit(),i.fit(),i.afterFit(),i.afterUpdate(),i.minSize},afterUpdate:Ti,beforeSetDimensions:Ti,setDimensions:function(){var t=this;t.isHorizontal()?(t.width=t.maxWidth,t.left=0,t.right=t.width):(t.height=t.maxHeight,t.top=0,t.bottom=t.height),t.paddingLeft=0,t.paddingTop=0,t.paddingRight=0,t.paddingBottom=0,t.minSize={width:0,height:0}},afterSetDimensions:Ti,beforeBuildLabels:Ti,buildLabels:Ti,afterBuildLabels:Ti,beforeFit:Ti,fit:function(){var t,e=this,n=e.options,i=e.minSize={},a=e.isHorizontal();n.display?(t=(V.isArray(n.text)?n.text.length:1)*V.options._parseFont(n).lineHeight+2*n.padding,e.width=i.width=a?e.maxWidth:t,e.height=i.height=a?t:e.maxHeight):e.width=i.width=e.height=i.height=0},afterFit:Ti,isHorizontal:function(){var t=this.options.position;return"top"===t||"bottom"===t},draw:function(){var t=this,e=t.ctx,n=t.options;if(n.display){var i,a,r,o=V.options._parseFont(n),s=o.lineHeight,l=s/2+n.padding,u=0,d=t.top,h=t.left,c=t.bottom,f=t.right;e.fillStyle=V.valueOrDefault(n.fontColor,z.global.defaultFontColor),e.font=o.string,t.isHorizontal()?(a=h+(f-h)/2,r=d+l,i=f-h):(a="left"===n.position?h+l:f-l,r=d+(c-d)/2,i=c-d,u=Math.PI*("left"===n.position?-.5:.5)),e.save(),e.translate(a,r),e.rotate(u),e.textAlign="center",e.textBaseline="middle";var g=n.text;if(V.isArray(g))for(var p=0,m=0;m=0;i--){var a=t[i];if(e(a))return a}},V.isNumber=function(t){return!isNaN(parseFloat(t))&&isFinite(t)},V.almostEquals=function(t,e,n){return Math.abs(t-e)=t},V.max=function(t){return t.reduce((function(t,e){return isNaN(e)?t:Math.max(t,e)}),Number.NEGATIVE_INFINITY)},V.min=function(t){return t.reduce((function(t,e){return isNaN(e)?t:Math.min(t,e)}),Number.POSITIVE_INFINITY)},V.sign=Math.sign?function(t){return Math.sign(t)}:function(t){return 0===(t=+t)||isNaN(t)?t:t>0?1:-1},V.toRadians=function(t){return t*(Math.PI/180)},V.toDegrees=function(t){return t*(180/Math.PI)},V._decimalPlaces=function(t){if(V.isFinite(t)){for(var e=1,n=0;Math.round(t*e)/e!==t;)e*=10,n++;return n}},V.getAngleFromPoint=function(t,e){var n=e.x-t.x,i=e.y-t.y,a=Math.sqrt(n*n+i*i),r=Math.atan2(i,n);return r<-.5*Math.PI&&(r+=2*Math.PI),{angle:r,distance:a}},V.distanceBetweenPoints=function(t,e){return Math.sqrt(Math.pow(e.x-t.x,2)+Math.pow(e.y-t.y,2))},V.aliasPixel=function(t){return t%2==0?0:.5},V._alignPixel=function(t,e,n){var i=t.currentDevicePixelRatio,a=n/2;return Math.round((e-a)*i)/i+a},V.splineCurve=function(t,e,n,i){var a=t.skip?e:t,r=e,o=n.skip?e:n,s=Math.sqrt(Math.pow(r.x-a.x,2)+Math.pow(r.y-a.y,2)),l=Math.sqrt(Math.pow(o.x-r.x,2)+Math.pow(o.y-r.y,2)),u=s/(s+l),d=l/(s+l),h=i*(u=isNaN(u)?0:u),c=i*(d=isNaN(d)?0:d);return{previous:{x:r.x-h*(o.x-a.x),y:r.y-h*(o.y-a.y)},next:{x:r.x+c*(o.x-a.x),y:r.y+c*(o.y-a.y)}}},V.EPSILON=Number.EPSILON||1e-14,V.splineCurveMonotone=function(t){var e,n,i,a,r,o,s,l,u,d=(t||[]).map((function(t){return{model:t._model,deltaK:0,mK:0}})),h=d.length;for(e=0;e0?d[e-1]:null,(a=e0?d[e-1]:null,a=e=t.length-1?t[0]:t[e+1]:e>=t.length-1?t[t.length-1]:t[e+1]},V.previousItem=function(t,e,n){return n?e<=0?t[t.length-1]:t[e-1]:e<=0?t[0]:t[e-1]},V.niceNum=function(t,e){var n=Math.floor(V.log10(t)),i=t/Math.pow(10,n);return(e?i<1.5?1:i<3?2:i<7?5:10:i<=1?1:i<=2?2:i<=5?5:10)*Math.pow(10,n)},V.requestAnimFrame="undefined"==typeof window?function(t){t()}:window.requestAnimationFrame||window.webkitRequestAnimationFrame||window.mozRequestAnimationFrame||window.oRequestAnimationFrame||window.msRequestAnimationFrame||function(t){return window.setTimeout(t,1e3/60)},V.getRelativePosition=function(t,e){var n,i,a=t.originalEvent||t,r=t.target||t.srcElement,o=r.getBoundingClientRect(),s=a.touches;s&&s.length>0?(n=s[0].clientX,i=s[0].clientY):(n=a.clientX,i=a.clientY);var l=parseFloat(V.getStyle(r,"padding-left")),u=parseFloat(V.getStyle(r,"padding-top")),d=parseFloat(V.getStyle(r,"padding-right")),h=parseFloat(V.getStyle(r,"padding-bottom")),c=o.right-o.left-l-d,f=o.bottom-o.top-u-h;return{x:n=Math.round((n-o.left-l)/c*r.width/e.currentDevicePixelRatio),y:i=Math.round((i-o.top-u)/f*r.height/e.currentDevicePixelRatio)}},V.getConstraintWidth=function(t){return n(t,"max-width","clientWidth")},V.getConstraintHeight=function(t){return n(t,"max-height","clientHeight")},V._calculatePadding=function(t,e,n){return(e=V.getStyle(t,e)).indexOf("%")>-1?n*parseInt(e,10)/100:parseInt(e,10)},V._getParentNode=function(t){var e=t.parentNode;return e&&"[object ShadowRoot]"===e.toString()&&(e=e.host),e},V.getMaximumWidth=function(t){var e=V._getParentNode(t);if(!e)return t.clientWidth;var n=e.clientWidth,i=n-V._calculatePadding(e,"padding-left",n)-V._calculatePadding(e,"padding-right",n),a=V.getConstraintWidth(t);return isNaN(a)?i:Math.min(i,a)},V.getMaximumHeight=function(t){var e=V._getParentNode(t);if(!e)return t.clientHeight;var n=e.clientHeight,i=n-V._calculatePadding(e,"padding-top",n)-V._calculatePadding(e,"padding-bottom",n),a=V.getConstraintHeight(t);return isNaN(a)?i:Math.min(i,a)},V.getStyle=function(t,e){return t.currentStyle?t.currentStyle[e]:document.defaultView.getComputedStyle(t,null).getPropertyValue(e)},V.retinaScale=function(t,e){var n=t.currentDevicePixelRatio=e||"undefined"!=typeof window&&window.devicePixelRatio||1;if(1!==n){var i=t.canvas,a=t.height,r=t.width;i.height=a*n,i.width=r*n,t.ctx.scale(n,n),i.style.height||i.style.width||(i.style.height=a+"px",i.style.width=r+"px")}},V.fontString=function(t,e,n){return e+" "+t+"px "+n},V.longestText=function(t,e,n,i){var a=(i=i||{}).data=i.data||{},r=i.garbageCollect=i.garbageCollect||[];i.font!==e&&(a=i.data={},r=i.garbageCollect=[],i.font=e),t.font=e;var o,s,l,u,d,h=0,c=n.length;for(o=0;on.length){for(o=0;oi&&(i=r),i},V.numberOfLabelLines=function(t){var e=1;return V.each(t,(function(t){V.isArray(t)&&t.length>e&&(e=t.length)})),e},V.color=k?function(t){return t instanceof CanvasGradient&&(t=z.global.defaultColor),k(t)}:function(t){return console.error("Color.js not found!"),t},V.getHoverColor=function(t){return t instanceof CanvasPattern||t instanceof CanvasGradient?t:V.color(t).saturate(.5).darken(.1).rgbString()}}(),tn._adapters=an,tn.Animation=Z,tn.animationService=$,tn.controllers=$t,tn.DatasetController=nt,tn.defaults=z,tn.Element=X,tn.elements=_t,tn.Interaction=ae,tn.layouts=ge,tn.platform=Fe,tn.plugins=Le,tn.Scale=xn,tn.scaleService=Oe,tn.Ticks=rn,tn.Tooltip=Ue,tn.helpers.each(ci,(function(t,e){tn.scaleService.registerScaleType(e,t,t._defaults)})),Li)Li.hasOwnProperty(Ni)&&tn.plugins.register(Li[Ni]);tn.platform.initialize();var Bi=tn;return"undefined"!=typeof window&&(window.Chart=tn),tn.Chart=tn,tn.Legend=Li.legend._element,tn.Title=Li.title._element,tn.pluginService=tn.plugins,tn.PluginBase=tn.Element.extend({}),tn.canvasHelpers=tn.helpers.canvas,tn.layoutService=tn.layouts,tn.LinearScaleBase=Sn,tn.helpers.each(["Bar","Bubble","Doughnut","Line","PolarArea","Radar","Scatter"],(function(t){tn[t]=function(e,n){return new tn(e,tn.helpers.merge(n||{},{type:t.charAt(0).toLowerCase()+t.slice(1)}))}})),Bi})); +!function(t,e){"object"==typeof exports&&"undefined"!=typeof module?module.exports=e(function(){try{return require("moment")}catch(t){}}()):"function"==typeof define&&define.amd?define(["require"],(function(t){return e(function(){try{return t("moment")}catch(t){}}())})):(t=t||self).Chart=e(t.moment)}(this,(function(t){"use strict";t=t&&t.hasOwnProperty("default")?t.default:t;var e={aliceblue:[240,248,255],antiquewhite:[250,235,215],aqua:[0,255,255],aquamarine:[127,255,212],azure:[240,255,255],beige:[245,245,220],bisque:[255,228,196],black:[0,0,0],blanchedalmond:[255,235,205],blue:[0,0,255],blueviolet:[138,43,226],brown:[165,42,42],burlywood:[222,184,135],cadetblue:[95,158,160],chartreuse:[127,255,0],chocolate:[210,105,30],coral:[255,127,80],cornflowerblue:[100,149,237],cornsilk:[255,248,220],crimson:[220,20,60],cyan:[0,255,255],darkblue:[0,0,139],darkcyan:[0,139,139],darkgoldenrod:[184,134,11],darkgray:[169,169,169],darkgreen:[0,100,0],darkgrey:[169,169,169],darkkhaki:[189,183,107],darkmagenta:[139,0,139],darkolivegreen:[85,107,47],darkorange:[255,140,0],darkorchid:[153,50,204],darkred:[139,0,0],darksalmon:[233,150,122],darkseagreen:[143,188,143],darkslateblue:[72,61,139],darkslategray:[47,79,79],darkslategrey:[47,79,79],darkturquoise:[0,206,209],darkviolet:[148,0,211],deeppink:[255,20,147],deepskyblue:[0,191,255],dimgray:[105,105,105],dimgrey:[105,105,105],dodgerblue:[30,144,255],firebrick:[178,34,34],floralwhite:[255,250,240],forestgreen:[34,139,34],fuchsia:[255,0,255],gainsboro:[220,220,220],ghostwhite:[248,248,255],gold:[255,215,0],goldenrod:[218,165,32],gray:[128,128,128],green:[0,128,0],greenyellow:[173,255,47],grey:[128,128,128],honeydew:[240,255,240],hotpink:[255,105,180],indianred:[205,92,92],indigo:[75,0,130],ivory:[255,255,240],khaki:[240,230,140],lavender:[230,230,250],lavenderblush:[255,240,245],lawngreen:[124,252,0],lemonchiffon:[255,250,205],lightblue:[173,216,230],lightcoral:[240,128,128],lightcyan:[224,255,255],lightgoldenrodyellow:[250,250,210],lightgray:[211,211,211],lightgreen:[144,238,144],lightgrey:[211,211,211],lightpink:[255,182,193],lightsalmon:[255,160,122],lightseagreen:[32,178,170],lightskyblue:[135,206,250],lightslategray:[119,136,153],lightslategrey:[119,136,153],lightsteelblue:[176,196,222],lightyellow:[255,255,224],lime:[0,255,0],limegreen:[50,205,50],linen:[250,240,230],magenta:[255,0,255],maroon:[128,0,0],mediumaquamarine:[102,205,170],mediumblue:[0,0,205],mediumorchid:[186,85,211],mediumpurple:[147,112,219],mediumseagreen:[60,179,113],mediumslateblue:[123,104,238],mediumspringgreen:[0,250,154],mediumturquoise:[72,209,204],mediumvioletred:[199,21,133],midnightblue:[25,25,112],mintcream:[245,255,250],mistyrose:[255,228,225],moccasin:[255,228,181],navajowhite:[255,222,173],navy:[0,0,128],oldlace:[253,245,230],olive:[128,128,0],olivedrab:[107,142,35],orange:[255,165,0],orangered:[255,69,0],orchid:[218,112,214],palegoldenrod:[238,232,170],palegreen:[152,251,152],paleturquoise:[175,238,238],palevioletred:[219,112,147],papayawhip:[255,239,213],peachpuff:[255,218,185],peru:[205,133,63],pink:[255,192,203],plum:[221,160,221],powderblue:[176,224,230],purple:[128,0,128],rebeccapurple:[102,51,153],red:[255,0,0],rosybrown:[188,143,143],royalblue:[65,105,225],saddlebrown:[139,69,19],salmon:[250,128,114],sandybrown:[244,164,96],seagreen:[46,139,87],seashell:[255,245,238],sienna:[160,82,45],silver:[192,192,192],skyblue:[135,206,235],slateblue:[106,90,205],slategray:[112,128,144],slategrey:[112,128,144],snow:[255,250,250],springgreen:[0,255,127],steelblue:[70,130,180],tan:[210,180,140],teal:[0,128,128],thistle:[216,191,216],tomato:[255,99,71],turquoise:[64,224,208],violet:[238,130,238],wheat:[245,222,179],white:[255,255,255],whitesmoke:[245,245,245],yellow:[255,255,0],yellowgreen:[154,205,50]},n=function(t,e){return t(e={exports:{}},e.exports),e.exports}((function(t){var n={};for(var i in e)e.hasOwnProperty(i)&&(n[e[i]]=i);var a=t.exports={rgb:{channels:3,labels:"rgb"},hsl:{channels:3,labels:"hsl"},hsv:{channels:3,labels:"hsv"},hwb:{channels:3,labels:"hwb"},cmyk:{channels:4,labels:"cmyk"},xyz:{channels:3,labels:"xyz"},lab:{channels:3,labels:"lab"},lch:{channels:3,labels:"lch"},hex:{channels:1,labels:["hex"]},keyword:{channels:1,labels:["keyword"]},ansi16:{channels:1,labels:["ansi16"]},ansi256:{channels:1,labels:["ansi256"]},hcg:{channels:3,labels:["h","c","g"]},apple:{channels:3,labels:["r16","g16","b16"]},gray:{channels:1,labels:["gray"]}};for(var r in a)if(a.hasOwnProperty(r)){if(!("channels"in a[r]))throw new Error("missing channels property: "+r);if(!("labels"in a[r]))throw new Error("missing channel labels property: "+r);if(a[r].labels.length!==a[r].channels)throw new Error("channel and label counts mismatch: "+r);var o=a[r].channels,s=a[r].labels;delete a[r].channels,delete a[r].labels,Object.defineProperty(a[r],"channels",{value:o}),Object.defineProperty(a[r],"labels",{value:s})}a.rgb.hsl=function(t){var e,n,i=t[0]/255,a=t[1]/255,r=t[2]/255,o=Math.min(i,a,r),s=Math.max(i,a,r),l=s-o;return s===o?e=0:i===s?e=(a-r)/l:a===s?e=2+(r-i)/l:r===s&&(e=4+(i-a)/l),(e=Math.min(60*e,360))<0&&(e+=360),n=(o+s)/2,[e,100*(s===o?0:n<=.5?l/(s+o):l/(2-s-o)),100*n]},a.rgb.hsv=function(t){var e,n,i,a,r,o=t[0]/255,s=t[1]/255,l=t[2]/255,u=Math.max(o,s,l),d=u-Math.min(o,s,l),h=function(t){return(u-t)/6/d+.5};return 0===d?a=r=0:(r=d/u,e=h(o),n=h(s),i=h(l),o===u?a=i-n:s===u?a=1/3+e-i:l===u&&(a=2/3+n-e),a<0?a+=1:a>1&&(a-=1)),[360*a,100*r,100*u]},a.rgb.hwb=function(t){var e=t[0],n=t[1],i=t[2];return[a.rgb.hsl(t)[0],100*(1/255*Math.min(e,Math.min(n,i))),100*(i=1-1/255*Math.max(e,Math.max(n,i)))]},a.rgb.cmyk=function(t){var e,n=t[0]/255,i=t[1]/255,a=t[2]/255;return[100*((1-n-(e=Math.min(1-n,1-i,1-a)))/(1-e)||0),100*((1-i-e)/(1-e)||0),100*((1-a-e)/(1-e)||0),100*e]},a.rgb.keyword=function(t){var i=n[t];if(i)return i;var a,r,o,s=1/0;for(var l in e)if(e.hasOwnProperty(l)){var u=e[l],d=(r=t,o=u,Math.pow(r[0]-o[0],2)+Math.pow(r[1]-o[1],2)+Math.pow(r[2]-o[2],2));d.04045?Math.pow((e+.055)/1.055,2.4):e/12.92)+.3576*(n=n>.04045?Math.pow((n+.055)/1.055,2.4):n/12.92)+.1805*(i=i>.04045?Math.pow((i+.055)/1.055,2.4):i/12.92)),100*(.2126*e+.7152*n+.0722*i),100*(.0193*e+.1192*n+.9505*i)]},a.rgb.lab=function(t){var e=a.rgb.xyz(t),n=e[0],i=e[1],r=e[2];return i/=100,r/=108.883,n=(n/=95.047)>.008856?Math.pow(n,1/3):7.787*n+16/116,[116*(i=i>.008856?Math.pow(i,1/3):7.787*i+16/116)-16,500*(n-i),200*(i-(r=r>.008856?Math.pow(r,1/3):7.787*r+16/116))]},a.hsl.rgb=function(t){var e,n,i,a,r,o=t[0]/360,s=t[1]/100,l=t[2]/100;if(0===s)return[r=255*l,r,r];e=2*l-(n=l<.5?l*(1+s):l+s-l*s),a=[0,0,0];for(var u=0;u<3;u++)(i=o+1/3*-(u-1))<0&&i++,i>1&&i--,r=6*i<1?e+6*(n-e)*i:2*i<1?n:3*i<2?e+(n-e)*(2/3-i)*6:e,a[u]=255*r;return a},a.hsl.hsv=function(t){var e=t[0],n=t[1]/100,i=t[2]/100,a=n,r=Math.max(i,.01);return n*=(i*=2)<=1?i:2-i,a*=r<=1?r:2-r,[e,100*(0===i?2*a/(r+a):2*n/(i+n)),100*((i+n)/2)]},a.hsv.rgb=function(t){var e=t[0]/60,n=t[1]/100,i=t[2]/100,a=Math.floor(e)%6,r=e-Math.floor(e),o=255*i*(1-n),s=255*i*(1-n*r),l=255*i*(1-n*(1-r));switch(i*=255,a){case 0:return[i,l,o];case 1:return[s,i,o];case 2:return[o,i,l];case 3:return[o,s,i];case 4:return[l,o,i];case 5:return[i,o,s]}},a.hsv.hsl=function(t){var e,n,i,a=t[0],r=t[1]/100,o=t[2]/100,s=Math.max(o,.01);return i=(2-r)*o,n=r*s,[a,100*(n=(n/=(e=(2-r)*s)<=1?e:2-e)||0),100*(i/=2)]},a.hwb.rgb=function(t){var e,n,i,a,r,o,s,l=t[0]/360,u=t[1]/100,d=t[2]/100,h=u+d;switch(h>1&&(u/=h,d/=h),i=6*l-(e=Math.floor(6*l)),0!=(1&e)&&(i=1-i),a=u+i*((n=1-d)-u),e){default:case 6:case 0:r=n,o=a,s=u;break;case 1:r=a,o=n,s=u;break;case 2:r=u,o=n,s=a;break;case 3:r=u,o=a,s=n;break;case 4:r=a,o=u,s=n;break;case 5:r=n,o=u,s=a}return[255*r,255*o,255*s]},a.cmyk.rgb=function(t){var e=t[0]/100,n=t[1]/100,i=t[2]/100,a=t[3]/100;return[255*(1-Math.min(1,e*(1-a)+a)),255*(1-Math.min(1,n*(1-a)+a)),255*(1-Math.min(1,i*(1-a)+a))]},a.xyz.rgb=function(t){var e,n,i,a=t[0]/100,r=t[1]/100,o=t[2]/100;return n=-.9689*a+1.8758*r+.0415*o,i=.0557*a+-.204*r+1.057*o,e=(e=3.2406*a+-1.5372*r+-.4986*o)>.0031308?1.055*Math.pow(e,1/2.4)-.055:12.92*e,n=n>.0031308?1.055*Math.pow(n,1/2.4)-.055:12.92*n,i=i>.0031308?1.055*Math.pow(i,1/2.4)-.055:12.92*i,[255*(e=Math.min(Math.max(0,e),1)),255*(n=Math.min(Math.max(0,n),1)),255*(i=Math.min(Math.max(0,i),1))]},a.xyz.lab=function(t){var e=t[0],n=t[1],i=t[2];return n/=100,i/=108.883,e=(e/=95.047)>.008856?Math.pow(e,1/3):7.787*e+16/116,[116*(n=n>.008856?Math.pow(n,1/3):7.787*n+16/116)-16,500*(e-n),200*(n-(i=i>.008856?Math.pow(i,1/3):7.787*i+16/116))]},a.lab.xyz=function(t){var e,n,i,a=t[0];e=t[1]/500+(n=(a+16)/116),i=n-t[2]/200;var r=Math.pow(n,3),o=Math.pow(e,3),s=Math.pow(i,3);return n=r>.008856?r:(n-16/116)/7.787,e=o>.008856?o:(e-16/116)/7.787,i=s>.008856?s:(i-16/116)/7.787,[e*=95.047,n*=100,i*=108.883]},a.lab.lch=function(t){var e,n=t[0],i=t[1],a=t[2];return(e=360*Math.atan2(a,i)/2/Math.PI)<0&&(e+=360),[n,Math.sqrt(i*i+a*a),e]},a.lch.lab=function(t){var e,n=t[0],i=t[1];return e=t[2]/360*2*Math.PI,[n,i*Math.cos(e),i*Math.sin(e)]},a.rgb.ansi16=function(t){var e=t[0],n=t[1],i=t[2],r=1 in arguments?arguments[1]:a.rgb.hsv(t)[2];if(0===(r=Math.round(r/50)))return 30;var o=30+(Math.round(i/255)<<2|Math.round(n/255)<<1|Math.round(e/255));return 2===r&&(o+=60),o},a.hsv.ansi16=function(t){return a.rgb.ansi16(a.hsv.rgb(t),t[2])},a.rgb.ansi256=function(t){var e=t[0],n=t[1],i=t[2];return e===n&&n===i?e<8?16:e>248?231:Math.round((e-8)/247*24)+232:16+36*Math.round(e/255*5)+6*Math.round(n/255*5)+Math.round(i/255*5)},a.ansi16.rgb=function(t){var e=t%10;if(0===e||7===e)return t>50&&(e+=3.5),[e=e/10.5*255,e,e];var n=.5*(1+~~(t>50));return[(1&e)*n*255,(e>>1&1)*n*255,(e>>2&1)*n*255]},a.ansi256.rgb=function(t){if(t>=232){var e=10*(t-232)+8;return[e,e,e]}var n;return t-=16,[Math.floor(t/36)/5*255,Math.floor((n=t%36)/6)/5*255,n%6/5*255]},a.rgb.hex=function(t){var e=(((255&Math.round(t[0]))<<16)+((255&Math.round(t[1]))<<8)+(255&Math.round(t[2]))).toString(16).toUpperCase();return"000000".substring(e.length)+e},a.hex.rgb=function(t){var e=t.toString(16).match(/[a-f0-9]{6}|[a-f0-9]{3}/i);if(!e)return[0,0,0];var n=e[0];3===e[0].length&&(n=n.split("").map((function(t){return t+t})).join(""));var i=parseInt(n,16);return[i>>16&255,i>>8&255,255&i]},a.rgb.hcg=function(t){var e,n=t[0]/255,i=t[1]/255,a=t[2]/255,r=Math.max(Math.max(n,i),a),o=Math.min(Math.min(n,i),a),s=r-o;return e=s<=0?0:r===n?(i-a)/s%6:r===i?2+(a-n)/s:4+(n-i)/s+4,e/=6,[360*(e%=1),100*s,100*(s<1?o/(1-s):0)]},a.hsl.hcg=function(t){var e=t[1]/100,n=t[2]/100,i=1,a=0;return(i=n<.5?2*e*n:2*e*(1-n))<1&&(a=(n-.5*i)/(1-i)),[t[0],100*i,100*a]},a.hsv.hcg=function(t){var e=t[1]/100,n=t[2]/100,i=e*n,a=0;return i<1&&(a=(n-i)/(1-i)),[t[0],100*i,100*a]},a.hcg.rgb=function(t){var e=t[0]/360,n=t[1]/100,i=t[2]/100;if(0===n)return[255*i,255*i,255*i];var a,r=[0,0,0],o=e%1*6,s=o%1,l=1-s;switch(Math.floor(o)){case 0:r[0]=1,r[1]=s,r[2]=0;break;case 1:r[0]=l,r[1]=1,r[2]=0;break;case 2:r[0]=0,r[1]=1,r[2]=s;break;case 3:r[0]=0,r[1]=l,r[2]=1;break;case 4:r[0]=s,r[1]=0,r[2]=1;break;default:r[0]=1,r[1]=0,r[2]=l}return a=(1-n)*i,[255*(n*r[0]+a),255*(n*r[1]+a),255*(n*r[2]+a)]},a.hcg.hsv=function(t){var e=t[1]/100,n=e+t[2]/100*(1-e),i=0;return n>0&&(i=e/n),[t[0],100*i,100*n]},a.hcg.hsl=function(t){var e=t[1]/100,n=t[2]/100*(1-e)+.5*e,i=0;return n>0&&n<.5?i=e/(2*n):n>=.5&&n<1&&(i=e/(2*(1-n))),[t[0],100*i,100*n]},a.hcg.hwb=function(t){var e=t[1]/100,n=e+t[2]/100*(1-e);return[t[0],100*(n-e),100*(1-n)]},a.hwb.hcg=function(t){var e=t[1]/100,n=1-t[2]/100,i=n-e,a=0;return i<1&&(a=(n-i)/(1-i)),[t[0],100*i,100*a]},a.apple.rgb=function(t){return[t[0]/65535*255,t[1]/65535*255,t[2]/65535*255]},a.rgb.apple=function(t){return[t[0]/255*65535,t[1]/255*65535,t[2]/255*65535]},a.gray.rgb=function(t){return[t[0]/100*255,t[0]/100*255,t[0]/100*255]},a.gray.hsl=a.gray.hsv=function(t){return[0,0,t[0]]},a.gray.hwb=function(t){return[0,100,t[0]]},a.gray.cmyk=function(t){return[0,0,0,t[0]]},a.gray.lab=function(t){return[t[0],0,0]},a.gray.hex=function(t){var e=255&Math.round(t[0]/100*255),n=((e<<16)+(e<<8)+e).toString(16).toUpperCase();return"000000".substring(n.length)+n},a.rgb.gray=function(t){return[(t[0]+t[1]+t[2])/3/255*100]}}));n.rgb,n.hsl,n.hsv,n.hwb,n.cmyk,n.xyz,n.lab,n.lch,n.hex,n.keyword,n.ansi16,n.ansi256,n.hcg,n.apple,n.gray;function i(t){var e=function(){for(var t={},e=Object.keys(n),i=e.length,a=0;a1&&(e=Array.prototype.slice.call(arguments));var n=t(e);if("object"==typeof n)for(var i=n.length,a=0;a1&&(e=Array.prototype.slice.call(arguments)),t(e))};return"conversion"in t&&(e.conversion=t.conversion),e}(i)}))}));var s=o,l={aliceblue:[240,248,255],antiquewhite:[250,235,215],aqua:[0,255,255],aquamarine:[127,255,212],azure:[240,255,255],beige:[245,245,220],bisque:[255,228,196],black:[0,0,0],blanchedalmond:[255,235,205],blue:[0,0,255],blueviolet:[138,43,226],brown:[165,42,42],burlywood:[222,184,135],cadetblue:[95,158,160],chartreuse:[127,255,0],chocolate:[210,105,30],coral:[255,127,80],cornflowerblue:[100,149,237],cornsilk:[255,248,220],crimson:[220,20,60],cyan:[0,255,255],darkblue:[0,0,139],darkcyan:[0,139,139],darkgoldenrod:[184,134,11],darkgray:[169,169,169],darkgreen:[0,100,0],darkgrey:[169,169,169],darkkhaki:[189,183,107],darkmagenta:[139,0,139],darkolivegreen:[85,107,47],darkorange:[255,140,0],darkorchid:[153,50,204],darkred:[139,0,0],darksalmon:[233,150,122],darkseagreen:[143,188,143],darkslateblue:[72,61,139],darkslategray:[47,79,79],darkslategrey:[47,79,79],darkturquoise:[0,206,209],darkviolet:[148,0,211],deeppink:[255,20,147],deepskyblue:[0,191,255],dimgray:[105,105,105],dimgrey:[105,105,105],dodgerblue:[30,144,255],firebrick:[178,34,34],floralwhite:[255,250,240],forestgreen:[34,139,34],fuchsia:[255,0,255],gainsboro:[220,220,220],ghostwhite:[248,248,255],gold:[255,215,0],goldenrod:[218,165,32],gray:[128,128,128],green:[0,128,0],greenyellow:[173,255,47],grey:[128,128,128],honeydew:[240,255,240],hotpink:[255,105,180],indianred:[205,92,92],indigo:[75,0,130],ivory:[255,255,240],khaki:[240,230,140],lavender:[230,230,250],lavenderblush:[255,240,245],lawngreen:[124,252,0],lemonchiffon:[255,250,205],lightblue:[173,216,230],lightcoral:[240,128,128],lightcyan:[224,255,255],lightgoldenrodyellow:[250,250,210],lightgray:[211,211,211],lightgreen:[144,238,144],lightgrey:[211,211,211],lightpink:[255,182,193],lightsalmon:[255,160,122],lightseagreen:[32,178,170],lightskyblue:[135,206,250],lightslategray:[119,136,153],lightslategrey:[119,136,153],lightsteelblue:[176,196,222],lightyellow:[255,255,224],lime:[0,255,0],limegreen:[50,205,50],linen:[250,240,230],magenta:[255,0,255],maroon:[128,0,0],mediumaquamarine:[102,205,170],mediumblue:[0,0,205],mediumorchid:[186,85,211],mediumpurple:[147,112,219],mediumseagreen:[60,179,113],mediumslateblue:[123,104,238],mediumspringgreen:[0,250,154],mediumturquoise:[72,209,204],mediumvioletred:[199,21,133],midnightblue:[25,25,112],mintcream:[245,255,250],mistyrose:[255,228,225],moccasin:[255,228,181],navajowhite:[255,222,173],navy:[0,0,128],oldlace:[253,245,230],olive:[128,128,0],olivedrab:[107,142,35],orange:[255,165,0],orangered:[255,69,0],orchid:[218,112,214],palegoldenrod:[238,232,170],palegreen:[152,251,152],paleturquoise:[175,238,238],palevioletred:[219,112,147],papayawhip:[255,239,213],peachpuff:[255,218,185],peru:[205,133,63],pink:[255,192,203],plum:[221,160,221],powderblue:[176,224,230],purple:[128,0,128],rebeccapurple:[102,51,153],red:[255,0,0],rosybrown:[188,143,143],royalblue:[65,105,225],saddlebrown:[139,69,19],salmon:[250,128,114],sandybrown:[244,164,96],seagreen:[46,139,87],seashell:[255,245,238],sienna:[160,82,45],silver:[192,192,192],skyblue:[135,206,235],slateblue:[106,90,205],slategray:[112,128,144],slategrey:[112,128,144],snow:[255,250,250],springgreen:[0,255,127],steelblue:[70,130,180],tan:[210,180,140],teal:[0,128,128],thistle:[216,191,216],tomato:[255,99,71],turquoise:[64,224,208],violet:[238,130,238],wheat:[245,222,179],white:[255,255,255],whitesmoke:[245,245,245],yellow:[255,255,0],yellowgreen:[154,205,50]},u={getRgba:d,getHsla:h,getRgb:function(t){var e=d(t);return e&&e.slice(0,3)},getHsl:function(t){var e=h(t);return e&&e.slice(0,3)},getHwb:c,getAlpha:function(t){var e=d(t);if(e)return e[3];if(e=h(t))return e[3];if(e=c(t))return e[3]},hexString:function(t,e){e=void 0!==e&&3===t.length?e:t[3];return"#"+v(t[0])+v(t[1])+v(t[2])+(e>=0&&e<1?v(Math.round(255*e)):"")},rgbString:function(t,e){if(e<1||t[3]&&t[3]<1)return f(t,e);return"rgb("+t[0]+", "+t[1]+", "+t[2]+")"},rgbaString:f,percentString:function(t,e){if(e<1||t[3]&&t[3]<1)return g(t,e);var n=Math.round(t[0]/255*100),i=Math.round(t[1]/255*100),a=Math.round(t[2]/255*100);return"rgb("+n+"%, "+i+"%, "+a+"%)"},percentaString:g,hslString:function(t,e){if(e<1||t[3]&&t[3]<1)return p(t,e);return"hsl("+t[0]+", "+t[1]+"%, "+t[2]+"%)"},hslaString:p,hwbString:function(t,e){void 0===e&&(e=void 0!==t[3]?t[3]:1);return"hwb("+t[0]+", "+t[1]+"%, "+t[2]+"%"+(void 0!==e&&1!==e?", "+e:"")+")"},keyword:function(t){return b[t.slice(0,3)]}};function d(t){if(t){var e=[0,0,0],n=1,i=t.match(/^#([a-fA-F0-9]{3,4})$/i),a="";if(i){a=(i=i[1])[3];for(var r=0;rn?(e+.05)/(n+.05):(n+.05)/(e+.05)},level:function(t){var e=this.contrast(t);return e>=7.1?"AAA":e>=4.5?"AA":""},dark:function(){var t=this.values.rgb;return(299*t[0]+587*t[1]+114*t[2])/1e3<128},light:function(){return!this.dark()},negate:function(){for(var t=[],e=0;e<3;e++)t[e]=255-this.values.rgb[e];return this.setValues("rgb",t),this},lighten:function(t){var e=this.values.hsl;return e[2]+=e[2]*t,this.setValues("hsl",e),this},darken:function(t){var e=this.values.hsl;return e[2]-=e[2]*t,this.setValues("hsl",e),this},saturate:function(t){var e=this.values.hsl;return e[1]+=e[1]*t,this.setValues("hsl",e),this},desaturate:function(t){var e=this.values.hsl;return e[1]-=e[1]*t,this.setValues("hsl",e),this},whiten:function(t){var e=this.values.hwb;return e[1]+=e[1]*t,this.setValues("hwb",e),this},blacken:function(t){var e=this.values.hwb;return e[2]+=e[2]*t,this.setValues("hwb",e),this},greyscale:function(){var t=this.values.rgb,e=.3*t[0]+.59*t[1]+.11*t[2];return this.setValues("rgb",[e,e,e]),this},clearer:function(t){var e=this.values.alpha;return this.setValues("alpha",e-e*t),this},opaquer:function(t){var e=this.values.alpha;return this.setValues("alpha",e+e*t),this},rotate:function(t){var e=this.values.hsl,n=(e[0]+t)%360;return e[0]=n<0?360+n:n,this.setValues("hsl",e),this},mix:function(t,e){var n=t,i=void 0===e?.5:e,a=2*i-1,r=this.alpha()-n.alpha(),o=((a*r==-1?a:(a+r)/(1+a*r))+1)/2,s=1-o;return this.rgb(o*this.red()+s*n.red(),o*this.green()+s*n.green(),o*this.blue()+s*n.blue()).alpha(this.alpha()*i+n.alpha()*(1-i))},toJSON:function(){return this.rgb()},clone:function(){var t,e,n=new y,i=this.values,a=n.values;for(var r in i)i.hasOwnProperty(r)&&(t=i[r],"[object Array]"===(e={}.toString.call(t))?a[r]=t.slice(0):"[object Number]"===e?a[r]=t:console.error("unexpected color value:",t));return n}},y.prototype.spaces={rgb:["red","green","blue"],hsl:["hue","saturation","lightness"],hsv:["hue","saturation","value"],hwb:["hue","whiteness","blackness"],cmyk:["cyan","magenta","yellow","black"]},y.prototype.maxes={rgb:[255,255,255],hsl:[360,100,100],hsv:[360,100,100],hwb:[360,100,100],cmyk:[100,100,100,100]},y.prototype.getValues=function(t){for(var e=this.values,n={},i=0;i=0;a--)e.call(n,t[a],a);else for(a=0;a=1?t:-(Math.sqrt(1-t*t)-1)},easeOutCirc:function(t){return Math.sqrt(1-(t-=1)*t)},easeInOutCirc:function(t){return(t/=.5)<1?-.5*(Math.sqrt(1-t*t)-1):.5*(Math.sqrt(1-(t-=2)*t)+1)},easeInElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:1===t?1:(n||(n=.3),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),-i*Math.pow(2,10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n))},easeOutElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:1===t?1:(n||(n=.3),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),i*Math.pow(2,-10*t)*Math.sin((t-e)*(2*Math.PI)/n)+1)},easeInOutElastic:function(t){var e=1.70158,n=0,i=1;return 0===t?0:2==(t/=.5)?1:(n||(n=.45),i<1?(i=1,e=n/4):e=n/(2*Math.PI)*Math.asin(1/i),t<1?i*Math.pow(2,10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n)*-.5:i*Math.pow(2,-10*(t-=1))*Math.sin((t-e)*(2*Math.PI)/n)*.5+1)},easeInBack:function(t){var e=1.70158;return t*t*((e+1)*t-e)},easeOutBack:function(t){var e=1.70158;return(t-=1)*t*((e+1)*t+e)+1},easeInOutBack:function(t){var e=1.70158;return(t/=.5)<1?t*t*((1+(e*=1.525))*t-e)*.5:.5*((t-=2)*t*((1+(e*=1.525))*t+e)+2)},easeInBounce:function(t){return 1-C.easeOutBounce(1-t)},easeOutBounce:function(t){return t<1/2.75?7.5625*t*t:t<2/2.75?7.5625*(t-=1.5/2.75)*t+.75:t<2.5/2.75?7.5625*(t-=2.25/2.75)*t+.9375:7.5625*(t-=2.625/2.75)*t+.984375},easeInOutBounce:function(t){return t<.5?.5*C.easeInBounce(2*t):.5*C.easeOutBounce(2*t-1)+.5}},P={effects:C};S.easingEffects=C;var A=Math.PI,D=A/180,T=2*A,I=A/2,F=A/4,O=2*A/3,L={clear:function(t){t.ctx.clearRect(0,0,t.width,t.height)},roundedRect:function(t,e,n,i,a,r){if(r){var o=Math.min(r,a/2,i/2),s=e+o,l=n+o,u=e+i-o,d=n+a-o;t.moveTo(e,l),se.left-1e-6&&t.xe.top-1e-6&&t.y0&&this.requestAnimationFrame()},advance:function(){for(var t,e,n,i,a=this.animations,r=0;r=n?(H.callback(t.onAnimationComplete,[t],e),e.animating=!1,a.splice(r,1)):++r}},Q=H.options.resolve,tt=["push","pop","shift","splice","unshift"];function et(t,e){var n=t._chartjs;if(n){var i=n.listeners,a=i.indexOf(e);-1!==a&&i.splice(a,1),i.length>0||(tt.forEach((function(e){delete t[e]})),delete t._chartjs)}}var nt=function(t,e){this.initialize(t,e)};H.extend(nt.prototype,{datasetElementType:null,dataElementType:null,_datasetElementOptions:["backgroundColor","borderCapStyle","borderColor","borderDash","borderDashOffset","borderJoinStyle","borderWidth"],_dataElementOptions:["backgroundColor","borderColor","borderWidth","pointStyle"],initialize:function(t,e){var n=this;n.chart=t,n.index=e,n.linkScales(),n.addElements(),n._type=n.getMeta().type},updateIndex:function(t){this.index=t},linkScales:function(){var t=this.getMeta(),e=this.chart,n=e.scales,i=this.getDataset(),a=e.options.scales;null!==t.xAxisID&&t.xAxisID in n&&!i.xAxisID||(t.xAxisID=i.xAxisID||a.xAxes[0].id),null!==t.yAxisID&&t.yAxisID in n&&!i.yAxisID||(t.yAxisID=i.yAxisID||a.yAxes[0].id)},getDataset:function(){return this.chart.data.datasets[this.index]},getMeta:function(){return this.chart.getDatasetMeta(this.index)},getScaleForId:function(t){return this.chart.scales[t]},_getValueScaleId:function(){return this.getMeta().yAxisID},_getIndexScaleId:function(){return this.getMeta().xAxisID},_getValueScale:function(){return this.getScaleForId(this._getValueScaleId())},_getIndexScale:function(){return this.getScaleForId(this._getIndexScaleId())},reset:function(){this._update(!0)},destroy:function(){this._data&&et(this._data,this)},createMetaDataset:function(){var t=this.datasetElementType;return t&&new t({_chart:this.chart,_datasetIndex:this.index})},createMetaData:function(t){var e=this.dataElementType;return e&&new e({_chart:this.chart,_datasetIndex:this.index,_index:t})},addElements:function(){var t,e,n=this.getMeta(),i=this.getDataset().data||[],a=n.data;for(t=0,e=i.length;tn&&this.insertElements(n,i-n)},insertElements:function(t,e){for(var n=0;na?(r=a/e.innerRadius,t.arc(o,s,e.innerRadius-a,i+r,n-r,!0)):t.arc(o,s,a,i+Math.PI/2,n-Math.PI/2),t.closePath(),t.clip()}function ot(t,e,n){var i="inner"===e.borderAlign;i?(t.lineWidth=2*e.borderWidth,t.lineJoin="round"):(t.lineWidth=e.borderWidth,t.lineJoin="bevel"),n.fullCircles&&function(t,e,n,i){var a,r=n.endAngle;for(i&&(n.endAngle=n.startAngle+at,rt(t,n),n.endAngle=r,n.endAngle===n.startAngle&&n.fullCircles&&(n.endAngle+=at,n.fullCircles--)),t.beginPath(),t.arc(n.x,n.y,n.innerRadius,n.startAngle+at,n.startAngle,!0),a=0;as;)a-=at;for(;a=o&&a<=s,u=r>=n.innerRadius&&r<=n.outerRadius;return l&&u}return!1},getCenterPoint:function(){var t=this._view,e=(t.startAngle+t.endAngle)/2,n=(t.innerRadius+t.outerRadius)/2;return{x:t.x+Math.cos(e)*n,y:t.y+Math.sin(e)*n}},getArea:function(){var t=this._view;return Math.PI*((t.endAngle-t.startAngle)/(2*Math.PI))*(Math.pow(t.outerRadius,2)-Math.pow(t.innerRadius,2))},tooltipPosition:function(){var t=this._view,e=t.startAngle+(t.endAngle-t.startAngle)/2,n=(t.outerRadius-t.innerRadius)/2+t.innerRadius;return{x:t.x+Math.cos(e)*n,y:t.y+Math.sin(e)*n}},draw:function(){var t,e=this._chart.ctx,n=this._view,i="inner"===n.borderAlign?.33:0,a={x:n.x,y:n.y,innerRadius:n.innerRadius,outerRadius:Math.max(n.outerRadius-i,0),pixelMargin:i,startAngle:n.startAngle,endAngle:n.endAngle,fullCircles:Math.floor(n.circumference/at)};if(e.save(),e.fillStyle=n.backgroundColor,e.strokeStyle=n.borderColor,a.fullCircles){for(a.endAngle=a.startAngle+at,e.beginPath(),e.arc(a.x,a.y,a.outerRadius,a.startAngle,a.endAngle),e.arc(a.x,a.y,a.innerRadius,a.endAngle,a.startAngle,!0),e.closePath(),t=0;tt.x&&(e=bt(e,"left","right")):t.basen?n:i,r:l.right||a<0?0:a>e?e:a,b:l.bottom||r<0?0:r>n?n:r,l:l.left||o<0?0:o>e?e:o}}function yt(t,e,n){var i=null===e,a=null===n,r=!(!t||i&&a)&&vt(t);return r&&(i||e>=r.left&&e<=r.right)&&(a||n>=r.top&&n<=r.bottom)}N._set("global",{elements:{rectangle:{backgroundColor:pt,borderColor:pt,borderSkipped:"bottom",borderWidth:0}}});var _t=K.extend({_type:"rectangle",draw:function(){var t=this._chart.ctx,e=this._view,n=function(t){var e=vt(t),n=e.right-e.left,i=e.bottom-e.top,a=xt(t,n/2,i/2);return{outer:{x:e.left,y:e.top,w:n,h:i},inner:{x:e.left+a.l,y:e.top+a.t,w:n-a.l-a.r,h:i-a.t-a.b}}}(e),i=n.outer,a=n.inner;t.fillStyle=e.backgroundColor,t.fillRect(i.x,i.y,i.w,i.h),i.w===a.w&&i.h===a.h||(t.save(),t.beginPath(),t.rect(i.x,i.y,i.w,i.h),t.clip(),t.fillStyle=e.borderColor,t.rect(a.x,a.y,a.w,a.h),t.fill("evenodd"),t.restore())},height:function(){var t=this._view;return t.base-t.y},inRange:function(t,e){return yt(this._view,t,e)},inLabelRange:function(t,e){var n=this._view;return mt(n)?yt(n,t,null):yt(n,null,e)},inXRange:function(t){return yt(this._view,t,null)},inYRange:function(t){return yt(this._view,null,t)},getCenterPoint:function(){var t,e,n=this._view;return mt(n)?(t=n.x,e=(n.y+n.base)/2):(t=(n.x+n.base)/2,e=n.y),{x:t,y:e}},getArea:function(){var t=this._view;return mt(t)?t.width*Math.abs(t.y-t.base):t.height*Math.abs(t.x-t.base)},tooltipPosition:function(){var t=this._view;return{x:t.x,y:t.y}}}),kt={},wt=st,Mt=dt,St=gt,Ct=_t;kt.Arc=wt,kt.Line=Mt,kt.Point=St,kt.Rectangle=Ct;var Pt=H._deprecated,At=H.valueOrDefault;function Dt(t,e,n){var i,a,r=n.barThickness,o=e.stackCount,s=e.pixels[t],l=H.isNullOrUndef(r)?function(t,e){var n,i,a,r,o=t._length;for(a=1,r=e.length;a0?Math.min(o,Math.abs(i-n)):o,n=i;return o}(e.scale,e.pixels):-1;return H.isNullOrUndef(r)?(i=l*n.categoryPercentage,a=n.barPercentage):(i=r*o,a=1),{chunk:i/o,ratio:a,start:s-i/2}}N._set("bar",{hover:{mode:"label"},scales:{xAxes:[{type:"category",offset:!0,gridLines:{offsetGridLines:!0}}],yAxes:[{type:"linear"}]}}),N._set("global",{datasets:{bar:{categoryPercentage:.8,barPercentage:.9}}});var Tt=it.extend({dataElementType:kt.Rectangle,_dataElementOptions:["backgroundColor","borderColor","borderSkipped","borderWidth","barPercentage","barThickness","categoryPercentage","maxBarThickness","minBarLength"],initialize:function(){var t,e,n=this;it.prototype.initialize.apply(n,arguments),(t=n.getMeta()).stack=n.getDataset().stack,t.bar=!0,e=n._getIndexScale().options,Pt("bar chart",e.barPercentage,"scales.[x/y]Axes.barPercentage","dataset.barPercentage"),Pt("bar chart",e.barThickness,"scales.[x/y]Axes.barThickness","dataset.barThickness"),Pt("bar chart",e.categoryPercentage,"scales.[x/y]Axes.categoryPercentage","dataset.categoryPercentage"),Pt("bar chart",n._getValueScale().options.minBarLength,"scales.[x/y]Axes.minBarLength","dataset.minBarLength"),Pt("bar chart",e.maxBarThickness,"scales.[x/y]Axes.maxBarThickness","dataset.maxBarThickness")},update:function(t){var e,n,i=this.getMeta().data;for(this._ruler=this.getRuler(),e=0,n=i.length;e=0&&p.min>=0?p.min:p.max,y=void 0===p.start?p.end:p.max>=0&&p.min>=0?p.max-p.min:p.min-p.max,_=g.length;if(v||void 0===v&&void 0!==b)for(i=0;i<_&&(a=g[i]).index!==t;++i)a.stack===b&&(r=void 0===(u=h._parseValue(f[a.index].data[e])).start?u.end:u.min>=0&&u.max>=0?u.max:u.min,(p.min<0&&r<0||p.max>=0&&r>0)&&(x+=r));return o=h.getPixelForValue(x),l=(s=h.getPixelForValue(x+y))-o,void 0!==m&&Math.abs(l)=0&&!c||y<0&&c?o-m:o+m),{size:l,base:o,head:s,center:s+l/2}},calculateBarIndexPixels:function(t,e,n,i){var a="flex"===i.barThickness?function(t,e,n){var i,a=e.pixels,r=a[t],o=t>0?a[t-1]:null,s=t=Rt?-zt:b<-Rt?zt:0)+m,y=Math.cos(b),_=Math.sin(b),k=Math.cos(x),w=Math.sin(x),M=b<=0&&x>=0||x>=zt,S=b<=Nt&&x>=Nt||x>=zt+Nt,C=b<=-Nt&&x>=-Nt||x>=Rt+Nt,P=b===-Rt||x>=Rt?-1:Math.min(y,y*p,k,k*p),A=C?-1:Math.min(_,_*p,w,w*p),D=M?1:Math.max(y,y*p,k,k*p),T=S?1:Math.max(_,_*p,w,w*p);u=(D-P)/2,d=(T-A)/2,h=-(D+P)/2,c=-(T+A)/2}for(i=0,a=g.length;i0&&!isNaN(t)?zt*(Math.abs(t)/e):0},getMaxBorderWidth:function(t){var e,n,i,a,r,o,s,l,u=0,d=this.chart;if(!t)for(e=0,n=d.data.datasets.length;e(u=s>u?s:u)?l:u);return u},setHoverStyle:function(t){var e=t._model,n=t._options,i=H.getHoverColor;t.$previousStyle={backgroundColor:e.backgroundColor,borderColor:e.borderColor,borderWidth:e.borderWidth},e.backgroundColor=Lt(n.hoverBackgroundColor,i(n.backgroundColor)),e.borderColor=Lt(n.hoverBorderColor,i(n.borderColor)),e.borderWidth=Lt(n.hoverBorderWidth,n.borderWidth)},_getRingWeightOffset:function(t){for(var e=0,n=0;n0&&Ht(l[t-1]._model,s)&&(n.controlPointPreviousX=u(n.controlPointPreviousX,s.left,s.right),n.controlPointPreviousY=u(n.controlPointPreviousY,s.top,s.bottom)),t0&&(r=t.getDatasetMeta(r[0]._datasetIndex).data),r},"x-axis":function(t,e){return ae(t,e,{intersect:!1})},point:function(t,e){return ee(t,Qt(e,t))},nearest:function(t,e,n){var i=Qt(e,t);n.axis=n.axis||"xy";var a=ie(n.axis);return ne(t,i,n.intersect,a)},x:function(t,e,n){var i=Qt(e,t),a=[],r=!1;return te(t,(function(t){t.inXRange(i.x)&&a.push(t),t.inRange(i.x,i.y)&&(r=!0)})),n.intersect&&!r&&(a=[]),a},y:function(t,e,n){var i=Qt(e,t),a=[],r=!1;return te(t,(function(t){t.inYRange(i.y)&&a.push(t),t.inRange(i.x,i.y)&&(r=!0)})),n.intersect&&!r&&(a=[]),a}}},oe=H.extend;function se(t,e){return H.where(t,(function(t){return t.pos===e}))}function le(t,e){return t.sort((function(t,n){var i=e?n:t,a=e?t:n;return i.weight===a.weight?i.index-a.index:i.weight-a.weight}))}function ue(t,e,n,i){return Math.max(t[n],e[n])+Math.max(t[i],e[i])}function de(t,e,n){var i,a,r=n.box,o=t.maxPadding;if(n.size&&(t[n.pos]-=n.size),n.size=n.horizontal?r.height:r.width,t[n.pos]+=n.size,r.getPadding){var s=r.getPadding();o.top=Math.max(o.top,s.top),o.left=Math.max(o.left,s.left),o.bottom=Math.max(o.bottom,s.bottom),o.right=Math.max(o.right,s.right)}if(i=e.outerWidth-ue(o,t,"left","right"),a=e.outerHeight-ue(o,t,"top","bottom"),i!==t.w||a!==t.h){t.w=i,t.h=a;var l=n.horizontal?[i,t.w]:[a,t.h];return!(l[0]===l[1]||isNaN(l[0])&&isNaN(l[1]))}}function he(t,e){var n=e.maxPadding;function i(t){var i={left:0,top:0,right:0,bottom:0};return t.forEach((function(t){i[t]=Math.max(e[t],n[t])})),i}return i(t?["left","right"]:["top","bottom"])}function ce(t,e,n){var i,a,r,o,s,l,u=[];for(i=0,a=t.length;idiv{position:absolute;width:1000000px;height:1000000px;left:0;top:0}.chartjs-size-monitor-shrink>div{position:absolute;width:200%;height:200%;left:0;top:0}"}))&&ge.default||ge,ve="$chartjs",be="chartjs-size-monitor",xe="chartjs-render-monitor",ye="chartjs-render-animation",_e=["animationstart","webkitAnimationStart"],ke={touchstart:"mousedown",touchmove:"mousemove",touchend:"mouseup",pointerenter:"mouseenter",pointerdown:"mousedown",pointermove:"mousemove",pointerup:"mouseup",pointerleave:"mouseout",pointerout:"mouseout"};function we(t,e){var n=H.getStyle(t,e),i=n&&n.match(/^(\d+)(\.\d+)?px$/);return i?Number(i[1]):void 0}var Me=!!function(){var t=!1;try{var e=Object.defineProperty({},"passive",{get:function(){t=!0}});window.addEventListener("e",null,e)}catch(t){}return t}()&&{passive:!0};function Se(t,e,n){t.addEventListener(e,n,Me)}function Ce(t,e,n){t.removeEventListener(e,n,Me)}function Pe(t,e,n,i,a){return{type:t,chart:e,native:a||null,x:void 0!==n?n:null,y:void 0!==i?i:null}}function Ae(t){var e=document.createElement("div");return e.className=t||"",e}function De(t,e,n){var i,a,r,o,s=t[ve]||(t[ve]={}),l=s.resizer=function(t){var e=Ae(be),n=Ae(be+"-expand"),i=Ae(be+"-shrink");n.appendChild(Ae()),i.appendChild(Ae()),e.appendChild(n),e.appendChild(i),e._reset=function(){n.scrollLeft=1e6,n.scrollTop=1e6,i.scrollLeft=1e6,i.scrollTop=1e6};var a=function(){e._reset(),t()};return Se(n,"scroll",a.bind(n,"expand")),Se(i,"scroll",a.bind(i,"shrink")),e}((i=function(){if(s.resizer){var i=n.options.maintainAspectRatio&&t.parentNode,a=i?i.clientWidth:0;e(Pe("resize",n)),i&&i.clientWidth0){var r=t[0];r.label?n=r.label:r.xLabel?n=r.xLabel:a>0&&r.index-1?t.split("\n"):t}function Ve(t){var e=N.global;return{xPadding:t.xPadding,yPadding:t.yPadding,xAlign:t.xAlign,yAlign:t.yAlign,rtl:t.rtl,textDirection:t.textDirection,bodyFontColor:t.bodyFontColor,_bodyFontFamily:ze(t.bodyFontFamily,e.defaultFontFamily),_bodyFontStyle:ze(t.bodyFontStyle,e.defaultFontStyle),_bodyAlign:t.bodyAlign,bodyFontSize:ze(t.bodyFontSize,e.defaultFontSize),bodySpacing:t.bodySpacing,titleFontColor:t.titleFontColor,_titleFontFamily:ze(t.titleFontFamily,e.defaultFontFamily),_titleFontStyle:ze(t.titleFontStyle,e.defaultFontStyle),titleFontSize:ze(t.titleFontSize,e.defaultFontSize),_titleAlign:t.titleAlign,titleSpacing:t.titleSpacing,titleMarginBottom:t.titleMarginBottom,footerFontColor:t.footerFontColor,_footerFontFamily:ze(t.footerFontFamily,e.defaultFontFamily),_footerFontStyle:ze(t.footerFontStyle,e.defaultFontStyle),footerFontSize:ze(t.footerFontSize,e.defaultFontSize),_footerAlign:t.footerAlign,footerSpacing:t.footerSpacing,footerMarginTop:t.footerMarginTop,caretSize:t.caretSize,cornerRadius:t.cornerRadius,backgroundColor:t.backgroundColor,opacity:0,legendColorBackground:t.multiKeyBackground,displayColors:t.displayColors,borderColor:t.borderColor,borderWidth:t.borderWidth}}function He(t,e){return"center"===e?t.x+t.width/2:"right"===e?t.x+t.width-t.xPadding:t.x+t.xPadding}function je(t){return Ee([],We(t))}var qe=K.extend({initialize:function(){this._model=Ve(this._options),this._lastActive=[]},getTitle:function(){var t=this,e=t._options,n=e.callbacks,i=n.beforeTitle.apply(t,arguments),a=n.title.apply(t,arguments),r=n.afterTitle.apply(t,arguments),o=[];return o=Ee(o,We(i)),o=Ee(o,We(a)),o=Ee(o,We(r))},getBeforeBody:function(){return je(this._options.callbacks.beforeBody.apply(this,arguments))},getBody:function(t,e){var n=this,i=n._options.callbacks,a=[];return H.each(t,(function(t){var r={before:[],lines:[],after:[]};Ee(r.before,We(i.beforeLabel.call(n,t,e))),Ee(r.lines,i.label.call(n,t,e)),Ee(r.after,We(i.afterLabel.call(n,t,e))),a.push(r)})),a},getAfterBody:function(){return je(this._options.callbacks.afterBody.apply(this,arguments))},getFooter:function(){var t=this,e=t._options.callbacks,n=e.beforeFooter.apply(t,arguments),i=e.footer.apply(t,arguments),a=e.afterFooter.apply(t,arguments),r=[];return r=Ee(r,We(n)),r=Ee(r,We(i)),r=Ee(r,We(a))},update:function(t){var e,n,i,a,r,o,s,l,u,d,h=this,c=h._options,f=h._model,g=h._model=Ve(c),p=h._active,m=h._data,v={xAlign:f.xAlign,yAlign:f.yAlign},b={x:f.x,y:f.y},x={width:f.width,height:f.height},y={x:f.caretX,y:f.caretY};if(p.length){g.opacity=1;var _=[],k=[];y=Be[c.position].call(h,p,h._eventPosition);var w=[];for(e=0,n=p.length;ei.width&&(a=i.width-e.width),a<0&&(a=0)),"top"===d?r+=h:r-="bottom"===d?e.height+h:e.height/2,"center"===d?"left"===u?a+=h:"right"===u&&(a-=h):"left"===u?a-=c:"right"===u&&(a+=c),{x:a,y:r}}(g,x,v=function(t,e){var n,i,a,r,o,s=t._model,l=t._chart,u=t._chart.chartArea,d="center",h="center";s.yl.height-e.height&&(h="bottom");var c=(u.left+u.right)/2,f=(u.top+u.bottom)/2;"center"===h?(n=function(t){return t<=c},i=function(t){return t>c}):(n=function(t){return t<=e.width/2},i=function(t){return t>=l.width-e.width/2}),a=function(t){return t+e.width+s.caretSize+s.caretPadding>l.width},r=function(t){return t-e.width-s.caretSize-s.caretPadding<0},o=function(t){return t<=f?"top":"bottom"},n(s.x)?(d="left",a(s.x)&&(d="center",h=o(s.y))):i(s.x)&&(d="right",r(s.x)&&(d="center",h=o(s.y)));var g=t._options;return{xAlign:g.xAlign?g.xAlign:d,yAlign:g.yAlign?g.yAlign:h}}(this,x),h._chart)}else g.opacity=0;return g.xAlign=v.xAlign,g.yAlign=v.yAlign,g.x=b.x,g.y=b.y,g.width=x.width,g.height=x.height,g.caretX=y.x,g.caretY=y.y,h._model=g,t&&c.custom&&c.custom.call(h,g),h},drawCaret:function(t,e){var n=this._chart.ctx,i=this._view,a=this.getCaretPosition(t,e,i);n.lineTo(a.x1,a.y1),n.lineTo(a.x2,a.y2),n.lineTo(a.x3,a.y3)},getCaretPosition:function(t,e,n){var i,a,r,o,s,l,u=n.caretSize,d=n.cornerRadius,h=n.xAlign,c=n.yAlign,f=t.x,g=t.y,p=e.width,m=e.height;if("center"===c)s=g+m/2,"left"===h?(a=(i=f)-u,r=i,o=s+u,l=s-u):(a=(i=f+p)+u,r=i,o=s-u,l=s+u);else if("left"===h?(i=(a=f+d+u)-u,r=a+u):"right"===h?(i=(a=f+p-d-u)-u,r=a+u):(i=(a=n.caretX)-u,r=a+u),"top"===c)s=(o=g)-u,l=o;else{s=(o=g+m)+u,l=o;var v=r;r=i,i=v}return{x1:i,x2:a,x3:r,y1:o,y2:s,y3:l}},drawTitle:function(t,e,n){var i,a,r,o=e.title,s=o.length;if(s){var l=Ne(e.rtl,e.x,e.width);for(t.x=He(e,e._titleAlign),n.textAlign=l.textAlign(e._titleAlign),n.textBaseline="middle",i=e.titleFontSize,a=e.titleSpacing,n.fillStyle=e.titleFontColor,n.font=H.fontString(i,e._titleFontStyle,e._titleFontFamily),r=0;r0&&n.stroke()},draw:function(){var t=this._chart.ctx,e=this._view;if(0!==e.opacity){var n={width:e.width,height:e.height},i={x:e.x,y:e.y},a=Math.abs(e.opacity<.001)?0:e.opacity,r=e.title.length||e.beforeBody.length||e.body.length||e.afterBody.length||e.footer.length;this._options.enabled&&r&&(t.save(),t.globalAlpha=a,this.drawBackground(i,e,t,n),i.y+=e.yPadding,H.rtl.overrideTextDirection(t,e.textDirection),this.drawTitle(i,e,t),this.drawBody(i,e,t),this.drawFooter(i,e,t),H.rtl.restoreTextDirection(t,e.textDirection),t.restore())}},handleEvent:function(t){var e,n=this,i=n._options;return n._lastActive=n._lastActive||[],"mouseout"===t.type?n._active=[]:(n._active=n._chart.getElementsAtEventForMode(t,i.mode,i),i.reverse&&n._active.reverse()),(e=!H.arrayEquals(n._active,n._lastActive))&&(n._lastActive=n._active,(i.enabled||i.custom)&&(n._eventPosition={x:t.x,y:t.y},n.update(!0),n.pivot())),e}}),Ue=Be,Ye=qe;Ye.positioners=Ue;var Ge=H.valueOrDefault;function Xe(){return H.merge(Object.create(null),[].slice.call(arguments),{merger:function(t,e,n,i){if("xAxes"===t||"yAxes"===t){var a,r,o,s=n[t].length;for(e[t]||(e[t]=[]),a=0;a=e[t].length&&e[t].push({}),!e[t][a].type||o.type&&o.type!==e[t][a].type?H.merge(e[t][a],[Re.getScaleDefaults(r),o]):H.merge(e[t][a],o)}else H._merger(t,e,n,i)}})}function Ke(){return H.merge(Object.create(null),[].slice.call(arguments),{merger:function(t,e,n,i){var a=e[t]||Object.create(null),r=n[t];"scales"===t?e[t]=Xe(a,r):"scale"===t?e[t]=H.merge(a,[Re.getScaleDefaults(r.type),r]):H._merger(t,e,n,i)}})}function Ze(t){var e=t.options;H.each(t.scales,(function(e){pe.removeBox(t,e)})),e=Ke(N.global,N[t.config.type],e),t.options=t.config.options=e,t.ensureScalesHaveIDs(),t.buildOrUpdateScales(),t.tooltip._options=e.tooltips,t.tooltip.initialize()}function $e(t,e,n){var i,a=function(t){return t.id===i};do{i=e+n++}while(H.findIndex(t,a)>=0);return i}function Je(t){return"top"===t||"bottom"===t}function Qe(t,e){return function(n,i){return n[t]===i[t]?n[e]-i[e]:n[t]-i[t]}}N._set("global",{elements:{},events:["mousemove","mouseout","click","touchstart","touchmove"],hover:{onHover:null,mode:"nearest",intersect:!0,animationDuration:400},onClick:null,maintainAspectRatio:!0,responsive:!0,responsiveAnimationDuration:0});var tn=function(t,e){return this.construct(t,e),this};H.extend(tn.prototype,{construct:function(t,e){var n=this;e=function(t){var e=(t=t||Object.create(null)).data=t.data||{};return e.datasets=e.datasets||[],e.labels=e.labels||[],t.options=Ke(N.global,N[t.type],t.options||{}),t}(e);var i=Oe.acquireContext(t,e),a=i&&i.canvas,r=a&&a.height,o=a&&a.width;n.id=H.uid(),n.ctx=i,n.canvas=a,n.config=e,n.width=o,n.height=r,n.aspectRatio=r?o/r:null,n.options=e.options,n._bufferedRender=!1,n._layers=[],n.chart=n,n.controller=n,tn.instances[n.id]=n,Object.defineProperty(n,"data",{get:function(){return n.config.data},set:function(t){n.config.data=t}}),i&&a?(n.initialize(),n.update()):console.error("Failed to create chart: can't acquire context from the given item")},initialize:function(){var t=this;return Le.notify(t,"beforeInit"),H.retinaScale(t,t.options.devicePixelRatio),t.bindEvents(),t.options.responsive&&t.resize(!0),t.initToolTip(),Le.notify(t,"afterInit"),t},clear:function(){return H.canvas.clear(this),this},stop:function(){return J.cancelAnimation(this),this},resize:function(t){var e=this,n=e.options,i=e.canvas,a=n.maintainAspectRatio&&e.aspectRatio||null,r=Math.max(0,Math.floor(H.getMaximumWidth(i))),o=Math.max(0,Math.floor(a?r/a:H.getMaximumHeight(i)));if((e.width!==r||e.height!==o)&&(i.width=e.width=r,i.height=e.height=o,i.style.width=r+"px",i.style.height=o+"px",H.retinaScale(e,n.devicePixelRatio),!t)){var s={width:r,height:o};Le.notify(e,"resize",[s]),n.onResize&&n.onResize(e,s),e.stop(),e.update({duration:n.responsiveAnimationDuration})}},ensureScalesHaveIDs:function(){var t=this.options,e=t.scales||{},n=t.scale;H.each(e.xAxes,(function(t,n){t.id||(t.id=$e(e.xAxes,"x-axis-",n))})),H.each(e.yAxes,(function(t,n){t.id||(t.id=$e(e.yAxes,"y-axis-",n))})),n&&(n.id=n.id||"scale")},buildOrUpdateScales:function(){var t=this,e=t.options,n=t.scales||{},i=[],a=Object.keys(n).reduce((function(t,e){return t[e]=!1,t}),{});e.scales&&(i=i.concat((e.scales.xAxes||[]).map((function(t){return{options:t,dtype:"category",dposition:"bottom"}})),(e.scales.yAxes||[]).map((function(t){return{options:t,dtype:"linear",dposition:"left"}})))),e.scale&&i.push({options:e.scale,dtype:"radialLinear",isDefault:!0,dposition:"chartArea"}),H.each(i,(function(e){var i=e.options,r=i.id,o=Ge(i.type,e.dtype);Je(i.position)!==Je(e.dposition)&&(i.position=e.dposition),a[r]=!0;var s=null;if(r in n&&n[r].type===o)(s=n[r]).options=i,s.ctx=t.ctx,s.chart=t;else{var l=Re.getScaleConstructor(o);if(!l)return;s=new l({id:r,type:o,options:i,ctx:t.ctx,chart:t}),n[s.id]=s}s.mergeTicksOptions(),e.isDefault&&(t.scale=s)})),H.each(a,(function(t,e){t||delete n[e]})),t.scales=n,Re.addScalesToLayout(this)},buildOrUpdateControllers:function(){var t,e,n=this,i=[],a=n.data.datasets;for(t=0,e=a.length;t=0;--n)this.drawDataset(e[n],t);Le.notify(this,"afterDatasetsDraw",[t])}},drawDataset:function(t,e){var n={meta:t,index:t.index,easingValue:e};!1!==Le.notify(this,"beforeDatasetDraw",[n])&&(t.controller.draw(e),Le.notify(this,"afterDatasetDraw",[n]))},_drawTooltip:function(t){var e=this.tooltip,n={tooltip:e,easingValue:t};!1!==Le.notify(this,"beforeTooltipDraw",[n])&&(e.draw(),Le.notify(this,"afterTooltipDraw",[n]))},getElementAtEvent:function(t){return re.modes.single(this,t)},getElementsAtEvent:function(t){return re.modes.label(this,t,{intersect:!0})},getElementsAtXAxis:function(t){return re.modes["x-axis"](this,t,{intersect:!0})},getElementsAtEventForMode:function(t,e,n){var i=re.modes[e];return"function"==typeof i?i(this,t,n):[]},getDatasetAtEvent:function(t){return re.modes.dataset(this,t,{intersect:!0})},getDatasetMeta:function(t){var e=this.data.datasets[t];e._meta||(e._meta={});var n=e._meta[this.id];return n||(n=e._meta[this.id]={type:null,data:[],dataset:null,controller:null,hidden:null,xAxisID:null,yAxisID:null,order:e.order||0,index:t}),n},getVisibleDatasetCount:function(){for(var t=0,e=0,n=this.data.datasets.length;e3?n[2]-n[1]:n[1]-n[0];Math.abs(i)>1&&t!==Math.floor(t)&&(i=t-Math.floor(t));var a=H.log10(Math.abs(i)),r="";if(0!==t)if(Math.max(Math.abs(n[0]),Math.abs(n[n.length-1]))<1e-4){var o=H.log10(Math.abs(t)),s=Math.floor(o)-Math.floor(a);s=Math.max(Math.min(s,20),0),r=t.toExponential(s)}else{var l=-1*Math.floor(a);l=Math.max(Math.min(l,20),0),r=t.toFixed(l)}else r="0";return r},logarithmic:function(t,e,n){var i=t/Math.pow(10,Math.floor(H.log10(t)));return 0===t?"0":1===i||2===i||5===i||0===e||e===n.length-1?t.toExponential():""}}},sn=H.isArray,ln=H.isNullOrUndef,un=H.valueOrDefault,dn=H.valueAtIndexOrDefault;function hn(t,e,n){var i,a=t.getTicks().length,r=Math.min(e,a-1),o=t.getPixelForTick(r),s=t._startPixel,l=t._endPixel;if(!(n&&(i=1===a?Math.max(o-s,l-o):0===e?(t.getPixelForTick(1)-o)/2:(o-t.getPixelForTick(r-1))/2,(o+=rl+1e-6)))return o}function cn(t,e,n,i){var a,r,o,s,l,u,d,h,c,f,g,p,m,v=n.length,b=[],x=[],y=[],_=0,k=0;for(a=0;ae){for(n=0;n=c||d<=1||!s.isHorizontal()?s.labelRotation=h:(e=(t=s._getLabelSizes()).widest.width,n=t.highest.height-t.highest.offset,i=Math.min(s.maxWidth,s.chart.width-e),e+6>(a=l.offset?s.maxWidth/d:i/(d-1))&&(a=i/(d-(l.offset?.5:1)),r=s.maxHeight-fn(l.gridLines)-u.padding-gn(l.scaleLabel),o=Math.sqrt(e*e+n*n),f=H.toDegrees(Math.min(Math.asin(Math.min((t.highest.height+6)/a,1)),Math.asin(Math.min(r/o,1))-Math.asin(n/o))),f=Math.max(h,Math.min(c,f))),s.labelRotation=f)},afterCalculateTickRotation:function(){H.callback(this.options.afterCalculateTickRotation,[this])},beforeFit:function(){H.callback(this.options.beforeFit,[this])},fit:function(){var t=this,e=t.minSize={width:0,height:0},n=t.chart,i=t.options,a=i.ticks,r=i.scaleLabel,o=i.gridLines,s=t._isVisible(),l="bottom"===i.position,u=t.isHorizontal();if(u?e.width=t.maxWidth:s&&(e.width=fn(o)+gn(r)),u?s&&(e.height=fn(o)+gn(r)):e.height=t.maxHeight,a.display&&s){var d=mn(a),h=t._getLabelSizes(),c=h.first,f=h.last,g=h.widest,p=h.highest,m=.4*d.minor.lineHeight,v=a.padding;if(u){var b=0!==t.labelRotation,x=H.toRadians(t.labelRotation),y=Math.cos(x),_=Math.sin(x),k=_*g.width+y*(p.height-(b?p.offset:0))+(b?0:m);e.height=Math.min(t.maxHeight,e.height+k+v);var w,M,S=t.getPixelForTick(0)-t.left,C=t.right-t.getPixelForTick(t.getTicks().length-1);b?(w=l?y*c.width+_*c.offset:_*(c.height-c.offset),M=l?_*(f.height-f.offset):y*f.width+_*f.offset):(w=c.width/2,M=f.width/2),t.paddingLeft=Math.max((w-S)*t.width/(t.width-S),0)+3,t.paddingRight=Math.max((M-C)*t.width/(t.width-C),0)+3}else{var P=a.mirror?0:g.width+v+m;e.width=Math.min(t.maxWidth,e.width+P),t.paddingTop=c.height/2,t.paddingBottom=f.height/2}}t.handleMargins(),u?(t.width=t._length=n.width-t.margins.left-t.margins.right,t.height=e.height):(t.width=e.width,t.height=t._length=n.height-t.margins.top-t.margins.bottom)},handleMargins:function(){var t=this;t.margins&&(t.margins.left=Math.max(t.paddingLeft,t.margins.left),t.margins.top=Math.max(t.paddingTop,t.margins.top),t.margins.right=Math.max(t.paddingRight,t.margins.right),t.margins.bottom=Math.max(t.paddingBottom,t.margins.bottom))},afterFit:function(){H.callback(this.options.afterFit,[this])},isHorizontal:function(){var t=this.options.position;return"top"===t||"bottom"===t},isFullWidth:function(){return this.options.fullWidth},getRightValue:function(t){if(ln(t))return NaN;if(("number"==typeof t||t instanceof Number)&&!isFinite(t))return NaN;if(t)if(this.isHorizontal()){if(void 0!==t.x)return this.getRightValue(t.x)}else if(void 0!==t.y)return this.getRightValue(t.y);return t},_convertTicksToLabels:function(t){var e,n,i,a=this;for(a.ticks=t.map((function(t){return t.value})),a.beforeTickToLabelConversion(),e=a.convertTicksToLabels(t)||a.ticks,a.afterTickToLabelConversion(),n=0,i=t.length;nn-1?null:this.getPixelForDecimal(t*i+(e?i/2:0))},getPixelForDecimal:function(t){return this._reversePixels&&(t=1-t),this._startPixel+t*this._length},getDecimalForPixel:function(t){var e=(t-this._startPixel)/this._length;return this._reversePixels?1-e:e},getBasePixel:function(){return this.getPixelForValue(this.getBaseValue())},getBaseValue:function(){var t=this.min,e=this.max;return this.beginAtZero?0:t<0&&e<0?e:t>0&&e>0?t:0},_autoSkip:function(t){var e,n,i,a,r=this.options.ticks,o=this._length,s=r.maxTicksLimit||o/this._tickSize()+1,l=r.major.enabled?function(t){var e,n,i=[];for(e=0,n=t.length;es)return function(t,e,n){var i,a,r=0,o=e[0];for(n=Math.ceil(n),i=0;iu)return r;return Math.max(u,1)}(l,t,0,s),u>0){for(e=0,n=u-1;e1?(h-d)/(u-1):null,bn(t,i,H.isNullOrUndef(a)?0:d-a,d),bn(t,i,h,H.isNullOrUndef(a)?t.length:h+a),vn(t)}return bn(t,i),vn(t)},_tickSize:function(){var t=this.options.ticks,e=H.toRadians(this.labelRotation),n=Math.abs(Math.cos(e)),i=Math.abs(Math.sin(e)),a=this._getLabelSizes(),r=t.autoSkipPadding||0,o=a?a.widest.width+r:0,s=a?a.highest.height+r:0;return this.isHorizontal()?s*n>o*i?o/n:s/i:s*i=0&&(o=t),void 0!==r&&(t=n.indexOf(r))>=0&&(s=t),e.minIndex=o,e.maxIndex=s,e.min=n[o],e.max=n[s]},buildTicks:function(){var t=this._getLabels(),e=this.minIndex,n=this.maxIndex;this.ticks=0===e&&n===t.length-1?t:t.slice(e,n+1)},getLabelForIndex:function(t,e){var n=this.chart;return n.getDatasetMeta(e).controller._getValueScaleId()===this.id?this.getRightValue(n.data.datasets[e].data[t]):this._getLabels()[t]},_configure:function(){var t=this,e=t.options.offset,n=t.ticks;yn.prototype._configure.call(t),t.isHorizontal()||(t._reversePixels=!t._reversePixels),n&&(t._startValue=t.minIndex-(e?.5:0),t._valueRange=Math.max(n.length-(e?0:1),1))},getPixelForValue:function(t,e,n){var i,a,r,o=this;return _n(e)||_n(n)||(t=o.chart.data.datasets[n].data[e]),_n(t)||(i=o.isHorizontal()?t.x:t.y),(void 0!==i||void 0!==t&&isNaN(e))&&(a=o._getLabels(),t=H.valueOrDefault(i,t),e=-1!==(r=a.indexOf(t))?r:e,isNaN(e)&&(e=t)),o.getPixelForDecimal((e-o._startValue)/o._valueRange)},getPixelForTick:function(t){var e=this.ticks;return t<0||t>e.length-1?null:this.getPixelForValue(e[t],t+this.minIndex)},getValueForPixel:function(t){var e=Math.round(this._startValue+this.getDecimalForPixel(t)*this._valueRange);return Math.min(Math.max(e,0),this.ticks.length-1)},getBasePixel:function(){return this.bottom}}),wn={position:"bottom"};kn._defaults=wn;var Mn=H.noop,Sn=H.isNullOrUndef;var Cn=yn.extend({getRightValue:function(t){return"string"==typeof t?+t:yn.prototype.getRightValue.call(this,t)},handleTickRangeOptions:function(){var t=this,e=t.options.ticks;if(e.beginAtZero){var n=H.sign(t.min),i=H.sign(t.max);n<0&&i<0?t.max=0:n>0&&i>0&&(t.min=0)}var a=void 0!==e.min||void 0!==e.suggestedMin,r=void 0!==e.max||void 0!==e.suggestedMax;void 0!==e.min?t.min=e.min:void 0!==e.suggestedMin&&(null===t.min?t.min=e.suggestedMin:t.min=Math.min(t.min,e.suggestedMin)),void 0!==e.max?t.max=e.max:void 0!==e.suggestedMax&&(null===t.max?t.max=e.suggestedMax:t.max=Math.max(t.max,e.suggestedMax)),a!==r&&t.min>=t.max&&(a?t.max=t.min+1:t.min=t.max-1),t.min===t.max&&(t.max++,e.beginAtZero||t.min--)},getTickLimit:function(){var t,e=this.options.ticks,n=e.stepSize,i=e.maxTicksLimit;return n?t=Math.ceil(this.max/n)-Math.floor(this.min/n)+1:(t=this._computeTickLimit(),i=i||11),i&&(t=Math.min(i,t)),t},_computeTickLimit:function(){return Number.POSITIVE_INFINITY},handleDirectionalChanges:Mn,buildTicks:function(){var t=this,e=t.options.ticks,n=t.getTickLimit(),i={maxTicks:n=Math.max(2,n),min:e.min,max:e.max,precision:e.precision,stepSize:H.valueOrDefault(e.fixedStepSize,e.stepSize)},a=t.ticks=function(t,e){var n,i,a,r,o=[],s=t.stepSize,l=s||1,u=t.maxTicks-1,d=t.min,h=t.max,c=t.precision,f=e.min,g=e.max,p=H.niceNum((g-f)/u/l)*l;if(p<1e-14&&Sn(d)&&Sn(h))return[f,g];(r=Math.ceil(g/p)-Math.floor(f/p))>u&&(p=H.niceNum(r*p/u/l)*l),s||Sn(c)?n=Math.pow(10,H._decimalPlaces(p)):(n=Math.pow(10,c),p=Math.ceil(p*n)/n),i=Math.floor(f/p)*p,a=Math.ceil(g/p)*p,s&&(!Sn(d)&&H.almostWhole(d/p,p/1e3)&&(i=d),!Sn(h)&&H.almostWhole(h/p,p/1e3)&&(a=h)),r=(a-i)/p,r=H.almostEquals(r,Math.round(r),p/1e3)?Math.round(r):Math.ceil(r),i=Math.round(i*n)/n,a=Math.round(a*n)/n,o.push(Sn(d)?i:d);for(var m=1;me.length-1?null:this.getPixelForValue(e[t])}}),In=Pn;Tn._defaults=In;var Fn=H.valueOrDefault,On=H.math.log10;var Ln={position:"left",ticks:{callback:on.formatters.logarithmic}};function Rn(t,e){return H.isFinite(t)&&t>=0?t:e}var zn=yn.extend({determineDataLimits:function(){var t,e,n,i,a,r,o=this,s=o.options,l=o.chart,u=l.data.datasets,d=o.isHorizontal();function h(t){return d?t.xAxisID===o.id:t.yAxisID===o.id}o.min=Number.POSITIVE_INFINITY,o.max=Number.NEGATIVE_INFINITY,o.minNotZero=Number.POSITIVE_INFINITY;var c=s.stacked;if(void 0===c)for(t=0;t0){var e=H.min(t),n=H.max(t);o.min=Math.min(o.min,e),o.max=Math.max(o.max,n)}}))}else for(t=0;t0?t.minNotZero=t.min:t.max<1?t.minNotZero=Math.pow(10,Math.floor(On(t.max))):t.minNotZero=1)},buildTicks:function(){var t=this,e=t.options.ticks,n=!t.isHorizontal(),i={min:Rn(e.min),max:Rn(e.max)},a=t.ticks=function(t,e){var n,i,a=[],r=Fn(t.min,Math.pow(10,Math.floor(On(e.min)))),o=Math.floor(On(e.max)),s=Math.ceil(e.max/Math.pow(10,o));0===r?(n=Math.floor(On(e.minNotZero)),i=Math.floor(e.minNotZero/Math.pow(10,n)),a.push(r),r=i*Math.pow(10,n)):(n=Math.floor(On(r)),i=Math.floor(r/Math.pow(10,n)));var l=n<0?Math.pow(10,Math.abs(n)):1;do{a.push(r),10===++i&&(i=1,l=++n>=0?1:l),r=Math.round(i*Math.pow(10,n)*l)/l}while(ne.length-1?null:this.getPixelForValue(e[t])},_getFirstTickValue:function(t){var e=Math.floor(On(t));return Math.floor(t/Math.pow(10,e))*Math.pow(10,e)},_configure:function(){var t=this,e=t.min,n=0;yn.prototype._configure.call(t),0===e&&(e=t._getFirstTickValue(t.minNotZero),n=Fn(t.options.ticks.fontSize,N.global.defaultFontSize)/t._length),t._startValue=On(e),t._valueOffset=n,t._valueRange=(On(t.max)-On(e))/(1-n)},getPixelForValue:function(t){var e=this,n=0;return(t=+e.getRightValue(t))>e.min&&t>0&&(n=(On(t)-e._startValue)/e._valueRange+e._valueOffset),e.getPixelForDecimal(n)},getValueForPixel:function(t){var e=this,n=e.getDecimalForPixel(t);return 0===n&&0===e.min?0:Math.pow(10,e._startValue+(n-e._valueOffset)*e._valueRange)}}),Nn=Ln;zn._defaults=Nn;var Bn=H.valueOrDefault,En=H.valueAtIndexOrDefault,Wn=H.options.resolve,Vn={display:!0,animate:!0,position:"chartArea",angleLines:{display:!0,color:"rgba(0,0,0,0.1)",lineWidth:1,borderDash:[],borderDashOffset:0},gridLines:{circular:!1},ticks:{showLabelBackdrop:!0,backdropColor:"rgba(255,255,255,0.75)",backdropPaddingY:2,backdropPaddingX:2,callback:on.formatters.linear},pointLabels:{display:!0,fontSize:10,callback:function(t){return t}}};function Hn(t){var e=t.ticks;return e.display&&t.display?Bn(e.fontSize,N.global.defaultFontSize)+2*e.backdropPaddingY:0}function jn(t,e,n,i,a){return t===i||t===a?{start:e-n/2,end:e+n/2}:ta?{start:e-n,end:e}:{start:e,end:e+n}}function qn(t){return 0===t||180===t?"center":t<180?"left":"right"}function Un(t,e,n,i){var a,r,o=n.y+i/2;if(H.isArray(e))for(a=0,r=e.length;a270||t<90)&&(n.y-=e.h)}function Gn(t){return H.isNumber(t)?t:0}var Xn=Cn.extend({setDimensions:function(){var t=this;t.width=t.maxWidth,t.height=t.maxHeight,t.paddingTop=Hn(t.options)/2,t.xCenter=Math.floor(t.width/2),t.yCenter=Math.floor((t.height-t.paddingTop)/2),t.drawingArea=Math.min(t.height-t.paddingTop,t.width)/2},determineDataLimits:function(){var t=this,e=t.chart,n=Number.POSITIVE_INFINITY,i=Number.NEGATIVE_INFINITY;H.each(e.data.datasets,(function(a,r){if(e.isDatasetVisible(r)){var o=e.getDatasetMeta(r);H.each(a.data,(function(e,a){var r=+t.getRightValue(e);isNaN(r)||o.data[a].hidden||(n=Math.min(r,n),i=Math.max(r,i))}))}})),t.min=n===Number.POSITIVE_INFINITY?0:n,t.max=i===Number.NEGATIVE_INFINITY?0:i,t.handleTickRangeOptions()},_computeTickLimit:function(){return Math.ceil(this.drawingArea/Hn(this.options))},convertTicksToLabels:function(){var t=this;Cn.prototype.convertTicksToLabels.call(t),t.pointLabels=t.chart.data.labels.map((function(){var e=H.callback(t.options.pointLabels.callback,arguments,t);return e||0===e?e:""}))},getLabelForIndex:function(t,e){return+this.getRightValue(this.chart.data.datasets[e].data[t])},fit:function(){var t=this.options;t.display&&t.pointLabels.display?function(t){var e,n,i,a=H.options._parseFont(t.options.pointLabels),r={l:0,r:t.width,t:0,b:t.height-t.paddingTop},o={};t.ctx.font=a.string,t._pointLabelSizes=[];var s,l,u,d=t.chart.data.labels.length;for(e=0;er.r&&(r.r=f.end,o.r=h),g.startr.b&&(r.b=g.end,o.b=h)}t.setReductions(t.drawingArea,r,o)}(this):this.setCenterPoint(0,0,0,0)},setReductions:function(t,e,n){var i=this,a=e.l/Math.sin(n.l),r=Math.max(e.r-i.width,0)/Math.sin(n.r),o=-e.t/Math.cos(n.t),s=-Math.max(e.b-(i.height-i.paddingTop),0)/Math.cos(n.b);a=Gn(a),r=Gn(r),o=Gn(o),s=Gn(s),i.drawingArea=Math.min(Math.floor(t-(a+r)/2),Math.floor(t-(o+s)/2)),i.setCenterPoint(a,r,o,s)},setCenterPoint:function(t,e,n,i){var a=this,r=a.width-e-a.drawingArea,o=t+a.drawingArea,s=n+a.drawingArea,l=a.height-a.paddingTop-i-a.drawingArea;a.xCenter=Math.floor((o+r)/2+a.left),a.yCenter=Math.floor((s+l)/2+a.top+a.paddingTop)},getIndexAngle:function(t){var e=this.chart,n=(t*(360/e.data.labels.length)+((e.options||{}).startAngle||0))%360;return(n<0?n+360:n)*Math.PI*2/360},getDistanceFromCenterForValue:function(t){var e=this;if(H.isNullOrUndef(t))return NaN;var n=e.drawingArea/(e.max-e.min);return e.options.ticks.reverse?(e.max-t)*n:(t-e.min)*n},getPointPosition:function(t,e){var n=this.getIndexAngle(t)-Math.PI/2;return{x:Math.cos(n)*e+this.xCenter,y:Math.sin(n)*e+this.yCenter}},getPointPositionForValue:function(t,e){return this.getPointPosition(t,this.getDistanceFromCenterForValue(e))},getBasePosition:function(t){var e=this.min,n=this.max;return this.getPointPositionForValue(t||0,this.beginAtZero?0:e<0&&n<0?n:e>0&&n>0?e:0)},_drawGrid:function(){var t,e,n,i=this,a=i.ctx,r=i.options,o=r.gridLines,s=r.angleLines,l=Bn(s.lineWidth,o.lineWidth),u=Bn(s.color,o.color);if(r.pointLabels.display&&function(t){var e=t.ctx,n=t.options,i=n.pointLabels,a=Hn(n),r=t.getDistanceFromCenterForValue(n.ticks.reverse?t.min:t.max),o=H.options._parseFont(i);e.save(),e.font=o.string,e.textBaseline="middle";for(var s=t.chart.data.labels.length-1;s>=0;s--){var l=0===s?a/2:0,u=t.getPointPosition(s,r+l+5),d=En(i.fontColor,s,N.global.defaultFontColor);e.fillStyle=d;var h=t.getIndexAngle(s),c=H.toDegrees(h);e.textAlign=qn(c),Yn(c,t._pointLabelSizes[s],u),Un(e,t.pointLabels[s],u,o.lineHeight)}e.restore()}(i),o.display&&H.each(i.ticks,(function(t,n){0!==n&&(e=i.getDistanceFromCenterForValue(i.ticksAsNumbers[n]),function(t,e,n,i){var a,r=t.ctx,o=e.circular,s=t.chart.data.labels.length,l=En(e.color,i-1),u=En(e.lineWidth,i-1);if((o||s)&&l&&u){if(r.save(),r.strokeStyle=l,r.lineWidth=u,r.setLineDash&&(r.setLineDash(e.borderDash||[]),r.lineDashOffset=e.borderDashOffset||0),r.beginPath(),o)r.arc(t.xCenter,t.yCenter,n,0,2*Math.PI);else{a=t.getPointPosition(0,n),r.moveTo(a.x,a.y);for(var d=1;d=0;t--)e=i.getDistanceFromCenterForValue(r.ticks.reverse?i.min:i.max),n=i.getPointPosition(t,e),a.beginPath(),a.moveTo(i.xCenter,i.yCenter),a.lineTo(n.x,n.y),a.stroke();a.restore()}},_drawLabels:function(){var t=this,e=t.ctx,n=t.options.ticks;if(n.display){var i,a,r=t.getIndexAngle(0),o=H.options._parseFont(n),s=Bn(n.fontColor,N.global.defaultFontColor);e.save(),e.font=o.string,e.translate(t.xCenter,t.yCenter),e.rotate(r),e.textAlign="center",e.textBaseline="middle",H.each(t.ticks,(function(r,l){(0!==l||n.reverse)&&(i=t.getDistanceFromCenterForValue(t.ticksAsNumbers[l]),n.showLabelBackdrop&&(a=e.measureText(r).width,e.fillStyle=n.backdropColor,e.fillRect(-a/2-n.backdropPaddingX,-i-o.size/2-n.backdropPaddingY,a+2*n.backdropPaddingX,o.size+2*n.backdropPaddingY)),e.fillStyle=s,e.fillText(r,0,-i))})),e.restore()}},_drawTitle:H.noop}),Kn=Vn;Xn._defaults=Kn;var Zn=H._deprecated,$n=H.options.resolve,Jn=H.valueOrDefault,Qn=Number.MIN_SAFE_INTEGER||-9007199254740991,ti=Number.MAX_SAFE_INTEGER||9007199254740991,ei={millisecond:{common:!0,size:1,steps:1e3},second:{common:!0,size:1e3,steps:60},minute:{common:!0,size:6e4,steps:60},hour:{common:!0,size:36e5,steps:24},day:{common:!0,size:864e5,steps:30},week:{common:!1,size:6048e5,steps:4},month:{common:!0,size:2628e6,steps:12},quarter:{common:!1,size:7884e6,steps:4},year:{common:!0,size:3154e7}},ni=Object.keys(ei);function ii(t,e){return t-e}function ai(t){return H.valueOrDefault(t.time.min,t.ticks.min)}function ri(t){return H.valueOrDefault(t.time.max,t.ticks.max)}function oi(t,e,n,i){var a=function(t,e,n){for(var i,a,r,o=0,s=t.length-1;o>=0&&o<=s;){if(a=t[(i=o+s>>1)-1]||null,r=t[i],!a)return{lo:null,hi:r};if(r[e]n))return{lo:a,hi:r};s=i-1}}return{lo:r,hi:null}}(t,e,n),r=a.lo?a.hi?a.lo:t[t.length-2]:t[0],o=a.lo?a.hi?a.hi:t[t.length-1]:t[1],s=o[e]-r[e],l=s?(n-r[e])/s:0,u=(o[i]-r[i])*l;return r[i]+u}function si(t,e){var n=t._adapter,i=t.options.time,a=i.parser,r=a||i.format,o=e;return"function"==typeof a&&(o=a(o)),H.isFinite(o)||(o="string"==typeof r?n.parse(o,r):n.parse(o)),null!==o?+o:(a||"function"!=typeof r||(o=r(e),H.isFinite(o)||(o=n.parse(o))),o)}function li(t,e){if(H.isNullOrUndef(e))return null;var n=t.options.time,i=si(t,t.getRightValue(e));return null===i?i:(n.round&&(i=+t._adapter.startOf(i,n.round)),i)}function ui(t,e,n,i){var a,r,o,s=ni.length;for(a=ni.indexOf(t);a=0&&(e[r].major=!0);return e}(t,r,o,n):r}var hi=yn.extend({initialize:function(){this.mergeTicksOptions(),yn.prototype.initialize.call(this)},update:function(){var t=this,e=t.options,n=e.time||(e.time={}),i=t._adapter=new rn._date(e.adapters.date);return Zn("time scale",n.format,"time.format","time.parser"),Zn("time scale",n.min,"time.min","ticks.min"),Zn("time scale",n.max,"time.max","ticks.max"),H.mergeIf(n.displayFormats,i.formats()),yn.prototype.update.apply(t,arguments)},getRightValue:function(t){return t&&void 0!==t.t&&(t=t.t),yn.prototype.getRightValue.call(this,t)},determineDataLimits:function(){var t,e,n,i,a,r,o,s=this,l=s.chart,u=s._adapter,d=s.options,h=d.time.unit||"day",c=ti,f=Qn,g=[],p=[],m=[],v=s._getLabels();for(t=0,n=v.length;t1?function(t){var e,n,i,a={},r=[];for(e=0,n=t.length;e1e5*u)throw e+" and "+n+" are too far apart with stepSize of "+u+" "+l;for(a=h;a=a&&n<=r&&d.push(n);return i.min=a,i.max=r,i._unit=l.unit||(s.autoSkip?ui(l.minUnit,i.min,i.max,h):function(t,e,n,i,a){var r,o;for(r=ni.length-1;r>=ni.indexOf(n);r--)if(o=ni[r],ei[o].common&&t._adapter.diff(a,i,o)>=e-1)return o;return ni[n?ni.indexOf(n):0]}(i,d.length,l.minUnit,i.min,i.max)),i._majorUnit=s.major.enabled&&"year"!==i._unit?function(t){for(var e=ni.indexOf(t)+1,n=ni.length;ee&&s=0&&t0?s:1}}),ci={position:"bottom",distribution:"linear",bounds:"data",adapters:{},time:{parser:!1,unit:!1,round:!1,displayFormat:!1,isoWeekday:!1,minUnit:"millisecond",displayFormats:{}},ticks:{autoSkip:!1,source:"auto",major:{enabled:!1}}};hi._defaults=ci;var fi={category:kn,linear:Tn,logarithmic:zn,radialLinear:Xn,time:hi},gi={datetime:"MMM D, YYYY, h:mm:ss a",millisecond:"h:mm:ss.SSS a",second:"h:mm:ss a",minute:"h:mm a",hour:"hA",day:"MMM D",week:"ll",month:"MMM YYYY",quarter:"[Q]Q - YYYY",year:"YYYY"};rn._date.override("function"==typeof t?{_id:"moment",formats:function(){return gi},parse:function(e,n){return"string"==typeof e&&"string"==typeof n?e=t(e,n):e instanceof t||(e=t(e)),e.isValid()?e.valueOf():null},format:function(e,n){return t(e).format(n)},add:function(e,n,i){return t(e).add(n,i).valueOf()},diff:function(e,n,i){return t(e).diff(t(n),i)},startOf:function(e,n,i){return e=t(e),"isoWeek"===n?e.isoWeekday(i).valueOf():e.startOf(n).valueOf()},endOf:function(e,n){return t(e).endOf(n).valueOf()},_create:function(e){return t(e)}}:{}),N._set("global",{plugins:{filler:{propagate:!0}}});var pi={dataset:function(t){var e=t.fill,n=t.chart,i=n.getDatasetMeta(e),a=i&&n.isDatasetVisible(e)&&i.dataset._children||[],r=a.length||0;return r?function(t,e){return e=n)&&i;switch(r){case"bottom":return"start";case"top":return"end";case"zero":return"origin";case"origin":case"start":case"end":return r;default:return!1}}function vi(t){return(t.el._scale||{}).getPointPositionForValue?function(t){var e,n,i,a,r,o=t.el._scale,s=o.options,l=o.chart.data.labels.length,u=t.fill,d=[];if(!l)return null;for(e=s.ticks.reverse?o.max:o.min,n=s.ticks.reverse?o.min:o.max,i=o.getPointPositionForValue(0,e),a=0;a0;--r)H.canvas.lineTo(t,n[r],n[r-1],!0);else for(o=n[0].cx,s=n[0].cy,l=Math.sqrt(Math.pow(n[0].x-o,2)+Math.pow(n[0].y-s,2)),r=a-1;r>0;--r)t.arc(o,s,l,n[r].angle,n[r-1].angle,!0)}}function ki(t,e,n,i,a,r){var o,s,l,u,d,h,c,f,g=e.length,p=i.spanGaps,m=[],v=[],b=0,x=0;for(t.beginPath(),o=0,s=g;o=0;--n)(e=l[n].$filler)&&e.visible&&(a=(i=e.el)._view,r=i._children||[],o=e.mapper,s=a.backgroundColor||N.global.defaultColor,o&&s&&r.length&&(H.canvas.clipArea(u,t.chartArea),ki(u,r,o,a,s,i._loop),H.canvas.unclipArea(u)))}},Mi=H.rtl.getRtlAdapter,Si=H.noop,Ci=H.valueOrDefault;function Pi(t,e){return t.usePointStyle&&t.boxWidth>e?e:t.boxWidth}N._set("global",{legend:{display:!0,position:"top",align:"center",fullWidth:!0,reverse:!1,weight:1e3,onClick:function(t,e){var n=e.datasetIndex,i=this.chart,a=i.getDatasetMeta(n);a.hidden=null===a.hidden?!i.data.datasets[n].hidden:null,i.update()},onHover:null,onLeave:null,labels:{boxWidth:40,padding:10,generateLabels:function(t){var e=t.data.datasets,n=t.options.legend||{},i=n.labels&&n.labels.usePointStyle;return t._getSortedDatasetMetas().map((function(n){var a=n.controller.getStyle(i?0:void 0);return{text:e[n.index].label,fillStyle:a.backgroundColor,hidden:!t.isDatasetVisible(n.index),lineCap:a.borderCapStyle,lineDash:a.borderDash,lineDashOffset:a.borderDashOffset,lineJoin:a.borderJoinStyle,lineWidth:a.borderWidth,strokeStyle:a.borderColor,pointStyle:a.pointStyle,rotation:a.rotation,datasetIndex:n.index}}),this)}}},legendCallback:function(t){var e,n,i,a=document.createElement("ul"),r=t.data.datasets;for(a.setAttribute("class",t.id+"-legend"),e=0,n=r.length;el.width)&&(h+=o+n.padding,d[d.length-(e>0?0:1)]=0),s[e]={left:0,top:0,width:i,height:o},d[d.length-1]+=i+n.padding})),l.height+=h}else{var c=n.padding,f=t.columnWidths=[],g=t.columnHeights=[],p=n.padding,m=0,v=0;H.each(t.legendItems,(function(t,e){var i=Pi(n,o)+o/2+a.measureText(t.text).width;e>0&&v+o+2*c>l.height&&(p+=m+n.padding,f.push(m),g.push(v),m=0,v=0),m=Math.max(m,i),v+=o+c,s[e]={left:0,top:0,width:i,height:o}})),p+=m,f.push(m),g.push(v),l.width+=p}t.width=l.width,t.height=l.height}else t.width=l.width=t.height=l.height=0},afterFit:Si,isHorizontal:function(){return"top"===this.options.position||"bottom"===this.options.position},draw:function(){var t=this,e=t.options,n=e.labels,i=N.global,a=i.defaultColor,r=i.elements.line,o=t.height,s=t.columnHeights,l=t.width,u=t.lineWidths;if(e.display){var d,h=Mi(e.rtl,t.left,t.minSize.width),c=t.ctx,f=Ci(n.fontColor,i.defaultFontColor),g=H.options._parseFont(n),p=g.size;c.textAlign=h.textAlign("left"),c.textBaseline="middle",c.lineWidth=.5,c.strokeStyle=f,c.fillStyle=f,c.font=g.string;var m=Pi(n,p),v=t.legendHitBoxes,b=function(t,i){switch(e.align){case"start":return n.padding;case"end":return t-i;default:return(t-i+n.padding)/2}},x=t.isHorizontal();d=x?{x:t.left+b(l,u[0]),y:t.top+n.padding,line:0}:{x:t.left+n.padding,y:t.top+b(o,s[0]),line:0},H.rtl.overrideTextDirection(t.ctx,e.textDirection);var y=p+n.padding;H.each(t.legendItems,(function(e,i){var f=c.measureText(e.text).width,g=m+p/2+f,_=d.x,k=d.y;h.setWidth(t.minSize.width),x?i>0&&_+g+n.padding>t.left+t.minSize.width&&(k=d.y+=y,d.line++,_=d.x=t.left+b(l,u[d.line])):i>0&&k+y>t.top+t.minSize.height&&(_=d.x=_+t.columnWidths[d.line]+n.padding,d.line++,k=d.y=t.top+b(o,s[d.line]));var w=h.x(_);!function(t,e,i){if(!(isNaN(m)||m<=0)){c.save();var o=Ci(i.lineWidth,r.borderWidth);if(c.fillStyle=Ci(i.fillStyle,a),c.lineCap=Ci(i.lineCap,r.borderCapStyle),c.lineDashOffset=Ci(i.lineDashOffset,r.borderDashOffset),c.lineJoin=Ci(i.lineJoin,r.borderJoinStyle),c.lineWidth=o,c.strokeStyle=Ci(i.strokeStyle,a),c.setLineDash&&c.setLineDash(Ci(i.lineDash,r.borderDash)),n&&n.usePointStyle){var s=m*Math.SQRT2/2,l=h.xPlus(t,m/2),u=e+p/2;H.canvas.drawPoint(c,i.pointStyle,s,l,u,i.rotation)}else c.fillRect(h.leftForLtr(t,m),e,m,p),0!==o&&c.strokeRect(h.leftForLtr(t,m),e,m,p);c.restore()}}(w,k,e),v[i].left=h.leftForLtr(w,v[i].width),v[i].top=k,function(t,e,n,i){var a=p/2,r=h.xPlus(t,m+a),o=e+a;c.fillText(n.text,r,o),n.hidden&&(c.beginPath(),c.lineWidth=2,c.moveTo(r,o),c.lineTo(h.xPlus(r,i),o),c.stroke())}(w,k,e,f),x?d.x+=g+n.padding:d.y+=y})),H.rtl.restoreTextDirection(t.ctx,e.textDirection)}},_getLegendItemAt:function(t,e){var n,i,a,r=this;if(t>=r.left&&t<=r.right&&e>=r.top&&e<=r.bottom)for(a=r.legendHitBoxes,n=0;n=(i=a[n]).left&&t<=i.left+i.width&&e>=i.top&&e<=i.top+i.height)return r.legendItems[n];return null},handleEvent:function(t){var e,n=this,i=n.options,a="mouseup"===t.type?"click":t.type;if("mousemove"===a){if(!i.onHover&&!i.onLeave)return}else{if("click"!==a)return;if(!i.onClick)return}e=n._getLegendItemAt(t.x,t.y),"click"===a?e&&i.onClick&&i.onClick.call(n,t.native,e):(i.onLeave&&e!==n._hoveredItem&&(n._hoveredItem&&i.onLeave.call(n,t.native,n._hoveredItem),n._hoveredItem=e),i.onHover&&e&&i.onHover.call(n,t.native,e))}});function Di(t,e){var n=new Ai({ctx:t.ctx,options:e,chart:t});pe.configure(t,n,e),pe.addBox(t,n),t.legend=n}var Ti={id:"legend",_element:Ai,beforeInit:function(t){var e=t.options.legend;e&&Di(t,e)},beforeUpdate:function(t){var e=t.options.legend,n=t.legend;e?(H.mergeIf(e,N.global.legend),n?(pe.configure(t,n,e),n.options=e):Di(t,e)):n&&(pe.removeBox(t,n),delete t.legend)},afterEvent:function(t,e){var n=t.legend;n&&n.handleEvent(e)}},Ii=H.noop;N._set("global",{title:{display:!1,fontStyle:"bold",fullWidth:!0,padding:10,position:"top",text:"",weight:2e3}});var Fi=K.extend({initialize:function(t){H.extend(this,t),this.legendHitBoxes=[]},beforeUpdate:Ii,update:function(t,e,n){var i=this;return i.beforeUpdate(),i.maxWidth=t,i.maxHeight=e,i.margins=n,i.beforeSetDimensions(),i.setDimensions(),i.afterSetDimensions(),i.beforeBuildLabels(),i.buildLabels(),i.afterBuildLabels(),i.beforeFit(),i.fit(),i.afterFit(),i.afterUpdate(),i.minSize},afterUpdate:Ii,beforeSetDimensions:Ii,setDimensions:function(){var t=this;t.isHorizontal()?(t.width=t.maxWidth,t.left=0,t.right=t.width):(t.height=t.maxHeight,t.top=0,t.bottom=t.height),t.paddingLeft=0,t.paddingTop=0,t.paddingRight=0,t.paddingBottom=0,t.minSize={width:0,height:0}},afterSetDimensions:Ii,beforeBuildLabels:Ii,buildLabels:Ii,afterBuildLabels:Ii,beforeFit:Ii,fit:function(){var t,e=this,n=e.options,i=e.minSize={},a=e.isHorizontal();n.display?(t=(H.isArray(n.text)?n.text.length:1)*H.options._parseFont(n).lineHeight+2*n.padding,e.width=i.width=a?e.maxWidth:t,e.height=i.height=a?t:e.maxHeight):e.width=i.width=e.height=i.height=0},afterFit:Ii,isHorizontal:function(){var t=this.options.position;return"top"===t||"bottom"===t},draw:function(){var t=this,e=t.ctx,n=t.options;if(n.display){var i,a,r,o=H.options._parseFont(n),s=o.lineHeight,l=s/2+n.padding,u=0,d=t.top,h=t.left,c=t.bottom,f=t.right;e.fillStyle=H.valueOrDefault(n.fontColor,N.global.defaultFontColor),e.font=o.string,t.isHorizontal()?(a=h+(f-h)/2,r=d+l,i=f-h):(a="left"===n.position?h+l:f-l,r=d+(c-d)/2,i=c-d,u=Math.PI*("left"===n.position?-.5:.5)),e.save(),e.translate(a,r),e.rotate(u),e.textAlign="center",e.textBaseline="middle";var g=n.text;if(H.isArray(g))for(var p=0,m=0;m=0;i--){var a=t[i];if(e(a))return a}},H.isNumber=function(t){return!isNaN(parseFloat(t))&&isFinite(t)},H.almostEquals=function(t,e,n){return Math.abs(t-e)=t},H.max=function(t){return t.reduce((function(t,e){return isNaN(e)?t:Math.max(t,e)}),Number.NEGATIVE_INFINITY)},H.min=function(t){return t.reduce((function(t,e){return isNaN(e)?t:Math.min(t,e)}),Number.POSITIVE_INFINITY)},H.sign=Math.sign?function(t){return Math.sign(t)}:function(t){return 0===(t=+t)||isNaN(t)?t:t>0?1:-1},H.toRadians=function(t){return t*(Math.PI/180)},H.toDegrees=function(t){return t*(180/Math.PI)},H._decimalPlaces=function(t){if(H.isFinite(t)){for(var e=1,n=0;Math.round(t*e)/e!==t;)e*=10,n++;return n}},H.getAngleFromPoint=function(t,e){var n=e.x-t.x,i=e.y-t.y,a=Math.sqrt(n*n+i*i),r=Math.atan2(i,n);return r<-.5*Math.PI&&(r+=2*Math.PI),{angle:r,distance:a}},H.distanceBetweenPoints=function(t,e){return Math.sqrt(Math.pow(e.x-t.x,2)+Math.pow(e.y-t.y,2))},H.aliasPixel=function(t){return t%2==0?0:.5},H._alignPixel=function(t,e,n){var i=t.currentDevicePixelRatio,a=n/2;return Math.round((e-a)*i)/i+a},H.splineCurve=function(t,e,n,i){var a=t.skip?e:t,r=e,o=n.skip?e:n,s=Math.sqrt(Math.pow(r.x-a.x,2)+Math.pow(r.y-a.y,2)),l=Math.sqrt(Math.pow(o.x-r.x,2)+Math.pow(o.y-r.y,2)),u=s/(s+l),d=l/(s+l),h=i*(u=isNaN(u)?0:u),c=i*(d=isNaN(d)?0:d);return{previous:{x:r.x-h*(o.x-a.x),y:r.y-h*(o.y-a.y)},next:{x:r.x+c*(o.x-a.x),y:r.y+c*(o.y-a.y)}}},H.EPSILON=Number.EPSILON||1e-14,H.splineCurveMonotone=function(t){var e,n,i,a,r,o,s,l,u,d=(t||[]).map((function(t){return{model:t._model,deltaK:0,mK:0}})),h=d.length;for(e=0;e0?d[e-1]:null,(a=e0?d[e-1]:null,a=e=t.length-1?t[0]:t[e+1]:e>=t.length-1?t[t.length-1]:t[e+1]},H.previousItem=function(t,e,n){return n?e<=0?t[t.length-1]:t[e-1]:e<=0?t[0]:t[e-1]},H.niceNum=function(t,e){var n=Math.floor(H.log10(t)),i=t/Math.pow(10,n);return(e?i<1.5?1:i<3?2:i<7?5:10:i<=1?1:i<=2?2:i<=5?5:10)*Math.pow(10,n)},H.requestAnimFrame="undefined"==typeof window?function(t){t()}:window.requestAnimationFrame||window.webkitRequestAnimationFrame||window.mozRequestAnimationFrame||window.oRequestAnimationFrame||window.msRequestAnimationFrame||function(t){return window.setTimeout(t,1e3/60)},H.getRelativePosition=function(t,e){var n,i,a=t.originalEvent||t,r=t.target||t.srcElement,o=r.getBoundingClientRect(),s=a.touches;s&&s.length>0?(n=s[0].clientX,i=s[0].clientY):(n=a.clientX,i=a.clientY);var l=parseFloat(H.getStyle(r,"padding-left")),u=parseFloat(H.getStyle(r,"padding-top")),d=parseFloat(H.getStyle(r,"padding-right")),h=parseFloat(H.getStyle(r,"padding-bottom")),c=o.right-o.left-l-d,f=o.bottom-o.top-u-h;return{x:n=Math.round((n-o.left-l)/c*r.width/e.currentDevicePixelRatio),y:i=Math.round((i-o.top-u)/f*r.height/e.currentDevicePixelRatio)}},H.getConstraintWidth=function(t){return n(t,"max-width","clientWidth")},H.getConstraintHeight=function(t){return n(t,"max-height","clientHeight")},H._calculatePadding=function(t,e,n){return(e=H.getStyle(t,e)).indexOf("%")>-1?n*parseInt(e,10)/100:parseInt(e,10)},H._getParentNode=function(t){var e=t.parentNode;return e&&"[object ShadowRoot]"===e.toString()&&(e=e.host),e},H.getMaximumWidth=function(t){var e=H._getParentNode(t);if(!e)return t.clientWidth;var n=e.clientWidth,i=n-H._calculatePadding(e,"padding-left",n)-H._calculatePadding(e,"padding-right",n),a=H.getConstraintWidth(t);return isNaN(a)?i:Math.min(i,a)},H.getMaximumHeight=function(t){var e=H._getParentNode(t);if(!e)return t.clientHeight;var n=e.clientHeight,i=n-H._calculatePadding(e,"padding-top",n)-H._calculatePadding(e,"padding-bottom",n),a=H.getConstraintHeight(t);return isNaN(a)?i:Math.min(i,a)},H.getStyle=function(t,e){return t.currentStyle?t.currentStyle[e]:document.defaultView.getComputedStyle(t,null).getPropertyValue(e)},H.retinaScale=function(t,e){var n=t.currentDevicePixelRatio=e||"undefined"!=typeof window&&window.devicePixelRatio||1;if(1!==n){var i=t.canvas,a=t.height,r=t.width;i.height=a*n,i.width=r*n,t.ctx.scale(n,n),i.style.height||i.style.width||(i.style.height=a+"px",i.style.width=r+"px")}},H.fontString=function(t,e,n){return e+" "+t+"px "+n},H.longestText=function(t,e,n,i){var a=(i=i||{}).data=i.data||{},r=i.garbageCollect=i.garbageCollect||[];i.font!==e&&(a=i.data={},r=i.garbageCollect=[],i.font=e),t.font=e;var o,s,l,u,d,h=0,c=n.length;for(o=0;on.length){for(o=0;oi&&(i=r),i},H.numberOfLabelLines=function(t){var e=1;return H.each(t,(function(t){H.isArray(t)&&t.length>e&&(e=t.length)})),e},H.color=_?function(t){return t instanceof CanvasGradient&&(t=N.global.defaultColor),_(t)}:function(t){return console.error("Color.js not found!"),t},H.getHoverColor=function(t){return t instanceof CanvasPattern||t instanceof CanvasGradient?t:H.color(t).saturate(.5).darken(.1).rgbString()}}(),en._adapters=rn,en.Animation=$,en.animationService=J,en.controllers=Jt,en.DatasetController=it,en.defaults=N,en.Element=K,en.elements=kt,en.Interaction=re,en.layouts=pe,en.platform=Oe,en.plugins=Le,en.Scale=yn,en.scaleService=Re,en.Ticks=on,en.Tooltip=Ye,en.helpers.each(fi,(function(t,e){en.scaleService.registerScaleType(e,t,t._defaults)})),Li)Li.hasOwnProperty(Bi)&&en.plugins.register(Li[Bi]);en.platform.initialize();var Ei=en;return"undefined"!=typeof window&&(window.Chart=en),en.Chart=en,en.Legend=Li.legend._element,en.Title=Li.title._element,en.pluginService=en.plugins,en.PluginBase=en.Element.extend({}),en.canvasHelpers=en.helpers.canvas,en.layoutService=en.layouts,en.LinearScaleBase=Cn,en.helpers.each(["Bar","Bubble","Doughnut","Line","PolarArea","Radar","Scatter"],(function(t){en[t]=function(e,n){return new en(e,en.helpers.merge(n||{},{type:t.charAt(0).toLowerCase()+t.slice(1)}))}})),Ei})); From 9746a8427c82e43b7bf905ccbff4ba8420d0eca5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 May 2021 22:04:14 -0500 Subject: [PATCH 0088/2168] Use adafruit/Adafruit NeoPixel@~1.8.0 --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index 6fa74a343f..586af1653f 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -27,7 +27,7 @@ HAS_TMC26X = TMC26XStepper=https://github.com/trinam src_filter=+ HAS_L64XX = Arduino-L6470@0.8.0 src_filter=+ + + + -NEOPIXEL_LED = Adafruit NeoPixel@1.5.0 +NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 From 026431679747ff972be14e8de8433c0d2e20326e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 May 2021 02:59:54 -0500 Subject: [PATCH 0089/2168] Fix L64xx init for Z4 --- Marlin/src/module/stepper/L64xx.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/module/stepper/L64xx.cpp b/Marlin/src/module/stepper/L64xx.cpp index 3e2bf09446..004e17a3fd 100644 --- a/Marlin/src/module/stepper/L64xx.cpp +++ b/Marlin/src/module/stepper/L64xx.cpp @@ -196,6 +196,9 @@ void L64XX_Marlin::init_to_defaults() { #if AXIS_IS_L64XX(Z3) L6470_INIT_CHIP(Z3); #endif + #if AXIS_IS_L64XX(Z4) + L6470_INIT_CHIP(Z4); + #endif #if AXIS_IS_L64XX(E0) L6470_INIT_CHIP(E0); #endif From e5dc2c53215020cd2c2caeb519a51d4bd430ecc0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 May 2021 08:30:16 -0500 Subject: [PATCH 0090/2168] Simplify macro expansion with recursion (#21859) --- Marlin/src/core/macros.h | 36 +++----- Marlin/src/core/serial.h | 164 +++++++-------------------------- Marlin/src/module/settings.cpp | 4 +- 3 files changed, 51 insertions(+), 153 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index b026af1187..34d9e530ca 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -301,8 +301,12 @@ #define HYPOT(x,y) SQRT(HYPOT2(x,y)) // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments -#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT -#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) +#define _NUM_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT +#define NUM_ARGS(V...) _NUM_ARGS(0,V,40,39,38,37,36,35,34,33,32,31,30,29,28,27,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + +// Use TWO_ARGS(__VA_ARGS__) to get whether there are 1, 2, or >2 arguments +#define _TWO_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT +#define TWO_ARGS(V...) _TWO_ARGS(0,V,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,2,1,0) #ifdef __cplusplus @@ -414,31 +418,19 @@ #else - #define MIN_2(a,b) ((a)<(b)?(a):(b)) - #define MIN_3(a,V...) MIN_2(a,MIN_2(V)) - #define MIN_4(a,V...) MIN_2(a,MIN_3(V)) - #define MIN_5(a,V...) MIN_2(a,MIN_4(V)) - #define MIN_6(a,V...) MIN_2(a,MIN_5(V)) - #define MIN_7(a,V...) MIN_2(a,MIN_6(V)) - #define MIN_8(a,V...) MIN_2(a,MIN_7(V)) - #define MIN_9(a,V...) MIN_2(a,MIN_8(V)) - #define MIN_10(a,V...) MIN_2(a,MIN_9(V)) #define __MIN_N(N,V...) MIN_##N(V) #define _MIN_N(N,V...) __MIN_N(N,V) - #define _MIN(V...) _MIN_N(NUM_ARGS(V), V) + #define _MIN_N_REF() _MIN_N + #define _MIN(V...) EVAL(_MIN_N(TWO_ARGS(V),V)) + #define MIN_2(a,b) ((a)<(b)?(a):(b)) + #define MIN_3(a,V...) MIN_2(a,DEFER2(_MIN_N_REF)()(TWO_ARGS(V),V)) - #define MAX_2(a,b) ((a)>(b)?(a):(b)) - #define MAX_3(a,V...) MAX_2(a,MAX_2(V)) - #define MAX_4(a,V...) MAX_2(a,MAX_3(V)) - #define MAX_5(a,V...) MAX_2(a,MAX_4(V)) - #define MAX_6(a,V...) MAX_2(a,MAX_5(V)) - #define MAX_7(a,V...) MAX_2(a,MAX_6(V)) - #define MAX_8(a,V...) MAX_2(a,MAX_7(V)) - #define MAX_9(a,V...) MAX_2(a,MAX_8(V)) - #define MAX_10(a,V...) MAX_2(a,MAX_9(V)) #define __MAX_N(N,V...) MAX_##N(V) #define _MAX_N(N,V...) __MAX_N(N,V) - #define _MAX(V...) _MAX_N(NUM_ARGS(V), V) + #define _MAX_N_REF() _MAX_N + #define _MAX(V...) EVAL(_MAX_N(TWO_ARGS(V),V)) + #define MAX_2(a,b) ((a)>(b)?(a):(b)) + #define MAX_3(a,V...) MAX_2(a,DEFER2(_MAX_N_REF)()(TWO_ARGS(V),V)) #endif diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 5406bb3a7d..c8024f4b8c 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -182,139 +182,45 @@ inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } // Print a single PROGMEM string to serial void serialprintPGM(PGM_P str); -// SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything -// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). -#define __SEP_N(N,V...) _SEP_##N(V) -#define _SEP_N(N,V...) __SEP_N(N,V) -#define _SEP_1(PRE) SERIAL_ECHOPGM(PRE) -#define _SEP_2(PRE,V) serial_echopair_PGM(PSTR(PRE),V) -#define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0) -#define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0) -#define _SEP_5(a,b,V...) do{ _SEP_2(a,b); _SEP_3(V); }while(0) -#define _SEP_6(a,b,V...) do{ _SEP_2(a,b); _SEP_4(V); }while(0) -#define _SEP_7(a,b,V...) do{ _SEP_2(a,b); _SEP_5(V); }while(0) -#define _SEP_8(a,b,V...) do{ _SEP_2(a,b); _SEP_6(V); }while(0) -#define _SEP_9(a,b,V...) do{ _SEP_2(a,b); _SEP_7(V); }while(0) -#define _SEP_10(a,b,V...) do{ _SEP_2(a,b); _SEP_8(V); }while(0) -#define _SEP_11(a,b,V...) do{ _SEP_2(a,b); _SEP_9(V); }while(0) -#define _SEP_12(a,b,V...) do{ _SEP_2(a,b); _SEP_10(V); }while(0) -#define _SEP_13(a,b,V...) do{ _SEP_2(a,b); _SEP_11(V); }while(0) -#define _SEP_14(a,b,V...) do{ _SEP_2(a,b); _SEP_12(V); }while(0) -#define _SEP_15(a,b,V...) do{ _SEP_2(a,b); _SEP_13(V); }while(0) -#define _SEP_16(a,b,V...) do{ _SEP_2(a,b); _SEP_14(V); }while(0) -#define _SEP_17(a,b,V...) do{ _SEP_2(a,b); _SEP_15(V); }while(0) -#define _SEP_18(a,b,V...) do{ _SEP_2(a,b); _SEP_16(V); }while(0) -#define _SEP_19(a,b,V...) do{ _SEP_2(a,b); _SEP_17(V); }while(0) -#define _SEP_20(a,b,V...) do{ _SEP_2(a,b); _SEP_18(V); }while(0) -#define _SEP_21(a,b,V...) do{ _SEP_2(a,b); _SEP_19(V); }while(0) -#define _SEP_22(a,b,V...) do{ _SEP_2(a,b); _SEP_20(V); }while(0) -#define _SEP_23(a,b,V...) do{ _SEP_2(a,b); _SEP_21(V); }while(0) -#define _SEP_24(a,b,V...) do{ _SEP_2(a,b); _SEP_22(V); }while(0) +// +// SERIAL_ECHOPAIR... macros are used to output string-value pairs. +// -#define SERIAL_ECHOPAIR(V...) _SEP_N(NUM_ARGS(V),V) +// Print up to 20 pairs of values. Odd elements must be literal strings. +#define __SEP_N(N,V...) _SEP_##N(V) +#define _SEP_N(N,V...) __SEP_N(N,V) +#define _SEP_N_REF() _SEP_N +#define _SEP_1(s) SERIAL_ECHOPGM(s); +#define _SEP_2(s,v) serial_echopair_PGM(PSTR(s),v); +#define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOPAIR(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) -// Print up to 12 pairs of values. Odd elements must be PSTR pointers. -#define __SEP_N_P(N,V...) _SEP_##N##_P(V) -#define _SEP_N_P(N,V...) __SEP_N_P(N,V) -#define _SEP_1_P(PRE) serialprintPGM(PRE) -#define _SEP_2_P(PRE,V) serial_echopair_PGM(PRE,V) -#define _SEP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0) -#define _SEP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_2_P(V); }while(0) -#define _SEP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_3_P(V); }while(0) -#define _SEP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_4_P(V); }while(0) -#define _SEP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_5_P(V); }while(0) -#define _SEP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_6_P(V); }while(0) -#define _SEP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_7_P(V); }while(0) -#define _SEP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_8_P(V); }while(0) -#define _SEP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_9_P(V); }while(0) -#define _SEP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_10_P(V); }while(0) -#define _SEP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_11_P(V); }while(0) -#define _SEP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_12_P(V); }while(0) -#define _SEP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_13_P(V); }while(0) -#define _SEP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_14_P(V); }while(0) -#define _SEP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_15_P(V); }while(0) -#define _SEP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_16_P(V); }while(0) -#define _SEP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_17_P(V); }while(0) -#define _SEP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_18_P(V); }while(0) -#define _SEP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_19_P(V); }while(0) -#define _SEP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_20_P(V); }while(0) -#define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0) -#define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0) +// Print up to 20 pairs of values followed by newline. Odd elements must be literal strings. +#define __SELP_N(N,V...) _SELP_##N(V) +#define _SELP_N(N,V...) __SELP_N(N,V) +#define _SELP_N_REF() _SELP_N +#define _SELP_1(s) SERIAL_ECHOLNPGM(s); +#define _SELP_2(s,v) serial_echopair_PGM(PSTR(s),v); SERIAL_EOL(); +#define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOLNPAIR(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) -// SERIAL_ECHOPAIR_P is used to output a key value pair. Unlike SERIAL_ECHOPAIR, the key must be a PGM string already and the value can be anything -#define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V) +// Print up to 20 pairs of values. Odd elements must be PSTR pointers. +#define __SEP_N_P(N,V...) _SEP_##N##_P(V) +#define _SEP_N_P(N,V...) __SEP_N_P(N,V) +#define _SEP_N_P_REF() _SEP_N_P +#define _SEP_1_P(s) serialprintPGM(s); +#define _SEP_2_P(s,v) serial_echopair_PGM(s,v); +#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER(_SEP_N_P_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOPAIR_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) -// Print up to 12 pairs of values followed by newline -#define __SELP_N(N,V...) _SELP_##N(V) -#define _SELP_N(N,V...) __SELP_N(N,V) -#define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE) -#define _SELP_2(PRE,V) do{ serial_echopair_PGM(PSTR(PRE),V); SERIAL_EOL(); }while(0) -#define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0) -#define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0) -#define _SELP_5(a,b,V...) do{ _SEP_2(a,b); _SELP_3(V); }while(0) -#define _SELP_6(a,b,V...) do{ _SEP_2(a,b); _SELP_4(V); }while(0) -#define _SELP_7(a,b,V...) do{ _SEP_2(a,b); _SELP_5(V); }while(0) -#define _SELP_8(a,b,V...) do{ _SEP_2(a,b); _SELP_6(V); }while(0) -#define _SELP_9(a,b,V...) do{ _SEP_2(a,b); _SELP_7(V); }while(0) -#define _SELP_10(a,b,V...) do{ _SEP_2(a,b); _SELP_8(V); }while(0) -#define _SELP_11(a,b,V...) do{ _SEP_2(a,b); _SELP_9(V); }while(0) -#define _SELP_12(a,b,V...) do{ _SEP_2(a,b); _SELP_10(V); }while(0) -#define _SELP_13(a,b,V...) do{ _SEP_2(a,b); _SELP_11(V); }while(0) -#define _SELP_14(a,b,V...) do{ _SEP_2(a,b); _SELP_12(V); }while(0) -#define _SELP_15(a,b,V...) do{ _SEP_2(a,b); _SELP_13(V); }while(0) -#define _SELP_16(a,b,V...) do{ _SEP_2(a,b); _SELP_14(V); }while(0) -#define _SELP_17(a,b,V...) do{ _SEP_2(a,b); _SELP_15(V); }while(0) -#define _SELP_18(a,b,V...) do{ _SEP_2(a,b); _SELP_16(V); }while(0) -#define _SELP_19(a,b,V...) do{ _SEP_2(a,b); _SELP_17(V); }while(0) -#define _SELP_20(a,b,V...) do{ _SEP_2(a,b); _SELP_18(V); }while(0) -#define _SELP_21(a,b,V...) do{ _SEP_2(a,b); _SELP_19(V); }while(0) -#define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0) -#define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0) -#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0) -#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(0) -#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(0) -#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(0) -#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(0) -#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(0) -#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(0) // Eat two args, pass the rest up - -#define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) - -// Print up to 12 pairs of values followed by newline -#define __SELP_N_P(N,V...) _SELP_##N##_P(V) -#define _SELP_N_P(N,V...) __SELP_N_P(N,V) -#define _SELP_1_P(PRE) serialprintPGM(PRE) -#define _SELP_2_P(PRE,V) do{ serial_echopair_PGM(PRE,V); SERIAL_EOL(); }while(0) -#define _SELP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0) -#define _SELP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_2_P(V); }while(0) -#define _SELP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_3_P(V); }while(0) -#define _SELP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_4_P(V); }while(0) -#define _SELP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_5_P(V); }while(0) -#define _SELP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_6_P(V); }while(0) -#define _SELP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_7_P(V); }while(0) -#define _SELP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_8_P(V); }while(0) -#define _SELP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_9_P(V); }while(0) -#define _SELP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_10_P(V); }while(0) -#define _SELP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_11_P(V); }while(0) -#define _SELP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_12_P(V); }while(0) -#define _SELP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_13_P(V); }while(0) -#define _SELP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_14_P(V); }while(0) -#define _SELP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_15_P(V); }while(0) -#define _SELP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_16_P(V); }while(0) -#define _SELP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_17_P(V); }while(0) -#define _SELP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_18_P(V); }while(0) -#define _SELP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_19_P(V); }while(0) -#define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0) -#define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0) -#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0) -#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(0) -#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(0) -#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(0) -#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(0) -#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(0) -#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(0) // Eat two args, pass the rest up - -#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V) +// Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers. +#define __SELP_N_P(N,V...) _SELP_##N##_P(V) +#define _SELP_N_P(N,V...) __SELP_N_P(N,V) +#define _SELP_N_P_REF() _SELP_N_P +#define _SELP_1_P(s) { serialprintPGM(s); SERIAL_EOL(); } +#define _SELP_2_P(s,v) { serial_echopair_PGM(s,v); SERIAL_EOL(); } +#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER(_SELP_N_P_REF)()(TWO_ARGS(V),V); } +#define SERIAL_ECHOLNPAIR_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) #ifdef AllowDifferentTypeInList diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 07253c117a..35b55c82f9 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3880,8 +3880,8 @@ void MarlinSettings::reset() { say_M603(forReplay); SERIAL_ECHOLNPAIR("L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length)); #else - #define _ECHO_603(N) do{ say_M603(forReplay); SERIAL_ECHOLNPAIR("T" STRINGIFY(N) " L", LINEAR_UNIT(fc_settings[N].load_length), " U", LINEAR_UNIT(fc_settings[N].unload_length)); }while(0); - REPEAT(EXTRUDERS, _ECHO_603) + auto echo_603 = [](const bool f, const uint8_t n) { say_M603(f); SERIAL_ECHOLNPAIR("T", n, " L", LINEAR_UNIT(fc_settings[n].load_length), " U", LINEAR_UNIT(fc_settings[n].unload_length)); }; + LOOP_L_N(i, EXTRUDERS) echo_603(forReplay, i); #endif #endif From a42760d38a65c58178af7840ba57298cd0b7d31a Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Tue, 11 May 2021 12:44:54 -0300 Subject: [PATCH 0091/2168] BTT SKR Mini E3 for HAL/STM32 (#21488) --- .github/workflows/test-builds.yml | 1 + Marlin/src/HAL/STM32/HAL.cpp | 6 + Marlin/src/HAL/STM32F1/HAL.cpp | 2 +- Marlin/src/pins/pins.h | 10 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 13 +- .../PlatformIO/scripts/stm32_bootloader.py | 7 +- .../variants/MARLIN_F103Rx/PeripheralPins.c | 423 ++++++++++++++++++ .../variants/MARLIN_F103Rx/PinNamesVar.h | 30 ++ .../variants/MARLIN_F103Rx/ldscript.ld | 200 +++++++++ .../variants/MARLIN_F103Rx/variant.cpp | 152 +++++++ .../variants/MARLIN_F103Rx/variant.h | 161 +++++++ buildroot/tests/STM32F103RC_btt_USB_stm32 | 17 + buildroot/tests/STM32F103RC_btt_stm32 | 20 + ini/stm32f1.ini | 50 +++ 14 files changed, 1082 insertions(+), 10 deletions(-) create mode 100755 buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h create mode 100755 buildroot/tests/STM32F103RC_btt_USB_stm32 create mode 100755 buildroot/tests/STM32F103RC_btt_stm32 diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 6fdd7d67bc..979f56cb6a 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -72,6 +72,7 @@ jobs: # STM32 (ST) Environments + - STM32F103RC_btt_stm32 - STM32F407VE_black - STM32F401VE_STEVAL - BIGTREE_BTT002 diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 3bb12fd9e0..e09b52f7db 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -96,6 +96,12 @@ void HAL_init() { #if HAS_SD_HOST_DRIVE MSC_SD_init(); // Enable USB SD card access #endif + + #if PIN_EXISTS(USB_CONNECT) + OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection + delay(1000); // Give OS time to notice + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + #endif } // HAL idle task diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 2efea4f001..dcfdc88555 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -293,7 +293,7 @@ void HAL_init() { #if PIN_EXISTS(USB_CONNECT) OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection delay(1000); // Give OS time to notice - OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); #endif TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler } diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index d38dc595f2..2a70e571af 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -511,15 +511,15 @@ #elif MB(MKS_ROBIN_E3P) #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 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 "stm32f1/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 + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 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 "stm32f1/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 + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V2_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_MZ_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_E3_DIP) #include "stm32f1/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(BTT_SKR_CR6) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index bab662d1be..58adc5853a 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -21,7 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) +#if NOT_TARGET(__STM32F1__, STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -279,5 +279,14 @@ #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif -#define ONBOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card + +#define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI for SD on STM32 (for now) +#if ENABLED(CUSTOM_SPI_PINS) + #define ENABLE_SPI1 + #define SDSS ONBOARD_SD_CS_PIN + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 +#endif diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py index 4e7d2d9c07..b2b5daadb6 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -19,9 +19,12 @@ def noencrypt(source, target, env): # if 'offset' in board.get("build").keys(): LD_FLASH_OFFSET = board.get("build.offset") - marlin.relocate_vtab(LD_FLASH_OFFSET) + # Flash size + maximum_flash_size = int(board.get("upload.maximum_size") / 1024) + marlin.replace_define('STM32_FLASH_SIZE', maximum_flash_size) + # Get upload.maximum_ram_size (defined by /buildroot/share/PlatformIO/boards/VARIOUS.json) maximum_ram_size = board.get("upload.maximum_ram_size") @@ -35,6 +38,6 @@ if 'offset' in board.get("build").keys(): # Only copy the file if there's no encrypt # board_keys = board.get("build").keys() -if 'firmware' in board_keys and not 'encrypt' in board_keys: +if 'firmware' in board_keys and ('encrypt' not in board_keys or board.get("build.encrypt") == 'No'): import marlin marlin.add_post_action(noencrypt) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c new file mode 100755 index 0000000000..56ae00b41b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c @@ -0,0 +1,423 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F103R(F-G)Tx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Note: Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 +#endif + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 +#endif + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 +#endif + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 +#endif + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 +#endif + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 +#endif + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 +#endif + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 +#endif + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SCL[] = { + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_I2C1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM2_CH1 + // {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 +#endif + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 + // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 +#endif + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 + // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 +#if defined(STM32F103xG) + // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 +#endif + // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 +#else + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 +#endif +#if defined(STM32F103xG) + // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 +#endif + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xG) + // {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 +#endif + // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N +#else + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N +#endif +#if defined(STM32F103xG) + // {PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 +#endif + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 + // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 + // {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 + // {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 + // {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 + // {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 + // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N +#endif + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N + // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N +#endif + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 + // {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 +#endif +#if defined(STM32F103xG) + // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 +#endif +#if defined(STM32F103xG) + // {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 +#endif + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 + // {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 + // {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N +#if defined(STM32F103xG) + // {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 +#endif + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N +#if defined(STM32F103xG) + // {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 +#endif + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 +#endif + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 +#else + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 +#endif + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + // {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 +#endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xB) + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART1_ENABLE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PC_11, UART4, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif +#if defined(STM32F103xB) + {PC_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif +#if defined(STM32F103xE) || defined(STM32F103xG) + {PD_2, UART5, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RTS[] = { + {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_CTS[] = { + {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_USART3_PARTIAL)}, +#endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#if defined(STM32F103xE) || defined(STM32F103xG) + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#else + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_SPI1_ENABLE)}, +#endif +#if defined(STM32F103xB) || defined(STM32F103xE) || defined(STM32F103xG) + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +#endif + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {PA_11, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, + {PB_8, CAN1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_CAN1_2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_TD[] = { + {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, + {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_CAN1_2)}, + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB[] = { + {PA_11, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DM + {PA_12, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_FS *** + +//*** No USB_OTG_HS *** + +//*** SD *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 + {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 + {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 + {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h new file mode 100644 index 0000000000..d9e759f5d0 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h @@ -0,0 +1,30 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + USB_DM = PA_11, + USB_DP = PA_12, +#endif \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld new file mode 100644 index 0000000000..80bb1d2bb7 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld @@ -0,0 +1,200 @@ +/* +****************************************************************************** +** + +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32F103R(8/B/C/ETx Device from STM32F1 series +** 64/128/256/512Kbytes FLASH +** 20/20/48/64Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed as is without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of "RAM" Ram type memory */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp new file mode 100644 index 0000000000..4d815a34d7 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.cpp @@ -0,0 +1,152 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +const PinName digitalPin[] = { + PA_0, + PA_1, + PA_2, + PA_3, + PA_4, + PA_5, + PA_6, + PA_7, + PA_8, + PA_9, // RXD + PA_10, // TXD + PA_11, // USB D- + PA_12, // USB D+ + PA_13, // JTDI + PA_14, // JTCK + PA_15, + PB_0, + PB_1, + PB_2, + PB_3, // JTDO + PB_4, // JTRST + PB_5, + PB_6, + PB_7, + PB_8, + PB_9, + PB_10, + PB_11, // LED + PB_12, + PB_13, + PB_14, + PB_15, + PC_0, + PC_1, + PC_2, + PC_3, + PC_4, + PC_5, + PC_6, + PC_7, + PC_8, + PC_9, + PC_10, + PC_11, + PC_12, + PC_13, + PC_14, // OSC32_1 + PC_15, // OSC32_2 + PD_0, // OSCIN + PD_1, // OSCOUT + PD_2 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37 // A15, PC5 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + + /* Initializes the CPU, AHB and APB busses clocks */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + Error_Handler(); + } + /* Initializes the CPU, AHB and APB busses clocks */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + Error_Handler(); + } + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) { + Error_Handler(); + } +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h new file mode 100644 index 0000000000..7dcbb793d0 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -0,0 +1,161 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + + +// * = F103R8-B-C-D-E-F-G +// ** = F103RC-D-E-F-G +// | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PA0 PIN_A0 // | 0 | A0 | | | | | +#define PA1 PIN_A1 // | 1 | A1 | | | | | +#define PA2 PIN_A2 // | 2 | A2 | USART2_TX | | | | +#define PA3 PIN_A3 // | 2 | A2, DAC_OUT1** | USART2_RX | | | | +#define PA4 PIN_A4 // | 4 | A4, DAC_OUT2** | | | SPI1_SS | | +#define PA5 PIN_A5 // | 5 | A5 | | | SPI1_SCK | | +#define PA6 PIN_A6 // | 6 | A6 | | | SPI1_MISO | | +#define PA7 PIN_A7 // | 7 | A7 | | | SPI1_MOSI | | +#define PA8 8 // | 8 | | | | | | +#define PA9 9 // | 9 | | USART1_TX | | | | +#define PA10 10 // | 10 | | USART1_RX | | | | +#define PA11 11 // | 11 | | | | | USB_DM | +#define PA12 12 // | 12 | | | | | USB_DP | +#define PA13 13 // | 13 | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | SPI1_SS/SPI3_SS** | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PB0 PIN_A8 // | 16 | A8 | | | | | +#define PB1 PIN_A9 // | 17 | A9 | | | | | +#define PB2 18 // | 18 | | | | | BOOT1 | +#define PB3 19 // | 19 | | | | SPI1_SCK/SPI3_SCK** | | +#define PB4 20 // | 20 | | | | SPI1_MISO/SPI3_MISO** | | +#define PB5 21 // | 21 | | | | SPI1_MOSI/SPI3_MOSI** | | +#define PB6 22 // | 22 | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | TWI1_SDA | | | +#define PB10 26 // | 26 | | USART3_TX* | TWI2_SCL* | | | +#define PB11 27 // | 27 | | USART3_RX* | TWI2_SDA* | | | +#define PB12 28 // | 28 | | | | SPI2_SS* | | +#define PB13 29 // | 29 | | | | SPI2_SCK* | | +#define PB14 30 // | 30 | | | | SPI2_MISO* | | +#define PB15 31 // | 31 | | | | SPI2_MOSI* | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PC0 PIN_A10 // | 32 | A10 | | | | | +#define PC1 PIN_A11 // | 33 | A11 | | | | | +#define PC2 PIN_A12 // | 34 | A12 | | | | | +#define PC3 PIN_A13 // | 35 | A13 | | | | | +#define PC4 PIN_A14 // | 36 | A14 | | | | | +#define PC5 PIN_A15 // | 37 | A15 | | | | | +#define PC6 38 // | 38 | | | | | | +#define PC7 39 // | 39 | | | | | | +#define PC8 40 // | 40 | | | | | | +#define PC9 41 // | 41 | | | | | | +#define PC10 42 // | 42 | | USART3_TX*/UART4_TX** | | | | +#define PC11 43 // | 43 | | USART3_RX*/UART4_RX** | | | | +#define PC12 44 // | 44 | | UART5_TX** | | | | +#define PC13 45 // | 45 | | | | | | +#define PC14 46 // | 46 | | | | | OSC32_IN | +#define PC15 47 // | 47 | | | | | OSC32_OUT | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PD0 48 // | 48 | | | | | OSC_IN | +#define PD1 49 // | 48 | | | | | OSC_OUT | +#define PD2 50 // | 50 | | UART5_RX** | | | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| + +// This must be a literal +#define NUM_DIGITAL_PINS 51 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PB11 +#endif +#define LED_GREEN LED_BUILTIN + +// On-board user button +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// Override default Arduino configuration +// SPI Definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definitions +#define PIN_WIRE_SDA PB7 +#define PIN_WIRE_SCL PB6 + +// Timer Definitions +#ifndef TIMER_TONE + #define TIMER_TONE TIM3 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM2 +#endif +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial1' instance +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +/* Extra HAL modules */ +#if defined(STM32F103xE) || defined(STM32F103xG) +#define HAL_DAC_MODULE_ENABLED +#endif + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #define SERIAL_PORT_MONITOR Serial + #define SERIAL_PORT_HARDWARE Serial1 +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/tests/STM32F103RC_btt_USB_stm32 b/buildroot/tests/STM32F103RC_btt_USB_stm32 new file mode 100755 index 0000000000..8381de0ea6 --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt_USB_stm32 @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 +exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_stm32 b/buildroot/tests/STM32F103RC_btt_stm32 new file mode 100755 index 0000000000..e76060aee8 --- /dev/null +++ b/buildroot/tests/STM32F103RC_btt_stm32 @@ -0,0 +1,20 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 SERIAL_PORT 1 SERIAL_PORT_2 -1 \ + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2209 E0_DRIVER_TYPE TMC2209 +opt_enable PINS_DEBUGGING Z_IDLE_HEIGHT + +exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" "$3" + +# clean up +restore_configs diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 7283adda4b..6a234bdc97 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -143,6 +143,56 @@ build_flags = ${env:STM32F103RC_btt_512K.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${env:STM32F103RC_btt_512K.lib_deps} USBComposite for STM32F1@0.91 +# +# STM32 HAL version of STM32F103RC_btt envs +# + +[env:STM32F103RC_stm32] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103RC +monitor_speed = 115200 +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.ldscript = ldscript.ld +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py + +[env:STM32F103RC_btt_stm32] +platform = ${common_stm32.platform} +extends = env:STM32F103RC_stm32 +build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 +board_build.offset = 0x7000 +board_build.encrypt = No +board_build.firmware = firmware.bin +board_upload.offset_address = 0x08007000 + +[env:STM32F103RC_btt_USB_stm32] +extends = env:STM32F103RC_btt_stm32 +platform = ${common_stm32.platform} +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip +build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC +build_flags = ${env:STM32F103RC_btt_stm32.build_flags} ${env:stm32_flash_drive.build_flags} + -DUSBCON + -DUSE_USBHOST_HS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSE_USB_HS_IN_FS + -DUSBD_USE_CDC_MSC + +[env:STM32F103RC_btt_512K_stm32] +platform = ${common_stm32.platform} +extends = env:STM32F103RC_btt_stm32 +board_upload.maximum_size = 524288 +build_flags = ${env:STM32F103RC_btt_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 + +[env:STM32F103RC_btt_512K_USB_stm32] +platform = ${common_stm32.platform} +extends = env:STM32F103RC_btt_USB_stm32 +board_upload.maximum_size = 524288 +build_flags = ${env:STM32F103RC_btt_USB_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 + # # STM32F103RE # From 398ce22c2ed16629ead07d8154f1d7f127adfbfc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 May 2021 04:05:18 -0500 Subject: [PATCH 0092/2168] :art: Better error message for bad array sizes --- Marlin/src/inc/SanityCheck.h | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c9aebe89ad..cac54cd1aa 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2804,23 +2804,30 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, sanity_arr_3[] = DEFAULT_MAX_ACCELERATION; #define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0) +#if HAS_MULTI_EXTRUDER + #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" +#elif EXTRUDERS == 0 + #define _EXTRA_NOTE " (Note: EXTRUDERS is set to 0.)" +#else + #define _EXTRA_NOTE "" +#endif static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); static_assert(COUNT(sanity_arr_2) >= XYZE, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), "DEFAULT_MAX_FEEDRATE values must be positive."); static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)"); +static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), @@ -2863,6 +2870,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #undef _ARR_TEST +#undef _EXTRA_NOTE #if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS." From 390878e78af3a0f07e2a1b2e784fc882e22edbd4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 May 2021 04:01:21 -0500 Subject: [PATCH 0093/2168] :art: Additional utility macros --- Marlin/src/core/macros.h | 38 ++++++++++++++++++++++ Marlin/src/gcode/feature/trinamic/M122.cpp | 3 +- Marlin/src/inc/Conditionals_LCD.h | 4 +-- Marlin/src/module/temperature.cpp | 2 +- 4 files changed, 43 insertions(+), 4 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 34d9e530ca..566087b76b 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -237,6 +237,38 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +#define CODE_9( A,B,C,D,E,F,G,H,I,...) A; B; C; D; E; F; G; H; I +#define CODE_8( A,B,C,D,E,F,G,H,...) A; B; C; D; E; F; G; H +#define CODE_7( A,B,C,D,E,F,G,...) A; B; C; D; E; F; G +#define CODE_6( A,B,C,D,E,F,...) A; B; C; D; E; F +#define CODE_5( A,B,C,D,E,...) A; B; C; D; E +#define CODE_4( A,B,C,D,...) A; B; C; D +#define CODE_3( A,B,C,...) A; B; C +#define CODE_2( A,B,...) A; B +#define CODE_1( A,...) A +#define _CODE_N(N,V...) CODE_##N(V) +#define CODE_N(N,V...) _CODE_N(N,V) + +#define GANG_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A B C D E F G H I J K L M N O P +#define GANG_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A B C D E F G H I J K L M N O +#define GANG_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A B C D E F G H I J K L M N +#define GANG_13(A,B,C,D,E,F,G,H,I,J,K,L,M...) A B C D E F G H I J K L M +#define GANG_12(A,B,C,D,E,F,G,H,I,J,K,L...) A B C D E F G H I J K L +#define GANG_11(A,B,C,D,E,F,G,H,I,J,K,...) A B C D E F G H I J K +#define GANG_10(A,B,C,D,E,F,G,H,I,J,...) A B C D E F G H I J +#define GANG_9( A,B,C,D,E,F,G,H,I,...) A B C D E F G H I +#define GANG_8( A,B,C,D,E,F,G,H,...) A B C D E F G H +#define GANG_7( A,B,C,D,E,F,G,...) A B C D E F G +#define GANG_6( A,B,C,D,E,F,...) A B C D E F +#define GANG_5( A,B,C,D,E,...) A B C D E +#define GANG_4( A,B,C,D,...) A B C D +#define GANG_3( A,B,C,...) A B C +#define GANG_2( A,B,...) A B +#define GANG_1( A,...) A +#define _GANG_N(N,V...) GANG_##N(V) +#define GANG_N(N,V...) _GANG_N(N,V) +#define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) + // Macros for initializing arrays #define LIST_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P #define LIST_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O @@ -254,10 +286,13 @@ #define LIST_3( A,B,C,...) A,B,C #define LIST_2( A,B,...) A,B #define LIST_1( A,...) A +#define LIST_0(...) #define _LIST_N(N,V...) LIST_##N(V) #define LIST_N(N,V...) _LIST_N(N,V) +#define LIST_N_1(N,K) _LIST_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) #define ARRAY_N(N,V...) { _LIST_N(N,V) } +#define ARRAY_N_1(N,K) { LIST_N_1(N,K) } #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) @@ -465,6 +500,9 @@ #define ADD8(N) ADD4(ADD4(N)) #define ADD9(N) ADD4(ADD5(N)) #define ADD10(N) ADD5(ADD5(N)) +#define SUM(A,B) _CAT(ADD,A)(B) +#define DOUBLE_(n) ADD##n(n) +#define DOUBLE(n) DOUBLE_(n) // Macros for subtracting #define DEC_0 0 diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 429638665f..d007044ea3 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -32,7 +32,8 @@ * M122: Debug TMC drivers */ void GcodeSuite::M122() { - xyze_bool_t print_axis = { false, false, false, false }; + xyze_bool_t print_axis = ARRAY_N_1(NUM_AXIS, false); + bool print_all = true; LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ed86c1bf65..42349b955e 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -617,9 +617,9 @@ // 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_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, 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 ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) #if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) #define DO_SWITCH_EXTRUDER 1 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 72d801652f..03c0195085 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -313,7 +313,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif #if ENABLED(ADAPTIVE_FAN_SLOWING) - uint8_t Temperature::fan_speed_scaler[FAN_COUNT] = ARRAY_N(FAN_COUNT, 128, 128, 128, 128, 128, 128, 128, 128); + uint8_t Temperature::fan_speed_scaler[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 128); #endif /** From 0c8a53e507fa792b114a89fe6902f4efe4ed2fe8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 May 2021 10:47:32 -0500 Subject: [PATCH 0094/2168] :art: Misc. code cleanup --- Marlin/src/core/serial.h | 4 ++-- Marlin/src/feature/dac/dac_mcp4728.cpp | 2 +- Marlin/src/feature/joystick.cpp | 7 +------ Marlin/src/gcode/motion/M290.cpp | 2 +- Marlin/src/module/delta.cpp | 2 +- Marlin/src/module/settings.cpp | 8 ++++---- Marlin/src/module/stepper.h | 2 +- Marlin/src/module/tool_change.cpp | 5 +---- 8 files changed, 12 insertions(+), 20 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index c8024f4b8c..5c08be5c92 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -210,7 +210,7 @@ void serialprintPGM(PGM_P str); #define _SEP_N_P_REF() _SEP_N_P #define _SEP_1_P(s) serialprintPGM(s); #define _SEP_2_P(s,v) serial_echopair_PGM(s,v); -#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER(_SEP_N_P_REF)()(TWO_ARGS(V),V); +#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOPAIR_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) // Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers. @@ -219,7 +219,7 @@ void serialprintPGM(PGM_P str); #define _SELP_N_P_REF() _SELP_N_P #define _SELP_1_P(s) { serialprintPGM(s); SERIAL_EOL(); } #define _SELP_2_P(s,v) { serial_echopair_PGM(s,v); SERIAL_EOL(); } -#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER(_SELP_N_P_REF)()(TWO_ARGS(V),V); } +#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } #define SERIAL_ECHOLNPAIR_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) #ifdef AllowDifferentTypeInList diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 4f33c4e050..2b57037d99 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -66,7 +66,7 @@ uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) { } /** - * Write all input resistor values to EEPROM using SequencialWrite method. + * Write all input resistor values to EEPROM using SequentialWrite method. * This will update both input register and EEPROM value * This will also write current Vref, PowerDown, Gain settings to EEPROM */ diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index 3dca2eb2e9..2cc61ec5a3 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -164,12 +164,7 @@ Joystick joystick; xyz_float_t move_dist{0}; float hypot2 = 0; LOOP_XYZ(i) if (norm_jog[i]) { - move_dist[i] = seg_time * norm_jog[i] * - #if ENABLED(EXTENSIBLE_UI) - manual_feedrate_mm_s[i]; - #else - planner.settings.max_feedrate_mm_s[i]; - #endif + move_dist[i] = seg_time * norm_jog[i] * TERN(EXTENSIBLE_UI, manual_feedrate_mm_s, planner.settings.max_feedrate_mm_s)[i]; hypot2 += sq(move_dist[i]); } diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 7cfab8d2db..7e5a017783 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -82,7 +82,7 @@ void GcodeSuite::M290() { const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2); babystep.add_mm(Z_AXIS, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (!parser.seen('P') || parser.value_bool()) mod_probe_offset(offs); + if (parser.boolval('P', true)) mod_probe_offset(offs); #endif } #endif diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index eb42bd1946..1be3df220f 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -271,7 +271,7 @@ void home_delta() { // Do this here all at once for Delta, because // XYZ isn't ABC. Applying this per-tower would // give the impression that they are the same. - LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i); + LOOP_ABC(i) set_axis_is_at_home((AxisEnum)i); sync_plan_position(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 35b55c82f9..9d65bbb744 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1072,7 +1072,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(tmc_stepper_current); - tmc_stepper_current_t tmc_stepper_current = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; + tmc_stepper_current_t tmc_stepper_current{0}; #if HAS_TRINAMIC_CONFIG #if AXIS_IS_TMC(X) @@ -1134,7 +1134,7 @@ void MarlinSettings::postprocess() { _FIELD_TEST(tmc_hybrid_threshold); #if ENABLED(HYBRID_THRESHOLD) - tmc_hybrid_threshold_t tmc_hybrid_threshold = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; + tmc_hybrid_threshold_t tmc_hybrid_threshold{0}; #if AXIS_HAS_STEALTHCHOP(X) tmc_hybrid_threshold.X = stepperX.get_pwm_thrs(); #endif @@ -1538,7 +1538,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummyf); #endif #else - for (uint8_t q = 4; q--;) EEPROM_READ(dummyf); + for (uint8_t q = XYZE; q--;) EEPROM_READ(dummyf); #endif EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); @@ -2256,7 +2256,7 @@ void MarlinSettings::postprocess() { const xyz_float_t &backlash_distance_mm = backlash.distance_mm; const uint8_t &backlash_correction = backlash.correction; #else - float backlash_distance_mm[XYZ]; + xyz_float_t backlash_distance_mm; uint8_t backlash_correction; #endif #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index ca1781fb9c..bbe8df146f 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -250,7 +250,7 @@ class Stepper { #ifndef PWM_MOTOR_CURRENT #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT #endif - #define MOTOR_CURRENT_COUNT 3 + #define MOTOR_CURRENT_COUNT XYZ #elif HAS_MOTOR_CURRENT_SPI static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT; #define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 0c5673b31c..559caa7f98 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -113,10 +113,7 @@ void move_extruder_servo(const uint8_t e) { planner.synchronize(); - #if EXTRUDERS & 1 - if (e < EXTRUDERS - 1) - #endif - { + if ((EXTRUDERS & 1) && e < EXTRUDERS - 1) { MOVE_SERVO(_SERVO_NR(e), servo_angles[_SERVO_NR(e)][e & 1]); safe_delay(500); } From 5353a1ed1a5081783aad3870dd8af23483aa5437 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 12 May 2021 01:01:39 +0000 Subject: [PATCH 0095/2168] [cron] Bump distribution date (2021-05-12) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7e63f30775..0ba593fde0 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 "2021-05-11" + #define STRING_DISTRIBUTION_DATE "2021-05-12" #endif /** From 0d629c80c7e218cbe07a85ba0d9bfeb49feb65c6 Mon Sep 17 00:00:00 2001 From: vyacheslav-shubin Date: Wed, 12 May 2021 10:17:06 +0300 Subject: [PATCH 0096/2168] =?UTF-8?q?=F0=9F=A9=B9=20G60-G61=20Save=20E=20p?= =?UTF-8?q?osition=20(#21810)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/pause/G60.cpp | 5 +-- Marlin/src/gcode/feature/pause/G61.cpp | 47 +++++++++++++++++++------- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/motion.h | 2 +- 4 files changed, 39 insertions(+), 17 deletions(-) diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 6f695b99a9..670ea2a58b 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -48,10 +48,11 @@ void GcodeSuite::G60() { #if ENABLED(SAVED_POSITIONS_DEBUG) const xyze_pos_t &pos = stored_position[slot]; - DEBUG_ECHOPAIR_F(STR_SAVED_POS " S", slot); + DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot); DEBUG_ECHOPAIR_F(" : X", pos.x); DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y); - DEBUG_ECHOLNPAIR_F_P(SP_Z_STR, pos.z); + DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z); + DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e); #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 9d5dcc060a..bb11464902 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -27,6 +27,10 @@ #include "../../../module/planner.h" #include "../../gcode.h" #include "../../../module/motion.h" +#include "../../../module/planner.h" + +#define DEBUG_OUT ENABLED(SAVED_POSITIONS_DEBUG) +#include "../../../core/debug_out.h" /** * G61: Return to saved position @@ -34,11 +38,16 @@ * F - Feedrate (optional) for the move back. * S - Slot # (0-based) to restore from (default 0). * X Y Z - Axes to restore. At least one is required. + * E - Restore extruder position + * + * If XYZE are not given, default restore uses the smart blocking move. */ void GcodeSuite::G61(void) { const uint8_t slot = parser.byteval('S'); + #define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT))) + #if SAVED_POSITIONS < 256 if (slot >= SAVED_POSITIONS) { SERIAL_ERROR_MSG(STR_INVALID_POS_SLOT STRINGIFY(SAVED_POSITIONS)); @@ -47,25 +56,37 @@ void GcodeSuite::G61(void) { #endif // No saved position? No axes being restored? - if (!TEST(saved_slots[slot >> 3], slot & 0x07) || !parser.seen("XYZ")) return; - - SERIAL_ECHOPAIR(STR_RESTORING_POS " S", slot); - LOOP_XYZ(i) { - destination[i] = parser.seen(XYZ_CHAR(i)) - ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) - : current_position[i]; - SERIAL_CHAR(' ', XYZ_CHAR(i)); - SERIAL_ECHO_F(destination[i]); - } - SERIAL_EOL(); + if (!TEST(saved_slots[slot >> 3], slot & 0x07)) return; // Apply any given feedrate over 0.0 feedRate_t saved_feedrate = feedrate_mm_s; const float fr = parser.linearval('F'); if (fr > 0.0) feedrate_mm_s = MMM_TO_MMS(fr); - // Move to the saved position - prepare_line_to_destination(); + if (!parser.seen_axis()) { + DEBUG_ECHOLNPGM("Default position restore"); + do_blocking_move_to(stored_position[slot], feedrate_mm_s); + SYNC_E(stored_position[slot].e); + } + else { + if (parser.seen("XYZ")) { + DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); + LOOP_XYZ(i) { + destination[i] = parser.seen(XYZ_CHAR(i)) + ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) + : current_position[i]; + DEBUG_CHAR(' ', XYZ_CHAR(i)); + DEBUG_ECHO_F(destination[i]); + } + DEBUG_EOL(); + // Move to the saved position + prepare_line_to_destination(); + } + if (parser.seen_test('E')) { + DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); + SYNC_E(stored_position[slot].e); + } + } feedrate_mm_s = saved_feedrate; } diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 7c0f8f404a..6ca8dc054c 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -102,7 +102,7 @@ xyze_pos_t destination; // {0} // G60/G61 Position Save and Return #if SAVED_POSITIONS uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; - xyz_pos_t stored_position[SAVED_POSITIONS]; + xyze_pos_t stored_position[SAVED_POSITIONS]; #endif // The active extruder (tool). Set with T command. diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 647b3af52a..c734fbdf34 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -45,7 +45,7 @@ extern xyze_pos_t current_position, // High-level current tool position // G60/G61 Position Save and Return #if SAVED_POSITIONS extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; - extern xyz_pos_t stored_position[SAVED_POSITIONS]; + extern xyze_pos_t stored_position[SAVED_POSITIONS]; #endif // Scratch space for a cartesian result From 10a1ff1622271bcbbb90dbe48a3e2e047ed2c9a2 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 12 May 2021 19:18:44 +1200 Subject: [PATCH 0097/2168] Fix compile error (#21877) --- Marlin/src/gcode/feature/trinamic/M122.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index d007044ea3..c338e48df4 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -32,7 +32,7 @@ * M122: Debug TMC drivers */ void GcodeSuite::M122() { - xyze_bool_t print_axis = ARRAY_N_1(NUM_AXIS, false); + xyze_bool_t print_axis = ARRAY_N_1(XYZE, false); bool print_all = true; LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } From de77dbedf1091e401942739b56e2145d1b37790f Mon Sep 17 00:00:00 2001 From: Elton Law Date: Wed, 12 May 2021 03:21:55 -0400 Subject: [PATCH 0098/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20G5=20IJ=20with?= =?UTF-8?q?=20Motion=20Mode=20(#21858)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/parser.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 7e75783b7a..896ff273cd 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -216,10 +216,9 @@ void GCodeParser::parse(char *p) { break; #if ENABLED(GCODE_MOTION_MODES) - #if ENABLED(ARC_SUPPORT) - case 'I' ... 'J': - if (motion_mode_codenum != 2 && motion_mode_codenum != 3) return; - #endif + case 'I' ... 'J': + if (motion_mode_codenum != 5 && \ + TERN1(ARC_SUPPORT, motion_mode_codenum != 2 && motion_mode_codenum != 3)) return; case 'Q': if (motion_mode_codenum != 5) return; case 'X' ... 'Z': case 'E' ... 'F': From 3734e8e02f2ad0f2f717798a264dd879eba0fc81 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 12 May 2021 01:26:19 -0700 Subject: [PATCH 0099/2168] =?UTF-8?q?=E2=9C=A8=20BigTreeTech=20Octopus=20b?= =?UTF-8?q?oard=20(STM32F446ZET6)=20(#21826)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 30 +- Marlin/src/pins/pins.h | 6 +- .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 522 ++++++++++++++++++ .../boards/marlin_BigTree_Octopus_v1.json | 35 ++ .../PeripheralPins.c | 392 +++++++++++++ .../MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h | 30 + .../hal_conf_extra.h | 53 ++ .../MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld | 187 +++++++ .../MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp | 239 ++++++++ .../MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h | 216 ++++++++ ini/stm32f4.ini | 25 +- 11 files changed, 1718 insertions(+), 17 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h create mode 100644 buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index e32789e744..20aeac654d 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -370,20 +370,22 @@ #define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) #define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) #define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_LERDGE_K 4214 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4215 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4216 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4217 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4218 // FYSETC S6 (STM32F446VET6) -#define BOARD_FYSETC_S6_V2_0 4219 // FYSETC S6 v2.0 (STM32F446VET6) -#define BOARD_FYSETC_SPIDER 4220 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4221 // FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4222 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4223 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4224 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_ANET_ET4 4225 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4226 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4227 // FYSETC Cheetah V2.0 +#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6) +#define BOARD_LERDGE_K 4215 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4216 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4217 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4218 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4219 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4220 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4221 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4222 // FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4223 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4224 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4225 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_ANET_ET4 4226 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4227 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4228 // FYSETC Cheetah V2.0 + // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 2a70e571af..a8ed35b009 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -600,6 +600,8 @@ #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 #elif MB(BTT_SKR_V2_0_REV_B) #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 +#elif MB(BTT_OCTOPUS_V1_0) + #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1_0 env:BIGTREE_OCTOPUS_V1_0_USB #elif MB(LERDGE_K) #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive #elif MB(LERDGE_S) @@ -722,7 +724,7 @@ #error "BOARD_BIQU_SKR_V1_1 has been renamed BOARD_BTT_SKR_V1_1. Please update your configuration." #elif MB(BIGTREE_SKR_V1_1) #error "BOARD_BIGTREE_SKR_V1_1 has been renamed BOARD_BTT_SKR_V1_1. Please update your configuration." - #elif MB(BIGTREE_SKR_V2_2) + #elif MB(BIGTREE_SKR_V1_2) #error "BOARD_BIGTREE_SKR_V1_2 has been renamed BOARD_BTT_SKR_V1_2. Please update your configuration." #elif MB(BIGTREE_SKR_V1_3) #error "BOARD_BIGTREE_SKR_V1_3 has been renamed BOARD_BTT_SKR_V1_3. Please update your configuration." @@ -757,7 +759,7 @@ #elif MB(RAMPS_LONGER3D_LK4PRO) #error "BOARD_RAMPS_LONGER3D_LK4PRO is now BOARD_LONGER3D_LKx_PRO. Please update your configuration." #elif MB(BTT_SKR_V2_0) - #error "BTT_SKR_V2_0 is now BTT_SKR_V2_0_REV_A or BTT_SKR_V2_0_REV_B. Please update your configuration." + #error "BTT_SKR_V2_0 is now BTT_SKR_V2_0_REV_A or BTT_SKR_V2_0_REV_B. See https://bit.ly/3t5d9JQ for more information. Please update your configuration." #else #error "Unknown MOTHERBOARD value set in Configuration.h" #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h new file mode 100644 index 0000000000..9f3a141ab0 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -0,0 +1,522 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "BTT OCTOPUS V1.0" +#endif + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) +#define I2C_SCL_PIN PB8 +#define I2C_SDA_PIN PB9 + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// +// Servos +#define SERVO0_PIN PB6 + +// +// Misc. Functions +// +#define LED_PIN PA13 + +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PG6 // X-STOP +#define Y_DIAG_PIN PG9 // Y-STOP +#define Z_DIAG_PIN PG10 // Z-STOP +#define Z2_DIAG_PIN PG11 // Z2-STOP +#define E0_DIAG_PIN PG12 // E0DET +#define E1_DIAG_PIN PG13 // E1DET +#define E2_DIAG_PIN PG14 // E2DET +#define E3_DIAG_PIN PG15 // E3DET + +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif + +// +// Limit Switches +// +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_DIR < 0 + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #else + #define X_MIN_PIN E0_DIAG_PIN // E0DET + #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #ifndef X_MIN_PIN + #define X_MIN_PIN X_DIAG_PIN // X-STOP + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #endif +#else + #define X_STOP_PIN X_DIAG_PIN // X-STOP +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_DIR < 0 + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #else + #define Y_MIN_PIN E1_DIAG_PIN // E1DET + #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #endif +#else + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_DIR < 0 + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #else + #define Z_MIN_PIN E2_DIAG_PIN // PWRDET + #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #endif +#else + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PG12 // E0DET +#define FIL_RUNOUT2_PIN PG13 // E1DET +#define FIL_RUNOUT3_PIN PG14 // E2DET +#define FIL_RUNOUT4_PIN PG15 // E3DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PE11 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC0 // PWRDET +#endif + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PF13 // MOTOR 0 +#define X_DIR_PIN PF12 +#define X_ENABLE_PIN PF14 +#ifndef X_CS_PIN + #define X_CS_PIN PC4 +#endif + +#define Y_STEP_PIN PG0 // MOTOR 1 +#define Y_DIR_PIN PG1 +#define Y_ENABLE_PIN PF15 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD11 +#endif + +#define Z_STEP_PIN PF11 // MOTOR 2 +#define Z_DIR_PIN PG3 +#define Z_ENABLE_PIN PG5 +#ifndef Z_CS_PIN + #define Z_CS_PIN PC6 +#endif + +#define Z2_STEP_PIN PG4 // MOTOR 3 +#define Z2_DIR_PIN PC1 +#define Z2_ENABLE_PIN PA0 +#ifndef Z2_CS_PIN + #define Z2_CS_PIN PC7 +#endif + +#define E0_STEP_PIN PF9 // MOTOR 4 +#define E0_DIR_PIN PF10 +#define E0_ENABLE_PIN PG2 +#ifndef E0_CS_PIN + #define E0_CS_PIN PF2 +#endif + +#define E1_STEP_PIN PC13 // MOTOR 5 +#define E1_DIR_PIN PF0 +#define E1_ENABLE_PIN PF1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PE4 +#endif + +#define E2_STEP_PIN PE2 // MOTOR 6 +#define E2_DIR_PIN PE3 +#define E2_ENABLE_PIN PD4 +#ifndef E2_CS_PIN + + #define E2_CS_PIN PE1 +#endif + +#define E3_STEP_PIN PE6 // MOTOR 7 +#define E3_DIR_PIN PA14 +#define E3_ENABLE_PIN PE0 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD3 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PF3 // TB +#if TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 // PT100 Connector +#else + #define TEMP_0_PIN PF4 // TH0 +#endif +#define TEMP_1_PIN PF5 // TH1 +#define TEMP_2_PIN PF6 // TH2 +#define TEMP_3_PIN PF7 // TH3 + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PA1 // Hotbed +#define HEATER_0_PIN PA2 // Heater0 +#define HEATER_1_PIN PA3 // Heater1 +#define HEATER_2_PIN PB10 // Heater2 +#define HEATER_3_PIN PB11 // Heater3 + +#define FAN_PIN PA8 // Fan0 +#define FAN1_PIN PE5 // Fan1 +#define FAN2_PIN PD12 // Fan2 +#define FAN3_PIN PD13 // Fan3 +#define FAN4_PIN PD14 // Fan4 +#define FAN5_PIN PD15 // Fan5 + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PA7 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PA6 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PA5 + #endif +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC4 + #define X_SERIAL_RX_PIN PC4 + + #define Y_SERIAL_TX_PIN PD11 + #define Y_SERIAL_RX_PIN PD11 + + #define Z_SERIAL_TX_PIN PC6 + #define Z_SERIAL_RX_PIN PC6 + + #define Z2_SERIAL_TX_PIN PC7 + #define Z2_SERIAL_RX_PIN PC7 + + #define E0_SERIAL_TX_PIN PF2 + #define E0_SERIAL_RX_PIN PF2 + + #define E1_SERIAL_TX_PIN PE4 + #define E1_SERIAL_RX_PIN PE4 + + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE1 + + #define E3_SERIAL_TX_PIN PD3 + #define E3_SERIAL_RX_PIN PD3 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +/** + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) + * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) + * ------ ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PE15 +#define EXP1_04_PIN PE14 +#define EXP1_05_PIN PE13 +#define EXP1_06_PIN PE12 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE9 +#define EXP1_09_PIN PE7 +#define EXP1_10_PIN PE8 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC15 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB2 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PB1 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// Onboard SD card +// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 +// +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT // Use SDIO for onboard SD + #define SD_DETECT_PIN PC14 +#elif SD_CONNECTION_IS(LCD) + + #define CUSTOM_SPI_PINS + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC15 + +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** + * ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 + */ + + // M1 on Driver Expansion Module + #define E4_STEP_PIN EXP2_05_PIN + #define E4_DIR_PIN EXP2_06_PIN + #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_DIAG_PIN EXP1_06_PIN + #define E4_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_05_PIN + #define E4_SERIAL_RX_PIN EXP1_05_PIN + #endif + + // M2 on Driver Expansion Module + #define E5_STEP_PIN EXP2_08_PIN + #define E5_DIR_PIN EXP2_07_PIN + #define E5_ENABLE_PIN EXP1_03_PIN + #define E5_DIAG_PIN EXP1_08_PIN + #define E5_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_07_PIN + #define E5_SERIAL_RX_PIN EXP1_07_PIN + #endif + + // M3 on Driver Expansion Module + #define E6_STEP_PIN EXP2_10_PIN + #define E6_DIR_PIN EXP2_09_PIN + #define E6_ENABLE_PIN EXP1_04_PIN + #define E6_DIAG_PIN EXP1_10_PIN + #define E6_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E6_SERIAL_TX_PIN EXP1_09_PIN + #define E6_SERIAL_RX_PIN EXP1_09_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION + +// +// LCDs and Controllers +// +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_08_PIN + #endif + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif + + #endif +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #endif +#endif + +// +// WIFI +// + +/** + * ------- + * GND | 9 | | 8 | 3.3V + * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) + * 3.3V | 11 | | 6 | PB14 (ESP-MISO) + * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) + * (ESP-IO4) PD10 | 13 | | 4 | NC + * NC | 14 | | 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) + * ------- + * WIFI + */ +#define ESP_WIFI_MODULE_COM 3 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN PG7 +#define ESP_WIFI_MODULE_ENABLE_PIN PG8 +#define ESP_WIFI_MODULE_GPIO0_PIN PD7 +#define ESP_WIFI_MODULE_GPIO4_PIN PD10 diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json new file mode 100644 index 0000000000..a583b5783f --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json @@ -0,0 +1,35 @@ +{ + "build": { + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F446xx", + "f_cpu": "180000000L", + "mcu": "stm32f446zet6", + "variant": "MARLIN_BIGTREE_OCTOPUS_V1_0" + }, + "connectivity": [ + "can" + ], + "debug": { + "jlink_device": "STM32F446ZE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F446x.svd" + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F446ZE (128k RAM. 512k Flash)", + "upload": { + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial" + ] + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c new file mode 100644 index 0000000000..75bbd1cf20 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c @@ -0,0 +1,392 @@ +/* + ******************************************************************************* + * Copyright (c) 2016, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +// ===== +// Note: Commented lines are alternative possibilities which are not used per default. +// If you change them, you will have to know what you do +// ===== + + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 PT100 + {NC, NP, 0} + + // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + //{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + // {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + // {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + // {PC_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SCL[] = { + // {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + // {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + // {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx + // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx + // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx + // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx + // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx + // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N + // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N + {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4 + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // E1 Heater, TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2 + // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_RX[] = { + // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_RTS[] = { + // {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + // {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_CTS[] = { + // {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + // {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + // {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + // {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + // {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +const PinMap PinMap_CAN_RD[] = { + // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_CAN_MODULE_ENABLED +const PinMap PinMap_CAN_TD[] = { + // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, + // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +//*** No Ethernet *** + +//*** QUADSPI *** + +#ifdef HAL_QSPI_MODULE_ENABLED +const PinMap PinMap_QUADSPI[] = { + // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 + // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK + // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS + // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 + // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 + // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_FS[] = { + // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS + // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; +#endif + +#ifdef HAL_PCD_MODULE_ENABLED +const PinMap PinMap_USB_OTG_HS[] = { + {NC, NP, 0} +}; + + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + // {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 + // {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 + // {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 + // {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif +#endif + + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h new file mode 100644 index 0000000000..bff3f21349 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h @@ -0,0 +1,30 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h new file mode 100644 index 0000000000..da974b1ba7 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h @@ -0,0 +1,53 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) +#define HAL_SD_MODULE_ENABLED + +//#undef HAL_SD_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_FLASH_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_CRYP_MODULE_ENABLED +#undef HAL_DCMI_MODULE_ENABLED +#undef HAL_DMA2D_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_SRAM_MODULE_ENABLED +#undef HAL_SDRAM_MODULE_ENABLED +#undef HAL_HASH_MODULE_ENABLED +#undef HAL_EXTI_MODULE_ENABLED +#undef HAL_SMBUS_MODULE_ENABLED +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IWDG_MODULE_ENABLED +#undef HAL_LTDC_MODULE_ENABLED +#undef HAL_DSI_MODULE_ENABLED +#undef HAL_QSPI_MODULE_ENABLED +#undef HAL_RNG_MODULE_ENABLED +#undef HAL_SAI_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +//#undef HAL_HCD_MODULE_ENABLED +#undef HAL_FMPI2C_MODULE_ENABLED +#undef HAL_SPDIFRX_MODULE_ENABLED +#undef HAL_DFSDM_MODULE_ENABLED +#undef HAL_LPTIM_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld new file mode 100644 index 0000000000..5ced01158f --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld @@ -0,0 +1,187 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407VETx Device with +** 512KByte FLASH, 128KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2014 Ac6

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of Ac6 nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200;; /* required amount of heap */ +_Min_Stack_Size = 0x400;; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x8008000, LENGTH = 512K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text ALIGN(4): + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata ALIGN(4): + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /*_siccmram = LOADADDR(.ccmram);*/ + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp new file mode 100644 index 0000000000..5ed098aab9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp @@ -0,0 +1,239 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PA_0, //D0 + PA_1, //D1 + PA_2, //D2 + PA_3, //D3 + PA_4, //D4 + PA_5, //D5 + PA_6, //D6 + PA_7, //D7 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + PB_0, //D16 + PB_1, //D17 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_11, //D27 + PB_12, //D28 + PB_13, //D29 + PB_14, //D30 + PB_15, //D31 + PC_0, //D32 + PC_1, //D33 + PC_2, //D34 + PC_3, //D35 + PC_4, //D36 + PC_5, //D37 + PC_6, //D38 + PC_7, //D39 + PC_8, //D40 + PC_9, //D41 + PC_10, //D42 + PC_11, //D43 + PC_12, //D44 + PC_13, //D45 + PC_14, //D46 + PC_15, //D47 + PD_0, //D48 + PD_1, //D49 + PD_2, //D50 + PD_3, //D51 + PD_4, //D52 + PD_5, //D53 + PD_6, //D54 + PD_7, //D55 + PD_8, //D56 + PD_9, //D57 + PD_10, //D58 + PD_11, //D59 + PD_12, //D60 + PD_13, //D61 + PD_14, //D62 + PD_15, //D63 + PE_0, //D64 + PE_1, //D65 + PE_2, //D66 + PE_3, //D67 + PE_4, //D68 + PE_5, //D69 + PE_6, //D70 + PE_7, //D71 + PE_8, //D72 + PE_9, //D73 + PE_10, //D74 + PE_11, //D75 + PE_12, //D76 + PE_13, //D77 + PE_14, //D78 + PE_15, //D79 + PF_0, //D80 + PF_1, //D81 + PF_2, //D82 + PF_3, //D83 + PF_4, //D84 + PF_5, //D85 + PF_6, //D86 + PF_7, //D87 + PF_8, //D88 + PF_9, //D89 + PF_10, //D90 + PF_11, //D91 + PF_12, //D92 + PF_13, //D93 + PF_14, //D94 + PF_15, //D95 + PG_0, //D96 + PG_1, //D97 + PG_2, //D98 + PG_3, //D99 + PG_4, //D100 + PG_5, //D101 + PG_6, //D102 + PG_7, //D103 + PG_8, //D104 + PG_9, //D105 + PG_10, //D106 + PG_11, //D107 + PG_12, //D108 + PG_13, //D109 + PG_14, //D110 + PG_15, //D111 + + //Duplicated ADC Pins + PA_3, //D112/A0 + PA_4, //D113/A1 + PC_0, //D114/A2 + PC_1, //D115/A3 + PC_2, //D116/A4 + PC_3, //D117/A5 + PC_4, //D118/A6 + PF_3, //D119/A16 - 1:FSMC_A3 2:ADC3_IN9 + PF_4, //D120/A17 - 1:FSMC_A4 2:ADC3_IN14 + PF_5, //D121/A18 - 1:FSMC_A5 2:ADC3_IN15 + PF_6, //D122/A19 - 1:TIM10_CH1 2:ADC3_IN4 + PF_7, //D123/A20 - 1:TIM11_CH1 2:ADC3_IN5 + PF_8, //D124/A20 - 1:TIM11_CH1 2:ADC3_IN6 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 180000000 + * HCLK(Hz) = 180000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 12000000 + * PLL_M = 6 + * PLL_N = 180 + * PLL_P = 2 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + +#ifdef HAL_PWR_MODULE_ENABLED + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); +#endif + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 6; + RCC_OscInitStruct.PLL.PLLN = 180; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + RCC_OscInitStruct.PLL.PLLR = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | + RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLRCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; + PeriphClkInitStruct.PLLSAI.PLLSAIM = 6; + PeriphClkInitStruct.PLLSAI.PLLSAIN = 96; + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4; + PeriphClkInitStruct.PLLSAIDivQ = 1; + PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48CLKSOURCE_PLLSAIP; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h new file mode 100644 index 0000000000..4305c81a45 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h @@ -0,0 +1,216 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#define PA0 0 //D0 +#define PA1 1 //D1 +#define PA2 2 //D2 +#define PA3 3 //D3 +#define PA4 4 //D4 +#define PA5 5 //D5 +#define PA6 6 //D6 +#define PA7 7 //D7 +#define PA8 8 //D8 +#define PA9 9 //D9 +#define PA10 10 //D10 +#define PA11 11 //D11 +#define PA12 12 //D12 +#define PA13 13 //D13 +#define PA14 14 //D14 +#define PA15 15 //D15 +#define PB0 16 //D16 +#define PB1 17 //D17 +#define PB2 18 //D18 +#define PB3 19 //D19 +#define PB4 20 //D20 +#define PB5 21 //D21 +#define PB6 22 //D22 +#define PB7 23 //D23 +#define PB8 24 //D24 +#define PB9 25 //D25 +#define PB10 26 //D26 +#define PB11 27 //D27 +#define PB12 28 //D28 +#define PB13 29 //D29 +#define PB14 30 //D30 +#define PB15 31 //D31 +#define PC0 32 //D32 +#define PC1 33 //D33 +#define PC2 34 //D34 +#define PC3 35 //D35 +#define PC4 36 //D36 +#define PC5 37 //D37 +#define PC6 38 //D38 +#define PC7 39 //D39 +#define PC8 40 //D40 +#define PC9 41 //D41 +#define PC10 42 //D42 +#define PC11 43 //D43 +#define PC12 44 //D44 +#define PC13 45 //D45 +#define PC14 46 //D46 +#define PC15 47 //D47 +#define PD0 48 //D48 +#define PD1 49 //D49 +#define PD2 50 //D50 +#define PD3 51 //D51 +#define PD4 52 //D52 +#define PD5 53 //D53 +#define PD6 54 //D54 +#define PD7 55 //D55 +#define PD8 56 //D56 +#define PD9 57 //D57 +#define PD10 58 //D58 +#define PD11 59 //D59 +#define PD12 60 //D60 +#define PD13 61 //D61 +#define PD14 62 //D62 +#define PD15 63 //D63 +#define PE0 64 //D64 +#define PE1 65 //D65 +#define PE2 66 //D66 +#define PE3 67 //D67 +#define PE4 68 //D68 +#define PE5 69 //D69 +#define PE6 70 //D70 +#define PE7 71 //D71 +#define PE8 72 //D72 +#define PE9 73 //D73 +#define PE10 74 //D74 +#define PE11 75 //D75 +#define PE12 76 //D76 +#define PE13 77 //D77 +#define PE14 78 //D78 +#define PE15 79 //D79 +#define PF0 80 //D64 +#define PF1 81 //D65 +#define PF2 82 //D66 +#define PF3 83 //D67 +#define PF4 84 //D68 +#define PF5 85 //D69 +#define PF6 86 //D70 +#define PF7 87 //D71 +#define PF8 88 //D72 +#define PF9 89 //D73 +#define PF10 90 //D74 +#define PF11 91 //D75 +#define PF12 92 //D76 +#define PF13 93 //D77 +#define PF14 94 //D78 +#define PF15 95 //D79 +#define PG0 96 //D64 +#define PG1 97 //D65 +#define PG2 98 //D66 +#define PG3 99 //D67 +#define PG4 100 //D68 +#define PG5 101 //D69 +#define PG6 102 //D70 +#define PG7 103 //D71 +#define PG8 104 //D72 +#define PG9 105 //D73 +#define PG10 106 //D74 +#define PG11 107 //D75 +#define PG12 108 //D76 +#define PG13 109 //D77 +#define PG14 110 //D78 +#define PG15 111 //D79 + +// This must be a literal with the same value as PEND +#define NUM_DIGITAL_PINS 125 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 13 +#define NUM_ANALOG_FIRST 112 + +//#define ADC_RESOLUTION 12 + +// PWM resolution +//#define PWM_RESOLUTION 12 +#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans +#define PWM_MAX_DUTY_CYCLE 255 + +// SPI Definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definitions +#define PIN_WIRE_SDA PB9 +#define PIN_WIRE_SCL PB8 + +// Timer Definitions +// Do not use timer used by PWM pin. See PinMap_PWM. +#define TIMER_TONE TIM6 +#define TIMER_SERVO TIM5 +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header +/* Enable Serial 3 */ +#define HAVE_HWSERIAL1 +#define HAVE_HWSERIAL3 + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +/* HAL configuration */ +#define HSE_VALUE 12000000U + +#define FLASH_PAGE_SIZE (4U * 1024U) + +#ifdef __cplusplus +} // extern "C" +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE_OPEN Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 62038332b3..5d6d291182 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -228,7 +228,7 @@ extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py # -# Bigtreetech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Flash Drive Support +# BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_2] platform = ${common_stm32.platform} @@ -247,6 +247,29 @@ build_flags = ${stm_flash_drive.build_flags} -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED +# +# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) +# +[env:BIGTREE_OCTOPUS_V1_0] +platform = ${common_stm32.platform} +extends = common_stm32 +board = marlin_BigTree_octopus_v1 +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py +build_flags = ${common_stm32.build_flags} + -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 -DUSE_USB_HS_IN_FS + +# +# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support +# +[env:BIGTREE_OCTOPUS_V1_0_USB] +extends = env:BIGTREE_OCTOPUS_V1_0 +platform_packages = ${stm_flash_drive.platform_packages} +#build_unflags = -DUSBCON -DUSBD_USE_CDC +build_flags = ${stm_flash_drive.build_flags} + -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 + -DUSBCON -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DUSE_USB_HS_IN_FS -DUSBD_USE_CDC_MSC + # # Lerdge base # From 75dadcc6696239cc092ecfff264260041c52169a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 12 May 2021 02:51:25 -0500 Subject: [PATCH 0100/2168] =?UTF-8?q?=F0=9F=93=9D=20Fix=20version=20refere?= =?UTF-8?q?nce?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- docs/Serial.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Serial.md b/docs/Serial.md index 15c0480bb0..f51b902723 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -5,7 +5,7 @@ While many provide a Arduino-like Serial class, it's not all of them, and the di Moreover, many platform have intrinsic needs about serial port (like forwarding the output on multiple serial port, providing a *serial-like* telnet server, mixing USB-based serial port with SD card emulation) that are difficult to handle cleanly in the other platform serial logic. -Starting with version `2.0.9`, Marlin provides a common interface for its serial needs. +Starting with version 2.0.8, Marlin provides a common interface for its serial needs. ## Common interface From 175fac8fe87cd527e3670bafb51fec6d372f56ac Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 12 May 2021 15:48:24 -0700 Subject: [PATCH 0101/2168] Always Invert Octopus Onboard SD Detect Pin (#21882) --- Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 9f3a141ab0..dce3018d64 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -349,6 +349,8 @@ // #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD + #undef SD_DETECT_STATE + #define SD_DETECT_STATE HIGH #define SD_DETECT_PIN PC14 #elif SD_CONNECTION_IS(LCD) From b3804fb277ad402d5a50adb65ec4739016e75d8d Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Wed, 12 May 2021 19:57:43 -0300 Subject: [PATCH 0102/2168] minor multi volume config typo (#21880) --- Marlin/Configuration_adv.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3ec45f3f46..47a844101f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1486,8 +1486,8 @@ #if ENABLED(MULTI_VOLUME) #define VOLUME_SD_ONBOARD #define VOLUME_USB_FLASH_DRIVE - #define DEFAULT_VOLUME SD_ONBOARD - #define DEFAULT_SHARED_VOLUME USB_FLASH_DRIVE + #define DEFAULT_VOLUME SV_SD_ONBOARD + #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE #endif #endif // SDSUPPORT From c8f9a3261071af8bd138d1e6694a0f28216b2bf6 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Wed, 12 May 2021 20:10:31 -0300 Subject: [PATCH 0103/2168] Update Robin Pro TFT Pins (#21879) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 34 ++++++++++++++------ 1 file changed, 24 insertions(+), 10 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 10e1633124..ed0e0f3aea 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -43,7 +43,7 @@ // // Note: MKS Robin board is using SPI2 interface. // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // // Servos @@ -188,7 +188,7 @@ // SD Card // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(LCD) @@ -210,12 +210,16 @@ * If the screen stays white, disable 'LCD_RESET_PIN' * to let the bootloader init the screen. */ -#if HAS_FSMC_GRAPHICAL_TFT - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 +#if HAS_FSMC_TFT + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define LCD_RESET_PIN PF6 #define LCD_BACKLIGHT_PIN PD13 + #define TFT_RESET_PIN LCD_RESET_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PA7 @@ -251,7 +255,8 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #else + // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY #define LCD_PINS_D4 PF14 #if IS_ULTIPANEL @@ -260,7 +265,7 @@ #define LCD_PINS_D7 PF13 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif @@ -270,11 +275,20 @@ #endif #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define W25QXX_CS_PIN PB12 // Flash chip-select + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 #endif From eb7f75461a7751105bb18e67581df79e2f9131ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 12 May 2021 19:44:21 -0500 Subject: [PATCH 0104/2168] Clean up hasty PR --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 27 ++++++++++---------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index ed0e0f3aea..2f318dde42 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -43,7 +43,7 @@ // // Note: MKS Robin board is using SPI2 interface. // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // // Servos @@ -188,7 +188,7 @@ // SD Card // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(LCD) @@ -211,15 +211,15 @@ * to let the bootloader init the screen. */ #if HAS_FSMC_TFT - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 - #define TFT_CS_PIN FSMC_CS_PIN - #define TFT_RS_PIN FSMC_RS_PIN + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define LCD_RESET_PIN PF6 #define LCD_BACKLIGHT_PIN PD13 - #define TFT_RESET_PIN LCD_RESET_PIN - #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN + #define TFT_RESET_PIN LCD_RESET_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PA7 @@ -255,8 +255,7 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #else - // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY #define LCD_PINS_D4 PF14 #if IS_ULTIPANEL @@ -265,7 +264,7 @@ #define LCD_PINS_D7 PF13 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif @@ -284,10 +283,10 @@ #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 // Flash chip-select + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define W25QXX_CS_PIN PB12 // Flash chip-select #define W25QXX_MOSI_PIN PB15 #define W25QXX_MISO_PIN PB14 #define W25QXX_SCK_PIN PB13 From 75f76cbf26d0acb8beb7698e2cee8621d4ca40a7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 13 May 2021 01:06:32 +0000 Subject: [PATCH 0105/2168] [cron] Bump distribution date (2021-05-13) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0ba593fde0..23c3de8510 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 "2021-05-12" + #define STRING_DISTRIBUTION_DATE "2021-05-13" #endif /** From 69473daa3d5fb0d30a6d4ddfa17e8d4ee278c14c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 13 May 2021 01:14:37 -0500 Subject: [PATCH 0106/2168] =?UTF-8?q?=F0=9F=94=A7=20Improve=20SD=5FDETECT?= =?UTF-8?q?=5FSTATE=20default=20(#21885)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 23 ++++++++----------- Marlin/src/inc/SanityCheck.h | 7 ++++++ .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 7 ++++-- 3 files changed, 22 insertions(+), 15 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index c237e6edd9..ec6e66d35a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -330,11 +330,6 @@ */ #if ENABLED(SDSUPPORT) - // Extender cable doesn't support SD_DETECT_PIN - #if ENABLED(NO_SD_DETECT) - #undef SD_DETECT_PIN - #endif - #if HAS_SD_HOST_DRIVE && SD_CONNECTION_IS(ONBOARD) // // The external SD card is not used. Hardware SPI is used to access the card. @@ -345,18 +340,20 @@ #define HAS_SHARED_MEDIA 1 #endif - #if PIN_EXISTS(SD_DETECT) - #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 + // Set SD_DETECT_STATE based on hardware if not overridden + #if PIN_EXISTS(SD_DETECT) && !defined(SD_DETECT_STATE) + #if BOTH(HAS_LCD_MENU, ELB_FULL_GRAPHIC_CONTROLLER) && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #define SD_DETECT_STATE HIGH + #else #define SD_DETECT_STATE LOW #endif #endif + // Extender cable doesn't support SD_DETECT_PIN + #if ENABLED(NO_SD_DETECT) + #undef SD_DETECT_PIN + #endif + #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD) #if ENABLED(SDIO_SUPPORT) #define NEED_SD2CARD_SDIO 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index cac54cd1aa..0034c74c09 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -760,6 +760,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LIGHTWEIGHT_UI requires a U8GLIB_ST7920-based display." #endif +/** + * SD Card Settings + */ +#if ALL(SDSUPPORT, ELB_FULL_GRAPHIC_CONTROLLER, HAS_LCD_MENU) && PIN_EXISTS(SD_DETECT) && SD_DETECT_STATE != HIGH && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #error "SD_DETECT_STATE must be set HIGH for SD on the ELB_FULL_GRAPHIC_CONTROLLER." +#endif + /** * SD File Sorting */ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index dce3018d64..8c16c2df29 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -349,8 +349,11 @@ // #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - #undef SD_DETECT_STATE - #define SD_DETECT_STATE HIGH + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE HIGH + #elif SD_DETECT_STATE == LOW + #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." + #endif #define SD_DETECT_PIN PC14 #elif SD_CONNECTION_IS(LCD) From e72fe0ad142a3e36b1369cbc98b996b09cdef4bd Mon Sep 17 00:00:00 2001 From: FilippoR Date: Thu, 13 May 2021 17:56:49 +0200 Subject: [PATCH 0107/2168] fix compilation for home hon top (#21894) --- Marlin/src/feature/powerloss.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 552f1d9009..3764af13d0 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -380,12 +380,11 @@ void PrintJobRecovery::resume() { float z_now = z_raised; // If Z homing goes to max then just move back to the "raised" position - gcode.process_subcommands_now_P(PSTR( - "G28R0\n" // Home all axes (no raise) - "G1Z%sF1200" // Move Z down to (raised) height - ), - dtostrf(z_now, 1, 3, str_1) - ); + sprintf_P(cmd, PSTR( + "G28R0\n" // Home all axes (no raise) + "G1Z%sF1200" // Move Z down to (raised) height + ), dtostrf(z_now, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); #else From 9336517258805bf6826bbe2403d4b5ba0b49977f Mon Sep 17 00:00:00 2001 From: "Alexander D. Kanevskiy" Date: Thu, 13 May 2021 23:10:48 +0300 Subject: [PATCH 0108/2168] Fix compilation failure in M1001 (#21897) --- Marlin/src/gcode/sd/M1001.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 418e594deb..cd4933ff27 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -27,10 +27,7 @@ #include "../gcode.h" #include "../../module/planner.h" #include "../../module/printcounter.h" - -#if DISABLED(NO_SD_AUTOSTART) - #include "../../sd/cardreader.h" -#endif +#include "../../sd/cardreader.h" #ifdef SD_FINISHED_RELEASECOMMAND #include "../queue.h" From 90f14367640a942697f9e00df5762afe4121c566 Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 14 May 2021 08:19:12 +1200 Subject: [PATCH 0109/2168] Fix nextion compile error (#21884) --- Marlin/src/lcd/extui/nextion/nextion_extui.cpp | 6 +++--- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 10 +++++----- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index 2ec8eeb30e..a825bd502f 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -26,12 +26,12 @@ * Nextion TFT support for Marlin */ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(NEXTION_TFT) -#include "ui_api.h" -#include "lib/nextion/nextion_tft.h" +#include "../ui_api.h" +#include "nextion_tft.h" namespace ExtUI { diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 35a5bb7c68..9035442681 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -645,6 +645,9 @@ void NextionTFT::UpdateOnChange() { last_flow_speed = getFlow_percent(getActiveTool()); } + // tmppage Axis + static float last_get_axis_position_mmX = 999, last_get_axis_position_mmY = 999, last_get_axis_position_mmZ = 999; + // tmppage Progress + Layer + Time if (isPrinting()) { @@ -679,9 +682,6 @@ void NextionTFT::UpdateOnChange() { } } - // tmppage Axis - static float last_get_axis_position_mmX = 999, last_get_axis_position_mmY = 999, last_get_axis_position_mmZ = 999; - if (!WITHIN(last_get_axis_position_mmX - getAxisPosition_mm(X), -0.1, 0.1)) { if (ELAPSED(ms, next_event_ms)) { next_event_ms = ms + 30; @@ -723,9 +723,9 @@ void NextionTFT::UpdateOnChange() { last_homedZ = isAxisPositionKnown(Z); } - // tmppage IDEX Mode - static uint8_t last_IDEX_Mode = 99; #if ENABLED(DUAL_X_CARRIAGE) + // tmppage IDEX Mode + static uint8_t last_IDEX_Mode = 99; if (last_IDEX_Mode != getIDEX_Mode()) { SEND_VAL("tmppage.idexmode", getIDEX_Mode()); last_IDEX_Mode = getIDEX_Mode(); From fe60a1892339600da18d2f54c074aa30708651e1 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 13 May 2021 13:25:39 -0700 Subject: [PATCH 0110/2168] Fix Octopus 12864 LCD Delays (#21883) --- Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 8c16c2df29..994d19bb57 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -492,13 +492,13 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) #endif #endif From 558b60858c4500d98cd34c7ba19a82bafec23d4a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 14 May 2021 01:08:17 +0000 Subject: [PATCH 0111/2168] [cron] Bump distribution date (2021-05-14) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 23c3de8510..46ad109e30 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 "2021-05-13" + #define STRING_DISTRIBUTION_DATE "2021-05-14" #endif /** From d97c1f1c6245e2b1f3152e5a210ed840b4bdbefb Mon Sep 17 00:00:00 2001 From: Jamie Date: Fri, 14 May 2021 00:14:13 -0500 Subject: [PATCH 0112/2168] =?UTF-8?q?=E2=9C=A8=20Instant=20Freeze/Resume?= =?UTF-8?q?=20Function=20(#17462)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 10 ++++++++++ Marlin/src/MarlinCore.cpp | 8 ++++++++ Marlin/src/inc/Conditionals_post.h | 16 +++++++++++++--- Marlin/src/inc/SanityCheck.h | 4 ++++ Marlin/src/module/stepper.cpp | 7 +++++++ Marlin/src/module/stepper.h | 4 ++++ Marlin/src/pins/pinsDebug_list.h | 5 ++++- buildroot/tests/mega2560 | 2 +- 8 files changed, 51 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 47a844101f..1a1e11e234 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3781,6 +3781,16 @@ #define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position #endif +/** + * Instant freeze / unfreeze functionality + * Specified pin has pullup and connecting to ground will instantly pause motion. + * Potentially useful for emergency stop that allows being resumed. + */ +//#define FREEZE_FEATURE +#if ENABLED(FREEZE_FEATURE) + //#define FREEZE_PIN 41 // Override the default (KILL) pin here +#endif + /** * MAX7219 Debug Matrix * diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 85ee920e72..08d7968539 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -483,6 +483,10 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } #endif + #if HAS_FREEZE_PIN + Stepper::frozen = !READ(FREEZE_PIN); + #endif + #if HAS_HOME // Handle a standalone HOME button constexpr millis_t HOME_DEBOUNCE_DELAY = 1000UL; @@ -1089,6 +1093,10 @@ void setup() { #endif #endif + #if HAS_FREEZE_PIN + SET_INPUT_PULLUP(FREEZE_PIN); + #endif + #if HAS_SUICIDE SETUP_LOG("SUICIDE_PIN"); OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ec6e66d35a..8c115fbab6 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2318,12 +2318,22 @@ #endif // User Interface +#if ENABLED(FREEZE_FEATURE) + #if !PIN_EXISTS(FREEZE) && PIN_EXISTS(KILL) + #define FREEZE_PIN KILL_PIN + #endif + #if PIN_EXISTS(FREEZE) + #define HAS_FREEZE_PIN 1 + #endif +#else + #undef FREEZE_PIN +#endif +#if PIN_EXISTS(KILL) && TERN1(FREEZE_FEATURE, KILL_PIN != FREEZE_PIN) + #define HAS_KILL 1 +#endif #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 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 0034c74c09..2131fcd678 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3307,3 +3307,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) // Misc. Cleanup #undef _TEST_PWM + +#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) + #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." +#endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 5a5fa3afe6..ff2be0c356 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -179,6 +179,10 @@ bool Stepper::abort_current_block; uint32_t Stepper::acceleration_time, Stepper::deceleration_time; uint8_t Stepper::steps_per_isr; +#if HAS_FREEZE_PIN + bool Stepper::frozen; // = false +#endif + IF_DISABLED(ADAPTIVE_STEP_SMOOTHING, constexpr) uint8_t Stepper::oversampling_factor; xyze_long_t Stepper::delta_error{0}; @@ -1531,6 +1535,9 @@ void Stepper::pulse_phase_isr() { // If there is no current block, do nothing if (!current_block) return; + // Skipping step processing causes motion to freeze + if (TERN0(HAS_FREEZE_PIN, frozen)) return; + // Count of pending loops and events for this iteration const uint32_t pending_events = step_event_count - step_events_completed; uint8_t events_to_do = _MIN(pending_events, steps_per_isr); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index bbe8df146f..5ddd762aa9 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -266,6 +266,10 @@ class Stepper { static constexpr uint8_t last_moved_extruder = 0; #endif + #if HAS_FREEZE_PIN + static bool frozen; // Set this flag to instantly freeze motion + #endif + private: static block_t* current_block; // A pointer to the block currently being traced diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 51a00630a4..8eee4f18fb 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -721,9 +721,12 @@ #if PIN_EXISTS(I2C_SDA) REPORT_NAME_DIGITAL(__LINE__, I2C_SDA_PIN) #endif -#if PIN_EXISTS(KILL) +#if HAS_KILL REPORT_NAME_DIGITAL(__LINE__, KILL_PIN) #endif +#if HAS_FREEZE_PIN + REPORT_NAME_DIGITAL(__LINE__, FREEZE_PIN) +#endif #if PIN_EXISTS(LCD_BACKLIGHT) REPORT_NAME_DIGITAL(__LINE__, LCD_BACKLIGHT_PIN) #endif diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index b4a3d2b9ac..98c4b761e0 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -21,7 +21,7 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr \ opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES CANCEL_OBJECTS SOUND_MENU_ITEM \ - EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN \ + EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE \ MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE EXTRA_LIN_ADVANCE_K QUICK_HOME \ LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL From a69e2923dd02537d777ee2e0d7cd838e39e66548 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 14 May 2021 00:17:04 -0500 Subject: [PATCH 0113/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20RR=20collision?= =?UTF-8?q?=20with=20MM=20(#21902)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/parser.cpp | 97 +++++++++++++++++++------------------ 1 file changed, 51 insertions(+), 46 deletions(-) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 896ff273cd..bfa4346f03 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -150,12 +150,30 @@ void GCodeParser::parse(char *p) { #endif /** - * Screen for good command letters. G, M, and T are always accepted. - * With Motion Modes enabled any axis letter can come first. + * Screen for good command letters. * With Realtime Reporting, commands S000, P000, and R000 are allowed. */ + #if ENABLED(REALTIME_REPORTING_COMMANDS) + switch (letter) { + case 'P': case 'R' ... 'S': { + uint8_t digits = 0; + char *a = p; + while (*a++ == '0') digits++; // Count up '0' characters + if (digits == 3) { // Three '0' digits is a good command + codenum = 0; + command_letter = letter; + return; + } + } + } + #endif + + /** + * Screen for good command letters. G, M, and T are always accepted. + * With Motion Modes enabled any axis letter can come first. + */ switch (letter) { - case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':) + case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':) { // Skip spaces to get the numeric part while (*p == ' ') p++; @@ -177,20 +195,18 @@ void GCodeParser::parse(char *p) { // A '?' signifies an unknown command command_letter = letter; - { - #if ENABLED(SIGNED_CODENUM) - int sign = 1; // Allow for a negative code like D-1 or T-1 - if (*p == '-') { sign = -1; ++p; } - #endif + #if ENABLED(SIGNED_CODENUM) + int sign = 1; // Allow for a negative code like D-1 or T-1 + if (*p == '-') { sign = -1; ++p; } + #endif - // Get the code number - integer digits only - codenum = 0; + // Get the code number - integer digits only + codenum = 0; - do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p)); + do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p)); - // Apply the sign, if any - TERN_(SIGNED_CODENUM, codenum *= sign); - } + // Apply the sign, if any + TERN_(SIGNED_CODENUM, codenum *= sign); // Allow for decimal point in command #if USE_GCODE_SUBCODES @@ -213,38 +229,33 @@ void GCodeParser::parse(char *p) { } #endif - break; + } break; #if ENABLED(GCODE_MOTION_MODES) - case 'I' ... 'J': - if (motion_mode_codenum != 5 && \ - TERN1(ARC_SUPPORT, motion_mode_codenum != 2 && motion_mode_codenum != 3)) return; - case 'Q': - if (motion_mode_codenum != 5) return; + + #if EITHER(BEZIER_CURVE_SUPPORT, ARC_SUPPORT) + case 'I' ... 'J': case 'P': + if (TERN1(BEZIER_CURVE_SUPPORT, motion_mode_codenum != 5) + && TERN1(ARC_P_CIRCLES, !WITHIN(motion_mode_codenum, 2, 3)) + ) return; + #endif + + #if ENABLED(BEZIER_CURVE_SUPPORT) + case 'Q': if (motion_mode_codenum != 5) return; + #endif + + #if ENABLED(ARC_SUPPORT) + case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return; + #endif + case 'X' ... 'Z': case 'E' ... 'F': if (motion_mode_codenum < 0) return; command_letter = 'G'; codenum = motion_mode_codenum; TERN_(USE_GCODE_SUBCODES, subcode = motion_mode_subcode); p--; // Back up one character to use the current parameter - break; - #endif + break; - #if ENABLED(REALTIME_REPORTING_COMMANDS) - case 'P': case 'R': { - if (letter == 'R') { - #if ENABLED(GCODE_MOTION_MODES) - if (ENABLED(ARC_SUPPORT) && !WITHIN(motion_mode_codenum, 2, 3)) return; - #endif - } - else if (TERN0(GCODE_MOTION_MODES, motion_mode_codenum != 5)) return; - } // fall-thru - case 'S': { - codenum = 0; // The only valid codenum is 0 - uint8_t digits = 0; - while (*p++ == '0') digits++; // Count up '0' characters - command_letter = (digits == 3) ? letter : '?'; // Three '0' digits is a good command - } return; // No parameters needed, so return now #endif default: return; @@ -252,18 +263,12 @@ void GCodeParser::parse(char *p) { // The command parameters (if any) start here, for sure! - #if DISABLED(FASTER_GCODE_PARSER) - command_args = p; // Scan for parameters in seen() - #endif + IF_DISABLED(FASTER_GCODE_PARSER, command_args = p); // Scan for parameters in seen() // Only use string_arg for these M codes if (letter == 'M') switch (codenum) { - #if ENABLED(GCODE_MACROS) - case 810 ... 819: - #endif - #if ENABLED(EXPECTED_PRINTER_CHECK) - case 16: - #endif + TERN_(GCODE_MACROS, case 810 ... 819:) + TERN_(EXPECTED_PRINTER_CHECK, case 16:) case 23: case 28: case 30: case 117 ... 118: case 928: string_arg = unescape_string(p); return; From e5b280c3096a4c9974b1ba28ffca1bb27354e048 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 13 May 2021 22:20:24 -0700 Subject: [PATCH 0114/2168] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20BTT=20Octopus?= =?UTF-8?q?=20Step=20Timer=20(#21901)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 994d19bb57..6de3c544d3 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -36,6 +36,9 @@ // USB Flash Drive support #define HAS_OTG_USB_HOST_SUPPORT +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + // // Servos #define SERVO0_PIN PB6 From 2a5ab55c36380cd394c4922705412452f800c17c Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Fri, 14 May 2021 02:22:43 -0300 Subject: [PATCH 0115/2168] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Fix=20TFT=20f?= =?UTF-8?q?or=20Robin=20Pro=20(#21900)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 2f318dde42..b56971c7a3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -213,6 +213,9 @@ #if HAS_FSMC_TFT #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN @@ -221,8 +224,15 @@ #define TFT_RESET_PIN LCD_RESET_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN + #define TFT_BUFFER_SIZE 14400 + #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN PA7 + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + #define TOUCH_CS_PIN PA7 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 // SPI2_SCK + #define TOUCH_MISO_PIN PB14 // SPI2_MISO + #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI #else #define BEEPER_PIN PC5 #define BTN_ENC PG2 From 3b4643d31a24cc6329ea3dd16827da18e77992e3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 15 May 2021 01:05:33 +0000 Subject: [PATCH 0116/2168] [cron] Bump distribution date (2021-05-15) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 46ad109e30..f0695fe168 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 "2021-05-14" + #define STRING_DISTRIBUTION_DATE "2021-05-15" #endif /** From 874c531f27e7f342c7864c12310ef12c177d9000 Mon Sep 17 00:00:00 2001 From: ondrada <82547068+ondrada@users.noreply.github.com> Date: Sat, 15 May 2021 05:29:17 +0200 Subject: [PATCH 0117/2168] Fix G29_RETRY_AND_RECOVER dependency (#21907) Co-authored-by: Scott Lahteine --- Marlin/src/gcode/gcode.cpp | 8 ++++++-- Marlin/src/inc/Conditionals_LCD.h | 1 + 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 241def0f77..7a3976a7bd 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -211,7 +211,7 @@ void GcodeSuite::dwell(millis_t time) { * When G29_RETRY_AND_RECOVER is enabled, call G29() in * a loop with recovery and retry handling. */ -#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER) +#if ENABLED(G29_RETRY_AND_RECOVER) void GcodeSuite::event_probe_recover() { TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR)); @@ -223,6 +223,10 @@ void GcodeSuite::dwell(millis_t time) { #endif } + #if ENABLED(G29_HALT_ON_FAILURE) + #include "../lcd/marlinui.h" + #endif + void GcodeSuite::event_probe_failure() { #ifdef ACTION_ON_G29_FAILURE host_action(PSTR(ACTION_ON_G29_FAILURE)); @@ -262,7 +266,7 @@ void GcodeSuite::dwell(millis_t time) { #endif } -#endif // HAS_LEVELING && G29_RETRY_AND_RECOVER +#endif // G29_RETRY_AND_RECOVER /** * Process the parsed command and dispatch it to its handler diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 42349b955e..000aa60347 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -870,6 +870,7 @@ #if !HAS_LEVELING #undef RESTORE_LEVELING_AFTER_G28 #undef ENABLE_LEVELING_AFTER_G28 + #undef G29_RETRY_AND_RECOVER #endif #if !HAS_LEVELING || EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) #undef PROBE_MANUALLY From 376f0be5da972c4e87e927b7aadba6e663010bb6 Mon Sep 17 00:00:00 2001 From: Moonglow Date: Sat, 15 May 2021 06:30:16 +0300 Subject: [PATCH 0118/2168] Fix MKS UI missing font select condition (#21905) --- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 76898997eb..727120c183 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -374,7 +374,7 @@ void tft_style_init() { style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; style_sel_text.text.color = LV_COLOR_YELLOW; style_sel_text.text.sel_color = LV_COLOR_YELLOW; - style_sel_text.text.font = &gb2312_puhui32; + style_sel_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); style_sel_text.line.width = 0; style_sel_text.text.letter_space = 0; style_sel_text.text.line_space = -5; From 7f774cab9005dd56667bf4db09c23370bd2c873f Mon Sep 17 00:00:00 2001 From: Luu Lac <45380455+shitcreek@users.noreply.github.com> Date: Sat, 15 May 2021 15:02:20 -0500 Subject: [PATCH 0119/2168] M154 Position Auto-Report (#18427) Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 5 ++++ Marlin/src/MarlinCore.cpp | 1 + Marlin/src/gcode/gcode.cpp | 4 +++ Marlin/src/gcode/gcode.h | 5 ++++ Marlin/src/gcode/host/M115.cpp | 3 +++ Marlin/src/gcode/host/M154.cpp | 40 ++++++++++++++++++++++++++++++ Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/module/motion.cpp | 5 ++++ Marlin/src/module/motion.h | 6 +++++ buildroot/tests/mega2560 | 2 +- ini/features.ini | 1 + platformio.ini | 1 + 12 files changed, 73 insertions(+), 2 deletions(-) create mode 100644 Marlin/src/gcode/host/M154.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 1a1e11e234..4d75c8407a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3416,6 +3416,11 @@ */ #define AUTO_REPORT_TEMPERATURES +/** + * Auto-report position with M154 S + */ +//#define AUTO_REPORT_POSITION + /** * Include capabilities in M115 output */ diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 08d7968539..5cd0269bac 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -796,6 +796,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { if (!gcode.autoreport_paused) { TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_reporter.tick()); TERN_(AUTO_REPORT_SD_STATUS, card.auto_reporter.tick()); + TERN_(AUTO_REPORT_POSITION, position_auto_reporter.tick()); } #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 7a3976a7bd..0ca6c82c2a 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -565,6 +565,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 193: M193(); break; // M193: Wait for cooler temperature to reach target #endif + #if ENABLED(AUTO_REPORT_POSITION) + case 154: M154(); break; // M155: Set position auto-report interval + #endif + #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) case 155: M155(); break; // M155: Set temperature auto-report interval #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index dc0b89e098..cdf04cd0f2 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -159,6 +159,7 @@ * M145 - Set heatup values for materials on the LCD. H B F for S (0=PLA, 1=ABS) * M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT) * M150 - Set Status LED Color as R U B W P. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, NEOPIXEL_LED, PCA9533, or PCA9632). + * M154 - Auto-report position with interval of S. (Requires AUTO_REPORT_POSITION) * M155 - Auto-report temperatures with interval of S. (Requires AUTO_REPORT_TEMPERATURES) * M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER) * M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER) @@ -721,6 +722,10 @@ private: static void M150(); #endif + #if ENABLED(AUTO_REPORT_POSITION) + static void M154(); + #endif + #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) static void M155(); #endif diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 4f18e5504d..ef4c8983cd 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -82,6 +82,9 @@ void GcodeSuite::M115() { // Volumetric Extrusion (M200) cap_line(PSTR("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS)); + // AUTOREPORT_POS (M154) + cap_line(PSTR("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION)); + // AUTOREPORT_TEMP (M155) cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES)); diff --git a/Marlin/src/gcode/host/M154.cpp b/Marlin/src/gcode/host/M154.cpp new file mode 100644 index 0000000000..156e6b69b6 --- /dev/null +++ b/Marlin/src/gcode/host/M154.cpp @@ -0,0 +1,40 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(AUTO_REPORT_POSITION) + +#include "../gcode.h" +#include "../../module/motion.h" + +/** + * M154: Set position auto-report interval. M154 S + */ +void GcodeSuite::M154() { + + if (parser.seenval('S')) + position_auto_reporter.set_interval(parser.value_byte()); + +} + +#endif // AUTO_REPORT_POSITION diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 8c115fbab6..6de9c40ac7 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2231,7 +2231,7 @@ #if !HAS_TEMP_SENSOR #undef AUTO_REPORT_TEMPERATURES #endif -#if EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) +#if ANY(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS, AUTO_REPORT_POSITION) #define HAS_AUTO_REPORTING 1 #endif diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 6ca8dc054c..171d9520cb 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -230,6 +230,11 @@ void report_current_position_projected() { stepper.report_a_position(planner.position); } +#if ENABLED(AUTO_REPORT_POSITION) + //struct PositionReport { void report() { report_current_position_projected(); } }; + AutoReporter position_auto_reporter; +#endif + #if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) M_StateEnum M_State_grbl = M_INIT; diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index c734fbdf34..e01978c852 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -211,6 +211,12 @@ void report_real_position(); void report_current_position(); void report_current_position_projected(); +#if ENABLED(AUTO_REPORT_POSITION) + #include "../libs/autoreport.h" + struct PositionReport { static void report() { report_current_position_projected(); } }; + extern AutoReporter position_auto_reporter; +#endif + #if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) #define HAS_GRBL_STATE 1 /** diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 98c4b761e0..7bbf29e630 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -56,7 +56,7 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO NUM_SERVOS 1 \ FIL_RUNOUT3_STATE HIGH opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE \ - EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL \ + EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL AUTO_REPORT_POSITION \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ DIRECT_STEPPING DETECT_BROKEN_ENDSTOP \ FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING FIL_RUNOUT3_PULLUP diff --git a/ini/features.ini b/ini/features.ini index 586af1653f..6a2ccbedac 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -182,6 +182,7 @@ CNC_COORDINATE_SYSTEMS = src_filter=+ EXPECTED_PRINTER_CHECK = src_filter=+ HOST_KEEPALIVE_FEATURE = src_filter=+ +AUTO_REPORT_POSITION = src_filter=+ REPETIER_GCODE_M360 = src_filter=+ HAS_GCODE_M876 = src_filter=+ HAS_RESUME_CONTINUE = src_filter=+ diff --git a/platformio.ini b/platformio.ini index e743eb2db4..4d69ca12df 100644 --- a/platformio.ini +++ b/platformio.ini @@ -198,6 +198,7 @@ default_src_filter = + - - + - - - + - - - - From 05bb3bde7a761a3a3087ec29d0b45814cb2174bb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 15 May 2021 15:21:02 -0500 Subject: [PATCH 0120/2168] Update Hex Version to 02000801 --- Marlin/Configuration.h | 2 +- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/Version.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 755b58fe15..78c2dc9160 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,7 +35,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 020008 +#define CONFIGURATION_H_VERSION 02000801 //=========================================================================== //============================= Getting Started ============================= diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4d75c8407a..5335fa012a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -30,7 +30,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 020008 +#define CONFIGURATION_ADV_H_VERSION 02000801 //=========================================================================== //============================= Thermal Settings ============================ diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f0695fe168..3d69c70ba4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 020008 +#define MARLIN_HEX_VERSION 02000801 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif From 533ba2ac96ee63ecc74bc4ba4473eecf0e4dab65 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 16 May 2021 01:12:19 +0000 Subject: [PATCH 0121/2168] [cron] Bump distribution date (2021-05-16) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3d69c70ba4..90bd9f080f 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 "2021-05-15" + #define STRING_DISTRIBUTION_DATE "2021-05-16" #endif /** From ebb75a529b8f9d3b53dac12ffc6301d515a1cdaa Mon Sep 17 00:00:00 2001 From: ekef <62036680+ekef@users.noreply.github.com> Date: Sun, 16 May 2021 02:22:30 +0300 Subject: [PATCH 0122/2168] Fix MKS Robin E3 BLTOUCH and Fan PWM timer conflicts (#21889) --- Marlin/src/HAL/STM32F1/timers.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 63ddfb9e60..38a0fc7fa1 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -80,7 +80,7 @@ typedef uint16_t hal_timer_t; //#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM #endif -#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE) +#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3) // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY #define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4 From 9c61e6f1c0b1cb003f440fb4410faaa371764a1e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 17 May 2021 01:06:01 +0000 Subject: [PATCH 0123/2168] [cron] Bump distribution date (2021-05-17) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 90bd9f080f..8fff7dcc17 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 "2021-05-16" + #define STRING_DISTRIBUTION_DATE "2021-05-17" #endif /** From c3a65eef7a4e62ee3db0ff672ccb94acfc896a34 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 18 May 2021 11:22:33 +1200 Subject: [PATCH 0124/2168] Fix envs using mks_encrypt.py (#21933) Fix #21928 --- buildroot/share/PlatformIO/scripts/mks_encrypt.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py index 78d7cf349d..0c622704e7 100644 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ b/buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -17,7 +17,7 @@ if 'firmware' in board.get("build").keys(): # Encrypt ${PROGNAME}.bin and save it as build.firmware def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, "build.firmware") + marlin.encrypt_mks(source, target, env, board.get("build.firmware")) marlin.add_post_action(encrypt); From 4d7feea72e1164da2bb0941e978e63a42bcabcf0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 18 May 2021 01:09:42 +0000 Subject: [PATCH 0125/2168] [cron] Bump distribution date (2021-05-18) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8fff7dcc17..708f130e40 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 "2021-05-17" + #define STRING_DISTRIBUTION_DATE "2021-05-18" #endif /** From 1e189506effcf6be1e681cedb396b0574a9f109e Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 18 May 2021 14:16:47 +1200 Subject: [PATCH 0126/2168] Fix EEPROM_CHITCHAT (#21934) Fix #21929 --- Marlin/src/module/settings.cpp | 35 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 18 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 9d65bbb744..2b20bba4fb 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -584,7 +584,11 @@ void MarlinSettings::postprocess() { "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data."); #endif -#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +// +// This file simply uses the DEBUG_ECHO macros to implement EEPROM_CHITCHAT. +// For deeper debugging of EEPROM issues enable DEBUG_EEPROM_READWRITE. +// +#define DEBUG_OUT EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" #if ENABLED(EEPROM_SETTINGS) @@ -1450,8 +1454,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(final_crc); // Report storage size - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); + DEBUG_ECHO_MSG("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); eeprom_error |= size_error(eeprom_size); } @@ -1490,8 +1493,7 @@ void MarlinSettings::postprocess() { stored_ver[0] = '?'; stored_ver[1] = '\0'; } - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); + DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); eeprom_error = true; } @@ -2186,9 +2188,13 @@ void MarlinSettings::postprocess() { = DIGIPOT_MOTOR_CURRENT #endif ; - DEBUG_ECHOLNPGM("DIGIPOTS Loading"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loading"); + #endif EEPROM_READ(motor_current_setting); - DEBUG_ECHOLNPGM("DIGIPOTS Loaded"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loaded"); + #endif #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM if (!validating) COPY(stepper.motor_current_setting, motor_current_setting); @@ -2357,14 +2363,12 @@ void MarlinSettings::postprocess() { // eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); if (eeprom_error) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize()); + DEBUG_ECHO_MSG("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize()); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_index()); } else if (working_crc != stored_crc) { eeprom_error = true; - DEBUG_ERROR_START(); - DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); + DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } else if (!validating) { @@ -2454,13 +2458,8 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) inline void ubl_invalid_slot(const int s) { - #if BOTH(EEPROM_CHITCHAT, DEBUG_OUT) - DEBUG_ECHOLNPGM("?Invalid slot."); - DEBUG_ECHO(s); - DEBUG_ECHOLNPGM(" mesh slots available."); - #else - UNUSED(s); - #endif + DEBUG_ECHOLNPAIR("?Invalid slot.\n", s, " mesh slots available."); + UNUSED(s); } const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; // 128 (+1 because of the change to capacity rather than last valid address) From ad8c16177e825c20c8868ac2d440762451d29c60 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 May 2021 21:17:22 -0500 Subject: [PATCH 0127/2168] Use defined strings --- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index be693a748f..a9ad9c189c 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -621,9 +621,9 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { if (tmpStr == 0) { gCfgItems.fileSysType = FILE_SYS_SD; - send_to_wifi((uint8_t *)"Begin file list\r\n", strlen("Begin file list\r\n")); + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); get_file_list((char *)"0:/"); - send_to_wifi((uint8_t *)"End file list\r\n", strlen("End file list\r\n")); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); SEND_OK_TO_WIFI; break; } @@ -634,7 +634,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { char *path = (char *)tempBuf; if (strlen((char *)&tmpStr[index]) < 80) { - send_to_wifi((uint8_t *)"Begin file list\r\n", strlen("Begin file list\r\n")); + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) gCfgItems.fileSysType = FILE_SYS_SD; @@ -643,7 +643,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { strcpy((char *)path, (char *)&tmpStr[index]); get_file_list(path); - send_to_wifi((uint8_t *)"End file list\r\n", strlen("End file list\r\n")); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); } SEND_OK_TO_WIFI; } From 90f46d12268ad96659380a15304a3eb7132ae615 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 19 May 2021 01:05:23 +0000 Subject: [PATCH 0128/2168] [cron] Bump distribution date (2021-05-19) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 708f130e40..2d6d17e6fa 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 "2021-05-18" + #define STRING_DISTRIBUTION_DATE "2021-05-19" #endif /** From 419d67237cc7afecd42ad4d8083b8008350c4ce0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 20 May 2021 01:03:10 +0000 Subject: [PATCH 0129/2168] [cron] Bump distribution date (2021-05-20) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2d6d17e6fa..4bb0f19a8a 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 "2021-05-19" + #define STRING_DISTRIBUTION_DATE "2021-05-20" #endif /** From 50355f46074fe0b1f64bd8700086f30b90cc7c8f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 19 May 2021 22:02:28 -0500 Subject: [PATCH 0130/2168] Fix 'G29 K' value --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 6f1425b60c..b5773b0d46 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -581,7 +581,7 @@ void unified_bed_leveling::G29() { // use cases for the users. So we can wait and see what to do with it. // - if (parser.seen_test('K')) // Kompare Current Mesh Data to Specified Stored Mesh + if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh g29_compare_current_mesh_to_stored_mesh(); #endif // UBL_DEVEL_DEBUGGING From abbe3f0dc7aa23bae4aa26f6d6b09a4a0665a1a0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:46:59 -0500 Subject: [PATCH 0131/2168] =?UTF-8?q?=F0=9F=8E=A8=20Misc=20cleanup=20and?= =?UTF-8?q?=20fixes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/debug_section.h | 2 +- Marlin/src/core/language.h | 16 +++---- Marlin/src/core/serial.cpp | 2 +- Marlin/src/core/serial.h | 10 ++-- Marlin/src/core/types.h | 20 ++++---- Marlin/src/gcode/calibrate/G425.cpp | 36 +++++++-------- Marlin/src/gcode/config/M200-M205.cpp | 32 +++++-------- Marlin/src/gcode/config/M92.cpp | 9 ++-- Marlin/src/gcode/control/M17_M18_M84.cpp | 16 +++---- Marlin/src/gcode/control/M211.cpp | 4 +- .../src/gcode/feature/trinamic/M911-M914.cpp | 46 ++++++++----------- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/host/M114.cpp | 22 ++++----- Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/G2_G3.cpp | 8 ++-- Marlin/src/gcode/parser.cpp | 2 +- Marlin/src/gcode/parser.h | 2 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 1 + Marlin/src/lcd/extui/ui_api.cpp | 12 ++--- Marlin/src/lcd/menu/menu_mmu2.cpp | 3 +- Marlin/src/module/endstops.cpp | 4 +- Marlin/src/module/motion.cpp | 20 ++++---- Marlin/src/module/settings.cpp | 4 +- Marlin/src/module/stepper/trinamic.cpp | 2 +- 26 files changed, 125 insertions(+), 156 deletions(-) diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h index 2862d35af1..ef1511e6f0 100644 --- a/Marlin/src/core/debug_section.h +++ b/Marlin/src/core/debug_section.h @@ -44,6 +44,6 @@ private: SERIAL_ECHOPGM_P(the_msg); } SERIAL_CHAR(' '); - print_xyz(current_position); + print_pos(current_position); } }; diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index de29535f87..cabdde983b 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -277,14 +277,6 @@ #define STR_REMINDER_SAVE_SETTINGS "Remember to save!" #define STR_PASSWORD_SET "Password is " -// LCD Menu Messages - -#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) -#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) - -#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) -#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) - #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" @@ -386,6 +378,14 @@ #define LCD_STR_E6 "E" LCD_STR_N6 #define LCD_STR_E7 "E" LCD_STR_N7 +// Include localized LCD Menu Messages + +#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) +#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) + +#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) +#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) + // Use superscripts, if possible. Evaluated at point of use. #define SUPERSCRIPT_TWO TERN(NOT_EXTENDED_ISO10646_1_5X7, "^2", "²") #define SUPERSCRIPT_THREE TERN(NOT_EXTENDED_ISO10646_1_5X7, "^3", "³") diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 28442594ce..b4184fcd62 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -101,7 +101,7 @@ void print_bin(uint16_t val) { } } -void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { +void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 5c08be5c92..74b96dbb64 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -310,11 +310,11 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); -inline void print_xyz(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_xyz(xyz.x, xyz.y, xyz.z, prefix, suffix); +inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { + print_pos(xyz.x, xyz.y, xyz.z, prefix, suffix); } -#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) -#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, PSTR(PREFIX), nullptr); }while(0) +#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, PSTR(PREFIX), nullptr); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 79a79b739b..4011473aa0 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -29,6 +29,16 @@ class __FlashStringHelper; typedef const __FlashStringHelper *progmem_str; +// +// Conditional type assignment magic. For example... +// +// typename IF<(MYOPT==12), int, float>::type myvar; +// +template +struct IF { typedef R type; }; +template +struct IF { typedef L type; }; + // // Enumerated axis indices // @@ -57,16 +67,6 @@ enum AxisEnum : uint8_t { #define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS) #define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N) -// -// Conditional type assignment magic. For example... -// -// typename IF<(MYOPT==12), int, float>::type myvar; -// -template -struct IF { typedef R type; }; -template -struct IF { typedef L type; }; - // // feedRate_t is just a humble float // diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 0918bc9d4f..2fb4502267 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -194,16 +194,20 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta inline float measure(const AxisEnum axis, const int dir, const bool stop_state, float * const backlash_ptr, const float uncertainty) { const bool fast = uncertainty == CALIBRATION_MEASUREMENT_UNKNOWN; - // Save position - destination = current_position; - const float start_pos = destination[axis]; + // Save the current position of the specified axis + const float start_pos = current_position[axis]; + + // Take a measurement. Only the specified axis will be affected. const float measured_pos = measuring_movement(axis, dir, stop_state, fast); + // Measure backlash if (backlash_ptr && !fast) { const float release_pos = measuring_movement(axis, -dir, !stop_state, fast); *backlash_ptr = ABS(release_pos - measured_pos); } - // Return to starting position + + // Move back to the starting position + destination = current_position; destination[axis] = start_pos; do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); return measured_pos; @@ -235,12 +239,12 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t } #endif #if AXIS_CAN_CALIBRATE(X) + case RIGHT: dir = -1; case LEFT: axis = X_AXIS; break; - case RIGHT: axis = X_AXIS; dir = -1; break; #endif #if AXIS_CAN_CALIBRATE(Y) + case BACK: dir = -1; case FRONT: axis = Y_AXIS; break; - case BACK: axis = Y_AXIS; dir = -1; break; #endif default: return; } @@ -303,16 +307,8 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error.x = (0 - #if HAS_X_CENTER - + true_center.x - m.obj_center.x - #endif - ); - m.pos_error.y = (0 - #if HAS_Y_CENTER - + true_center.y - m.obj_center.y - #endif - ); + m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x); + m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y); m.pos_error.z = true_center.z - m.obj_center.z; } @@ -589,12 +585,12 @@ void GcodeSuite::G425() { SET_SOFT_ENDSTOP_LOOSE(true); measurements_t m; - float uncertainty = parser.seenval('U') ? parser.value_float() : CALIBRATION_MEASUREMENT_UNCERTAIN; + const float uncertainty = parser.floatval('U', CALIBRATION_MEASUREMENT_UNCERTAIN); - if (parser.seen('B')) + if (parser.seen_test('B')) calibrate_backlash(m, uncertainty); - else if (parser.seen('T')) - calibrate_toolhead(m, uncertainty, parser.has_value() ? parser.value_int() : active_extruder); + else if (parser.seen_test('T')) + calibrate_toolhead(m, uncertainty, parser.intval('T', active_extruder)); #if ENABLED(CALIBRATION_REPORTING) else if (parser.seen('V')) { probe_sides(m, uncertainty); diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index cb17fc45a6..55cfc1bf46 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M201() { #endif LOOP_XYZE(i) { - if (parser.seen(axis_codes[i])) { + if (parser.seenval(axis_codes[i])) { const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a)); } @@ -105,7 +105,7 @@ void GcodeSuite::M203() { if (target_extruder < 0) return; LOOP_XYZE(i) - if (parser.seen(axis_codes[i])) { + if (parser.seenval(axis_codes[i])) { const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a)); } @@ -147,24 +147,14 @@ void GcodeSuite::M204() { * J = Junction Deviation (mm) (If not using CLASSIC_JERK) */ void GcodeSuite::M205() { - #if HAS_JUNCTION_DEVIATION - #define J_PARAM "J" - #else - #define J_PARAM - #endif - #if HAS_CLASSIC_JERK - #define XYZE_PARAM "XYZE" - #else - #define XYZE_PARAM - #endif - if (!parser.seen("BST" J_PARAM XYZE_PARAM)) return; + if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) return; //planner.synchronize(); - if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong(); - if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); - if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); + if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong(); + if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); + if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION - if (parser.seen('J')) { + if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { planner.junction_deviation_mm = junc_dev; @@ -175,9 +165,9 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seen('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); - if (parser.seen('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); - if (parser.seen('Z')) { + if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); + if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); + if (parser.seenval('Z')) { planner.set_max_jerk(Z_AXIS, parser.value_linear_units()); #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) if (planner.max_jerk.z <= 0.1f) @@ -185,7 +175,7 @@ void GcodeSuite::M205() { #endif } #if HAS_CLASSIC_E_JERK - if (parser.seen('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); + if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); #endif #endif } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index bdb95db8d6..e83f5b314f 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -42,7 +42,7 @@ void report_M92(const bool echo=true, const int8_t e=-1) { } #endif - UNUSED_E(e); + UNUSED(e); } /** @@ -64,11 +64,8 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen("XYZE" - #if ENABLED(MAGIC_NUMBERS_GCODE) - "HL" - #endif - )) return report_M92(true, target_extruder); + if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL"))) + return report_M92(true, target_extruder); LOOP_XYZE(i) { if (parser.seenval(axis_codes[i])) { diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index b35b465331..f02508a901 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -34,10 +34,10 @@ */ void GcodeSuite::M17() { if (parser.seen("XYZE")) { - if (parser.seen('X')) ENABLE_AXIS_X(); - if (parser.seen('Y')) ENABLE_AXIS_Y(); - if (parser.seen('Z')) ENABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers(); + if (parser.seen_test('X')) ENABLE_AXIS_X(); + if (parser.seen_test('Y')) ENABLE_AXIS_Y(); + if (parser.seen_test('Z')) ENABLE_AXIS_Z(); + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -56,10 +56,10 @@ void GcodeSuite::M18_M84() { else { if (parser.seen("XYZE")) { planner.synchronize(); - if (parser.seen('X')) DISABLE_AXIS_X(); - if (parser.seen('Y')) DISABLE_AXIS_Y(); - if (parser.seen('Z')) DISABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers(); + if (parser.seen_test('X')) DISABLE_AXIS_X(); + if (parser.seen_test('Y')) DISABLE_AXIS_Y(); + if (parser.seen_test('Z')) DISABLE_AXIS_Z(); + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 2049f1eb69..2ba777ba65 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -39,8 +39,8 @@ void GcodeSuite::M211() { SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS); if (parser.seen('S')) soft_endstop._enabled = parser.value_bool(); serialprint_onoff(soft_endstop._enabled); - print_xyz(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); - print_xyz(l_soft_max, PSTR(STR_SOFT_MAX)); + print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); + print_pos(l_soft_max, PSTR(STR_SOFT_MAX)); } #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 8c840db5bf..0c5fff7025 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -35,10 +35,19 @@ #define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160)) #define M91x_USE_E(N) (E_STEPPERS > N && M91x_USE(E##N)) - #define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2)) - #define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2)) - #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) - #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)) + #if M91x_USE(X) || M91x_USE(X2) + #define M91x_SOME_X 1 + #endif + #if M91x_USE(Y) || M91x_USE(Y2) + #define M91x_SOME_Y 1 + #endif + #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4) + #define M91x_SOME_Z 1 + #endif + + #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7) + #define M91x_SOME_E 1 + #endif #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." @@ -112,31 +121,12 @@ * M912 E1 ; clear E1 only */ void GcodeSuite::M912() { - #if M91x_SOME_X - const bool hasX = parser.seen(axis_codes.x); - #else - constexpr bool hasX = false; - #endif + const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)), + hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)), + hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)), + hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e)); - #if M91x_SOME_Y - const bool hasY = parser.seen(axis_codes.y); - #else - constexpr bool hasY = false; - #endif - - #if M91x_SOME_Z - const bool hasZ = parser.seen(axis_codes.z); - #else - constexpr bool hasZ = false; - #endif - - #if M91x_SOME_E - const bool hasE = parser.seen(axis_codes.e); - #else - constexpr bool hasE = false; - #endif - - const bool hasNone = !hasX && !hasY && !hasZ && !hasE; + const bool hasNone = !hasE && !hasX && !hasY && !hasZ; #if M91x_SOME_X const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0ca6c82c2a..34a719c466 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -140,7 +140,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { * - Set the feedrate, if included */ void GcodeSuite::get_destination_from_command() { - xyze_bool_t seen = { false, false, false, false }; + xyze_bool_t seen{false}; #if ENABLED(CANCEL_OBJECTS) const bool &skip_move = cancelable.skipping; diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index e5dc90fb30..27b193851d 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -34,7 +34,7 @@ #include "../../core/debug_out.h" #endif - void report_xyze(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { + void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { char str[12]; LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); @@ -43,9 +43,9 @@ } SERIAL_EOL(); } - inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); } + inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); } - void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { + void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) { char str[12]; LOOP_XYZ(a) { SERIAL_CHAR(' ', XYZ_CHAR(a), ':'); @@ -57,11 +57,11 @@ void report_current_position_detail() { // Position as sent by G-code SERIAL_ECHOPGM("\nLogical:"); - report_xyz(current_position.asLogical()); + report_linear_axis_pos(current_position.asLogical()); // Cartesian position in native machine space SERIAL_ECHOPGM("Raw: "); - report_xyz(current_position); + report_linear_axis_pos(current_position); xyze_pos_t leveled = current_position; @@ -69,20 +69,20 @@ // Current position with leveling applied SERIAL_ECHOPGM("Leveled:"); planner.apply_leveling(leveled); - report_xyz(leveled); + report_linear_axis_pos(leveled); // Test planner un-leveling. This should match the Raw result. SERIAL_ECHOPGM("UnLevel:"); xyze_pos_t unleveled = leveled; planner.unapply_leveling(unleveled); - report_xyz(unleveled); + report_linear_axis_pos(unleveled); #endif #if IS_KINEMATIC // Kinematics applied to the leveled position SERIAL_ECHOPGM(TERN(IS_SCARA, "ScaraK: ", "DeltaK: ")); inverse_kinematics(leveled); // writes delta[] - report_xyz(delta); + report_linear_axis_pos(delta); #endif planner.synchronize(); @@ -165,17 +165,17 @@ planner.get_axis_position_degrees(B_AXIS) }; SERIAL_ECHOPGM("Degrees:"); - report_xyze(deg, 2); + report_all_axis_pos(deg, 2); #endif SERIAL_ECHOPGM("FromStp:"); get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) }; - report_xyze(from_steppers); + report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; SERIAL_ECHOPGM("Diff: "); - report_xyze(diff); + report_all_axis_pos(diff); TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving()); } diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 089e00ab95..73c5b11714 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -83,7 +83,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { + if (fwretract.autoretract_enabled && parser.seen('E') && !parser.seen("XYZ")) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 5a8324362a..41ff7e9765 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -291,12 +291,12 @@ void plan_arc( * Mixing IJ/JK/KI with R will throw an error. * * - R specifies the radius. X or Y (Y or Z / Z or X) is required. - * Omitting both XY/YZ/ZX will throw an error. - * XY/YZ/ZX must differ from the current XY/YZ/ZX. - * Mixing R with IJ/JK/KI will throw an error. + * Omitting both XY/YZ/ZX will throw an error. + * XY/YZ/ZX must differ from the current XY/YZ/ZX. + * Mixing R with IJ/JK/KI will throw an error. * * - P specifies the number of full circles to do - * before the specified arc move. + * before the specified arc move. * * Examples: * diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index bfa4346f03..514d6b7a5d 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -222,7 +222,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(GCODE_MOTION_MODES) if (letter == 'G' - && (codenum <= TERN(ARC_SUPPORT, 3, 1) || codenum == 5 || TERN0(G38_PROBE_TARGET, codenum == 38)) + && (codenum <= TERN(ARC_SUPPORT, 3, 1) || TERN0(BEZIER_CURVE_SUPPORT, codenum == 5) || TERN0(G38_PROBE_TARGET, codenum == 38)) ) { motion_mode_codenum = codenum; TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode); diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 3aec17554b..4270e04c9f 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -226,7 +226,7 @@ public: // Seen any axis parameter static inline bool seen_axis() { - return seen_test('X') || seen_test('Y') || seen_test('Z') || seen_test('E'); + return seen("XYZE"); } #if ENABLED(GCODE_QUOTED_STRINGS) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 6de9c40ac7..46c1e59020 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -125,7 +125,7 @@ #if EITHER(IS_CORE, MARKFORGED_XY) #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else - #define CAN_CALIBRATE(A,B) 1 + #define CAN_CALIBRATE(A,B) true #endif #endif #define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2131fcd678..1f0b301f0a 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3247,7 +3247,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) /** * Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible */ -#if ENABLED(MIXING_EXTRUDER) && ENABLED(DISTINCT_E_FACTORS) +#if BOTH(MIXING_EXTRUDER, DISTINCT_E_FACTORS) #error "MIXING_EXTRUDER can't be used with DISTINCT_E_FACTORS. But you may use SINGLENOZZLE with DISTINCT_E_FACTORS." #endif diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index b389294175..55546caaf1 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -147,6 +147,7 @@ namespace ExtUI { case PID_DONE: ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); break; + case PID_STARTED: break; } ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index faa23665bb..fff31f099b 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -569,7 +569,7 @@ namespace ExtUI { } float getAxisSteps_per_mm(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)]; } @@ -579,7 +579,7 @@ namespace ExtUI { } void setAxisSteps_per_mm(const_float_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value; planner.refresh_positioning(); } @@ -589,7 +589,7 @@ namespace ExtUI { } feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_feedrate_mm_s[E_AXIS_N(extruder - E0)]; } @@ -598,7 +598,7 @@ namespace ExtUI { } void setAxisMaxFeedrate_mm_s(const feedRate_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.set_max_feedrate(E_AXIS_N(extruder - E0), value); } @@ -607,7 +607,7 @@ namespace ExtUI { } float getAxisMaxAcceleration_mm_s2(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(extruder - E0)]; } @@ -616,7 +616,7 @@ namespace ExtUI { } void setAxisMaxAcceleration_mm_s2(const_float_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.set_max_acceleration(E_AXIS_N(extruder - E0), value); } diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index af3d9232b2..425a8ca751 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -37,8 +37,7 @@ inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) { ui.reset_status(); ui.return_to_status(); ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(tool + 1)); - if (mmu2.load_filament_to_nozzle(tool)) - ui.reset_status(); + if (mmu2.load_filament_to_nozzle(tool)) ui.reset_status(); ui.return_to_status(); } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index d7f728ad4b..2ac20c92ef 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -508,7 +508,7 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) // If G38 command is active check Z_MIN_PROBE for ALL movement if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); #endif @@ -747,7 +747,7 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) #if ENABLED(G38_PROBE_AWAY) #define _G38_OPEN_STATE (G38_move >= 4) #else diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 171d9520cb..97be6226ba 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -83,13 +83,13 @@ bool relative_mode; // = false; * Used by 'line_to_current_position' to do a move after changing it. * Used by 'sync_plan_position' to update 'planner.position'. */ -xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, - #ifdef Z_IDLE_HEIGHT - Z_IDLE_HEIGHT - #else - Z_HOME_POS - #endif -}; +#ifdef Z_IDLE_HEIGHT + #define Z_INIT_POS Z_IDLE_HEIGHT +#else + #define Z_INIT_POS Z_HOME_POS +#endif + +xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_INIT_POS }; /** * Cartesian Destination @@ -204,11 +204,7 @@ void report_real_position() { get_cartesian_from_steppers(); xyze_pos_t npos = cartes; npos.e = planner.get_axis_position_mm(E_AXIS); - - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(npos, true); - #endif - + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); report_logical_position(npos); report_more_positions(); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 2b20bba4fb..0ef382a71c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2584,8 +2584,8 @@ void MarlinSettings::postprocess() { void MarlinSettings::reset() { LOOP_XYZE_N(i) { planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]); - planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]); - planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]); + planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]); + planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]); } planner.settings.min_segment_time_us = DEFAULT_MINSEGMENTTIME; diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index de3d45e4b6..8c943048ba 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -62,7 +62,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) #define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS) -#if DISTINCT_E > 1 +#if ENABLED(DISTINCT_E_FACTORS) #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI) #else From a6e5492b088add3589aeac168136369f21614e60 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:51:19 -0500 Subject: [PATCH 0132/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20axis?= =?UTF-8?q?=20counts=20and=20loops?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/types.h | 38 +++++++++---------- Marlin/src/core/utility.cpp | 4 +- Marlin/src/feature/backlash.cpp | 2 +- Marlin/src/feature/dac/dac_mcp4728.cpp | 4 +- Marlin/src/feature/dac/stepper_dac.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 22 +++++------ Marlin/src/feature/joystick.cpp | 2 +- Marlin/src/feature/powerloss.cpp | 8 ++-- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/gcode/calibrate/G33.cpp | 10 ++--- Marlin/src/gcode/calibrate/M425.cpp | 12 +++--- Marlin/src/gcode/calibrate/M666.cpp | 6 +-- Marlin/src/gcode/calibrate/M852.cpp | 2 +- Marlin/src/gcode/config/M200-M205.cpp | 4 +- Marlin/src/gcode/config/M92.cpp | 2 +- Marlin/src/gcode/control/M350_M351.cpp | 8 ++-- Marlin/src/gcode/control/M605.cpp | 2 +- Marlin/src/gcode/feature/L6470/M906.cpp | 2 +- .../src/gcode/feature/digipot/M907-M910.cpp | 6 +-- Marlin/src/gcode/feature/pause/G61.cpp | 6 +-- Marlin/src/gcode/feature/trinamic/M122.cpp | 6 +-- Marlin/src/gcode/feature/trinamic/M569.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M906.cpp | 2 +- .../src/gcode/feature/trinamic/M911-M914.cpp | 4 +- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/gcode/geometry/G53-G59.cpp | 2 +- Marlin/src/gcode/geometry/G92.cpp | 6 +-- Marlin/src/gcode/geometry/M206_M428.cpp | 8 ++-- Marlin/src/gcode/host/M114.cpp | 6 +-- Marlin/src/gcode/motion/M290.cpp | 4 +- Marlin/src/gcode/probe/G38.cpp | 6 +-- Marlin/src/inc/Conditionals_LCD.h | 30 +++++++++++---- Marlin/src/inc/SanityCheck.h | 24 ++++++------ Marlin/src/lcd/marlinui.cpp | 12 +++--- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 2 +- Marlin/src/module/motion.cpp | 10 ++--- Marlin/src/module/planner.cpp | 14 +++---- Marlin/src/module/planner.h | 18 ++++----- Marlin/src/module/scara.cpp | 2 +- Marlin/src/module/settings.cpp | 27 +++++++------ Marlin/src/module/stepper.h | 2 +- Marlin/src/module/tool_change.cpp | 2 +- 45 files changed, 178 insertions(+), 165 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 4011473aa0..98e2bedb00 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -47,25 +47,23 @@ struct IF { typedef L type; }; // - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics // enum AxisEnum : uint8_t { - X_AXIS = 0, A_AXIS = 0, - Y_AXIS = 1, B_AXIS = 1, - Z_AXIS = 2, C_AXIS = 2, - E_AXIS = 3, - X_HEAD = 4, Y_HEAD = 5, Z_HEAD = 6, - E0_AXIS = 3, + X_AXIS = 0, A_AXIS = X_AXIS, + Y_AXIS = 1, B_AXIS = Y_AXIS, + Z_AXIS = 2, C_AXIS = Z_AXIS, + E_AXIS, + X_HEAD, Y_HEAD, Z_HEAD, + E0_AXIS = E_AXIS, E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS, - ALL_AXES = 0xFE, NO_AXIS = 0xFF + ALL_AXES_MASK = 0xFE, NO_AXIS_MASK = 0xFF }; // -// Loop over XYZE axes +// Loop over axes // -#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS) -#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS) -#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N) #define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS) -#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N) +#define LOOP_LINEAR_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LINEAR_AXES) +#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES) +#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES) // // feedRate_t is just a humble float @@ -201,8 +199,8 @@ struct XYval { FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; } FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } #endif FI void reset() { x = y = 0; } FI T magnitude() const { return (T)sqrtf(x*x + y*y); } @@ -312,8 +310,8 @@ struct XYZval { FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; } + #if DISTINCT_AXES > XYZE + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; } #endif FI void reset() { x = y = z = 0; } FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } @@ -427,8 +425,8 @@ struct XYZEval { FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } - #if XYZE_N > XYZE - FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } + #if DISTINCT_AXES > XYZE + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } #endif FI XYZEval copy() const { return *this; } FI XYZEval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; } @@ -518,4 +516,4 @@ struct XYZEval { #undef FI const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; -#define XYZ_CHAR(A) ((char)('X' + A)) +#define AXIS_CHAR(A) ((char)('X' + A)) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 3d7897f95a..f4cdef43c8 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -123,9 +123,9 @@ void safe_delay(millis_t ms) { #endif #if ABL_PLANAR SERIAL_ECHOPGM("ABL Adjustment X"); - LOOP_XYZ(a) { + LOOP_LINEAR_AXES(a) { const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; - SERIAL_CHAR(' ', XYZ_CHAR(a)); + SERIAL_CHAR(' ', AXIS_CHAR(a)); if (v > 0) SERIAL_CHAR('+'); SERIAL_DECIMAL(v); } diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 610cfcb565..5ab95d1577 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -104,7 +104,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const const float f_corr = float(correction) / 255.0f; - LOOP_XYZ(axis) { + LOOP_LINEAR_AXES(axis) { if (distance_mm[axis]) { const bool reversing = TEST(dm,axis); diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 2b57037d99..ddbaced086 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -73,7 +73,7 @@ uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) { uint8_t MCP4728::eepromWrite() { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); Wire.write(SEQWRITE); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(dac_values[i])); Wire.write(lowByte(dac_values[i])); } @@ -135,7 +135,7 @@ void MCP4728::setDrvPct(xyze_uint_t &pct) { */ uint8_t MCP4728::fastWrite() { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { Wire.write(highByte(dac_values[i])); Wire.write(lowByte(dac_values[i])); } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 5170a35511..bb7954cfe0 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -77,7 +77,7 @@ static float dac_amps(int8_t n) { return mcp4728.getValue(dac_order[n]) * 0.125 uint8_t StepperDAC::get_current_percent(const AxisEnum axis) { return mcp4728.getDrvPct(dac_order[axis]); } void StepperDAC::set_current_percents(xyze_uint8_t &pct) { - LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; + LOOP_LOGICAL_AXES(i) dac_channel_pct[i] = pct[dac_order[i]]; mcp4728.setDrvPct(dac_channel_pct); } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index b3265b2c59..d6c88613fd 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -337,7 +337,7 @@ bool I2CPositionEncoder::test_axis() { ec = false; xyze_pos_t startCoord, endCoord; - LOOP_XYZ(a) { + LOOP_LINEAR_AXES(a) { startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } @@ -392,7 +392,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelDistance = endDistance - startDistance; xyze_pos_t startCoord, endCoord; - LOOP_XYZ(a) { + LOOP_LINEAR_AXES(a) { startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } @@ -822,7 +822,7 @@ void I2CPositionEncodersMgr::M860() { const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O'); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); @@ -849,7 +849,7 @@ void I2CPositionEncodersMgr::M861() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_status(idx); @@ -877,7 +877,7 @@ void I2CPositionEncodersMgr::M862() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) test_axis(idx); @@ -908,7 +908,7 @@ void I2CPositionEncodersMgr::M863() { const uint8_t iterations = constrain(parser.byteval('P', 1), 1, 10); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations); @@ -984,7 +984,7 @@ void I2CPositionEncodersMgr::M865() { if (parse()) return; if (!I2CPE_addr) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address()); @@ -1015,7 +1015,7 @@ void I2CPositionEncodersMgr::M866() { const bool hasR = parser.seen_test('R'); if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1053,7 +1053,7 @@ void I2CPositionEncodersMgr::M867() { const int8_t onoff = parser.seenval('S') ? parser.value_int() : -1; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1089,7 +1089,7 @@ void I2CPositionEncodersMgr::M868() { const float newThreshold = parser.seenval('T') ? parser.value_float() : -9999; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) { @@ -1123,7 +1123,7 @@ void I2CPositionEncodersMgr::M869() { if (parse()) return; if (I2CPE_idx == 0xFF) { - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { const uint8_t idx = idx_from_axis(AxisEnum(i)); if ((int8_t)idx >= 0) report_error(idx); diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index 2cc61ec5a3..d8e6cef3b6 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -163,7 +163,7 @@ Joystick joystick; // norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate] xyz_float_t move_dist{0}; float hypot2 = 0; - LOOP_XYZ(i) if (norm_jog[i]) { + LOOP_LINEAR_AXES(i) if (norm_jog[i]) { move_dist[i] = seg_time * norm_jog[i] * TERN(EXTENSIBLE_UI, manual_feedrate_mm_s, planner.settings.max_feedrate_mm_s)[i]; hypot2 += sq(move_dist[i]); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 3764af13d0..db78e7331b 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -549,7 +549,7 @@ void PrintJobRecovery::resume() { TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset); TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift); #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT - LOOP_XYZ(i) update_workspace_offset((AxisEnum)i); + LOOP_LINEAR_AXES(i) update_workspace_offset((AxisEnum)i); #endif // Relative axis modes @@ -581,7 +581,7 @@ void PrintJobRecovery::resume() { if (info.valid_head) { if (info.valid_head == info.valid_foot) { DEBUG_ECHOPGM("current_position: "); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.current_position[i]); } @@ -599,7 +599,7 @@ void PrintJobRecovery::resume() { #if HAS_HOME_OFFSET DEBUG_ECHOPGM("home_offset: "); - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.home_offset[i]); } @@ -608,7 +608,7 @@ void PrintJobRecovery::resume() { #if HAS_POSITION_SHIFT DEBUG_ECHOPGM("position_shift: "); - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (i) DEBUG_CHAR(','); DEBUG_DECIMAL(info.position_shift[i]); } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 92bbb8e6c5..23eafe4bb6 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -220,7 +220,7 @@ void GcodeSuite::G28() { #if ENABLED(MARLIN_DEV_MODE) if (parser.seen_test('S')) { - LOOP_XYZ(a) set_axis_is_at_home((AxisEnum)a); + LOOP_LINEAR_AXES(a) set_axis_is_at_home((AxisEnum)a); sync_plan_position(); SERIAL_ECHOLNPGM("Simulated Homing"); report_current_position(); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index a8de519335..14ac53aeba 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -347,7 +347,7 @@ static float auto_tune_a() { abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; delta_t.reset(); - LOOP_XYZ(axis) { + LOOP_LINEAR_AXES(axis) { delta_t[axis] = diff; calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); delta_t[axis] = 0; @@ -525,7 +525,7 @@ void GcodeSuite::G33() { case 1: test_precision = 0.0f; // forced end - LOOP_XYZ(axis) e_delta[axis] = +Z4(CEN); + LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN); break; case 2: @@ -573,14 +573,14 @@ void GcodeSuite::G33() { // Normalize angles to least-squares if (_angle_results) { float a_sum = 0.0f; - LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis]; - LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; + LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis]; + LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; } // adjust delta_height and endstops by the max amount const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c); delta_height -= z_temp; - LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp; + LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp; } recalc_delta_settings(); NOMORE(zero_std_dev_min, zero_std_dev); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 40441ac08d..432144f491 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -55,8 +55,8 @@ void GcodeSuite::M425() { } }; - LOOP_XYZ(a) { - if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) { + LOOP_LINEAR_AXES(a) { + if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -83,8 +83,8 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); - LOOP_XYZ(a) if (axis_can_calibrate(a)) { - SERIAL_CHAR(' ', XYZ_CHAR(a)); + LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) { + SERIAL_CHAR(' ', AXIS_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); } @@ -96,8 +96,8 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { - SERIAL_CHAR(' ', XYZ_CHAR(a)); + LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { + SERIAL_CHAR(' ', AXIS_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } } diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 75becf13f3..a3a48cd3fc 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -39,11 +39,11 @@ */ void GcodeSuite::M666() { DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING)); - LOOP_XYZ(i) { - if (parser.seen(XYZ_CHAR(i))) { + LOOP_LINEAR_AXES(i) { + if (parser.seen(AXIS_CHAR(i))) { const float v = parser.value_linear_units(); if (v * Z_HOME_DIR <= 0) delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(XYZ_CHAR(i)), "] = ", delta_endstop_adj[i]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", delta_endstop_adj[i]); } } } diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index e52f03b86c..a038dc59fd 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -86,7 +86,7 @@ void GcodeSuite::M852() { // When skew is changed the current position changes if (setval) { - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_MASK); sync_plan_position(); report_current_position(); } diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 55cfc1bf46..06751f41c4 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -86,7 +86,7 @@ void GcodeSuite::M201() { if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; #endif - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a)); @@ -104,7 +104,7 @@ void GcodeSuite::M203() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - LOOP_XYZE(i) + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) { const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a)); diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index e83f5b314f..06c47b8253 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -67,7 +67,7 @@ void GcodeSuite::M92() { if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL"))) return report_M92(true, target_extruder); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { if (i == E_AXIS) { const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index 463bd2ad58..a92238e4bb 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/Marlin/src/gcode/control/M350_M351.cpp @@ -34,7 +34,7 @@ */ void GcodeSuite::M350() { if (parser.seen('S')) LOOP_LE_N(i, 4) stepper.microstep_mode(i, parser.value_byte()); - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte()); + LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte()); if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte()); stepper.microstep_readings(); } @@ -46,15 +46,15 @@ void GcodeSuite::M350() { void GcodeSuite::M351() { if (parser.seenval('S')) switch (parser.value_byte()) { case 1: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1); if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1, -1); break; case 2: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1); if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte(), -1); break; case 3: - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte()); if (parser.seenval('B')) stepper.microstep_ms(4, -1, -1, parser.value_byte()); break; } diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index e0c79f0e54..ac84ac6217 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -141,7 +141,7 @@ HOTEND_LOOP() { DEBUG_ECHOPAIR_P(SP_T_STR, e); - LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", e, "].", AS_CHAR(XYZ_CHAR(a) | 0x20), "=", hotend_offset[e][a]); + LOOP_LINEAR_AXES(a) DEBUG_ECHOPAIR(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 3638fae45b..87614e9c73 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -234,7 +234,7 @@ void GcodeSuite::M906() { const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { report_current = false; diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index e463666207..ee9801eda9 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_SPI - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int()); if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int()); if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int()); @@ -64,7 +64,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_I2C // this one uses actual amps in floating point - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); // Additional extruders use B,C,D for channels 4,5,6. // TODO: Change these parameters because 'E' is used. B? for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) @@ -76,7 +76,7 @@ void GcodeSuite::M907() { const float dac_percent = parser.value_float(); LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent); } - LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float()); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float()); #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index bb11464902..a6d7cb3094 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -71,11 +71,11 @@ void GcodeSuite::G61(void) { else { if (parser.seen("XYZ")) { DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); - LOOP_XYZ(i) { - destination[i] = parser.seen(XYZ_CHAR(i)) + LOOP_LINEAR_AXES(i) { + destination[i] = parser.seen(AXIS_CHAR(i)) ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) : current_position[i]; - DEBUG_CHAR(' ', XYZ_CHAR(i)); + DEBUG_CHAR(' ', AXIS_CHAR(i)); DEBUG_ECHO_F(destination[i]); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index c338e48df4..054d145c8c 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -32,12 +32,12 @@ * M122: Debug TMC drivers */ void GcodeSuite::M122() { - xyze_bool_t print_axis = ARRAY_N_1(XYZE, false); + xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); bool print_all = true; - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } + LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } - if (print_all) LOOP_XYZE(i) print_axis[i] = true; + if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true; if (parser.boolval('I')) restore_stepper_drivers(); diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index a92812004f..8f1c0ed819 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -50,7 +50,7 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder) const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { switch (i) { case X_AXIS: #if AXIS_HAS_STEALTHCHOP(X) diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index e834ebd67d..86e0cd2987 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -52,7 +52,7 @@ void GcodeSuite::M906() { const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 0c5fff7025..c4b4a8772e 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -209,7 +209,7 @@ #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) const uint8_t index = parser.byteval('I'); #endif - LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: @@ -338,7 +338,7 @@ bool report = true; const uint8_t index = parser.byteval('I'); - LOOP_XYZ(i) if (parser.seen(XYZ_CHAR(i))) { + LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) { const int16_t value = parser.value_int(); report = false; switch (i) { diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 34a719c466..33877cd61c 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -149,8 +149,8 @@ void GcodeSuite::get_destination_from_command() { #endif // Get new XYZ position, whether absolute or relative - LOOP_XYZ(i) { - if ( (seen[i] = parser.seenval(XYZ_CHAR(i))) ) { + LOOP_LINEAR_AXES(i) { + if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) { const float v = parser.value_axis_units((AxisEnum)i); if (skip_move) destination[i] = current_position[i]; diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index 05bc522768..a5a9f70a8b 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/Marlin/src/gcode/geometry/G53-G59.cpp @@ -39,7 +39,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) { xyz_float_t new_offset{0}; if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1)) new_offset = coordinate_system[_new]; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { if (position_shift[i] != new_offset[i]) { position_shift[i] = new_offset[i]; update_workspace_offset((AxisEnum)i); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 30620be6f9..a9970b1e9c 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -61,7 +61,7 @@ void GcodeSuite::G92() { #if ENABLED(CNC_COORDINATE_SYSTEMS) && !IS_SCARA case 1: // G92.1 - Zero the Workspace Offset - LOOP_XYZ(i) if (position_shift[i]) { + LOOP_LINEAR_AXES(i) if (position_shift[i]) { position_shift[i] = 0; update_workspace_offset((AxisEnum)i); } @@ -70,7 +70,7 @@ void GcodeSuite::G92() { #if ENABLED(POWER_LOSS_RECOVERY) case 9: // G92.9 - Set Current Position directly (like Marlin 1.0) - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { if (i == E_AXIS) sync_E = true; else sync_XYZE = true; current_position[i] = parser.value_axis_units((AxisEnum)i); @@ -80,7 +80,7 @@ void GcodeSuite::G92() { #endif case 0: - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters v = i == E_AXIS ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index ac2420fcc3..e65540eb8c 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -42,8 +42,8 @@ void M206_report() { * *** In the 2.0 release, it will simply be disabled by default. */ void GcodeSuite::M206() { - LOOP_XYZ(i) - if (parser.seen(XYZ_CHAR(i))) + LOOP_LINEAR_AXES(i) + if (parser.seen(AXIS_CHAR(i))) set_home_offset((AxisEnum)i, parser.value_linear_units()); #if ENABLED(MORGAN_SCARA) @@ -72,7 +72,7 @@ void GcodeSuite::M428() { if (homing_needed_error()) return; xyz_float_t diff; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { diff[i] = base_home_pos((AxisEnum)i) - current_position[i]; if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0) diff[i] = -current_position[i]; @@ -84,7 +84,7 @@ void GcodeSuite::M428() { } } - LOOP_XYZ(i) set_home_offset((AxisEnum)i, diff[i]); + LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]); report_current_position(); LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED); BUZZ(100, 659); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 27b193851d..2d43d33aa1 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -47,8 +47,8 @@ void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) { char str[12]; - LOOP_XYZ(a) { - SERIAL_CHAR(' ', XYZ_CHAR(a), ':'); + LOOP_LINEAR_AXES(a) { + SERIAL_CHAR(' ', AXIS_CHAR(a), ':'); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); } SERIAL_EOL(); @@ -153,7 +153,7 @@ #endif // HAS_L64XX SERIAL_ECHOPGM("Stepper:"); - LOOP_XYZE(i) { + LOOP_LOGICAL_AXES(i) { SERIAL_CHAR(' ', axis_codes[i], ':'); SERIAL_ECHO(stepper.position((AxisEnum)i)); } diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 7e5a017783..0a858090f9 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -69,8 +69,8 @@ */ void GcodeSuite::M290() { #if ENABLED(BABYSTEP_XY) - LOOP_XYZ(a) - if (parser.seenval(XYZ_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) { + LOOP_LINEAR_AXES(a) + if (parser.seenval(AXIS_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) { const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2); babystep.add_mm((AxisEnum)a, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index b06cd47359..606776f402 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -38,7 +38,7 @@ inline void G38_single_probe(const uint8_t move_value) { planner.synchronize(); G38_move = 0; endstops.hit_on_purpose(); - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_MASK); sync_plan_position(); } @@ -49,7 +49,7 @@ inline bool G38_run_probe() { #if MULTIPLE_PROBING > 1 // Get direction of move and retract xyz_float_t retract_mm; - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { const float dist = destination[i] - current_position[i]; retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); } @@ -119,7 +119,7 @@ void GcodeSuite::G38(const int8_t subcode) { ; // If any axis has enough movement, do the move - LOOP_XYZ(i) + LOOP_LINEAR_AXES(i) if (ABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i); // If G38.2 fails throw an error diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 000aa60347..ccfe30947c 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -651,22 +651,38 @@ #endif /** - * DISTINCT_E_FACTORS affects how some E factors are accessed + * Number of Linear Axes (e.g., XYZ) + * All the logical axes except for the tool (E) axis + */ +#ifndef LINEAR_AXES + #define LINEAR_AXES XYZ +#endif + +/** + * Number of Logical Axes (e.g., XYZE) + * All the logical axes that can be commanded directly by G-code. + * Delta maps stepper-specific values to ABC steppers. + */ +#if EXTRUDERS + #define LOGICAL_AXES INCREMENT(LINEAR_AXES) +#else + #define LOGICAL_AXES LINEAR_AXES +#endif + +/** + * DISTINCT_E_FACTORS affects whether Extruders use different settings */ #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 #define DISTINCT_E E_STEPPERS - #define XYZE_N (XYZ + E_STEPPERS) + #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS) #define E_INDEX_N(E) (E) - #define E_AXIS_N(E) AxisEnum(E_AXIS + E) - #define UNUSED_E(E) NOOP #else #undef DISTINCT_E_FACTORS #define DISTINCT_E 1 - #define XYZE_N XYZE + #define DISTINCT_AXES LOGICAL_AXES #define E_INDEX_N(E) 0 - #define E_AXIS_N(E) E_AXIS - #define UNUSED_E(E) UNUSED(E) #endif +#define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) /** * The BLTouch Probe emulates a servo probe diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1f0b301f0a..04f8a45c3b 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2819,22 +2819,22 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, #define _EXTRA_NOTE "" #endif -static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); +static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); -static_assert(COUNT(sanity_arr_2) >= XYZE, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); +static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), "DEFAULT_MAX_FEEDRATE values must be positive."); -static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); -static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); +static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), @@ -2843,8 +2843,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_MAX_ACCEL_EDITING) #ifdef MAX_ACCEL_EDIT_VALUES constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES; - static_assert(COUNT(sanity_arr_4) >= XYZE, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_4) <= XYZE, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements."); + static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2) && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5) && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8), @@ -2855,8 +2855,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_MAX_FR_EDITING) #ifdef MAX_FEEDRATE_EDIT_VALUES constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES; - static_assert(COUNT(sanity_arr_5) >= XYZE, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_5) <= XYZE, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements."); + static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2) && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5) && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8), @@ -2867,8 +2867,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_JERK_EDITING) #ifdef MAX_JERK_EDIT_VALUES constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES; - static_assert(COUNT(sanity_arr_6) >= XYZE, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_6) <= XYZE, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements."); + static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2) && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5) && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8), diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 4c33b924c4..acc3b63ac0 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -684,7 +684,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #if ENABLED(MULTI_MANUAL) int8_t ManualMove::e_index = 0; #endif - AxisEnum ManualMove::axis = NO_AXIS; + AxisEnum ManualMove::axis = NO_AXIS_MASK; /** * If a manual move has been posted and its time has arrived, and if the planner @@ -695,7 +695,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { * * To post a manual move: * - Update current_position to the new place you want to go. - * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES for diagonal moves. + * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_MASK for diagonal moves. * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. * * For kinematic machines: @@ -710,7 +710,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { if (processing) return; // Prevent re-entry from idle() calls // Add a manual move to the queue? - if (axis != NO_AXIS && ELAPSED(millis(), start_time) && !planner.is_full()) { + if (axis != NO_AXIS_MASK && ELAPSED(millis(), start_time) && !planner.is_full()) { const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; @@ -722,7 +722,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #endif // Apply a linear offset to a single axis - if (axis == ALL_AXES) + if (axis == ALL_AXES_MASK) destination = all_axes_destination; else if (axis <= XYZE) { destination = current_position; @@ -731,7 +731,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Reset for the next move offset = 0; - axis = NO_AXIS; + axis = NO_AXIS_MASK; // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to // move_to_destination. This will cause idle() to be called, which can then call this function while the @@ -748,7 +748,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); - axis = NO_AXIS; + axis = NO_AXIS_MASK; #endif } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 044797b749..e751b53446 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -64,7 +64,7 @@ void menu_backlash(); void menu_dac() { static xyze_uint8_t driverPercent; - LOOP_XYZE(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i); + LOOP_LOGICAL_AXES(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }) diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 8e9707de5b..70de53dab5 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -206,7 +206,7 @@ #if ENABLED(MESH_EDIT_MENU) inline void refresh_planner() { - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_MASK); sync_plan_position(); } diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 1171837a57..f923f98c78 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -430,7 +430,7 @@ void ubl_map_move_to_xy() { // Use the built-in manual move handler to move to the mesh point. ui.manual_move.set_destination(xy); - ui.manual_move.soon(ALL_AXES); + ui.manual_move.soon(ALL_AXES_MASK); } inline int32_t grid_index(const uint8_t x, const uint8_t y) { diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 8f71d52ec8..45c947e790 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -395,7 +395,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } uint8_t found_displacement = false; - LOOP_XYZE(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) { + LOOP_LOGICAL_AXES(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) { found_displacement = true; displacement = _displacement; uint8_t axis_offset = parser.byteval('J'); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 97be6226ba..427aea80b1 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -124,7 +124,7 @@ xyze_pos_t destination; // {0} "Offsets for the first hotend must be 0.0." ); // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ] - HOTEND_LOOP() LOOP_XYZ(a) hotend_offset[e][a] = tmp[a][e]; + HOTEND_LOOP() LOOP_LINEAR_AXES(a) hotend_offset[e][a] = tmp[a][e]; #if ENABLED(DUAL_X_CARRIAGE) hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS); #endif @@ -282,7 +282,7 @@ void report_current_position_projected() { void quickstop_stepper() { planner.quick_stop(); planner.synchronize(); - set_current_from_steppers_for_axis(ALL_AXES); + set_current_from_steppers_for_axis(ALL_AXES_MASK); sync_plan_position(); } @@ -360,7 +360,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { planner.unapply_modifiers(pos, true); #endif - if (axis == ALL_AXES) + if (axis == ALL_AXES_MASK) current_position = pos; else current_position[axis] = pos[axis]; @@ -681,7 +681,7 @@ void restore_feedrate_and_scaling() { #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); + SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -1951,7 +1951,7 @@ void set_axis_is_at_home(const AxisEnum axis) { #if HAS_WORKSPACE_OFFSET void update_workspace_offset(const AxisEnum axis) { workspace_offset[axis] = home_offset[axis] + position_shift[axis]; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); } #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index f11f273867..dde6e89a1f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -136,9 +136,9 @@ planner_settings_t Planner::settings; // Initialized by settings.load( laser_state_t Planner::laser_inline; // Current state for blocks #endif -uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 +uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 -float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step +float Planner::steps_to_mm[DISTINCT_AXES]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J @@ -2201,7 +2201,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, float speed_factor = 1.0f; // factor <1 decreases speed // Linear axes first with less logic - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { current_speed[i] = steps_dist_mm[i] * inverse_secs; const feedRate_t cs = ABS(current_speed[i]), max_fr = settings.max_feedrate_mm_s[i]; @@ -2593,7 +2593,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; uint8_t limited = 0; - TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) { + TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) { const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis if (jerk > maxj) { // cs > mj : New current speed too fast? @@ -2631,7 +2631,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, vmax_junction = previous_nominal_speed; // Now limit the jerk in all axes. - TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(axis) { + TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(axis) { // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop. float v_exit = previous_speed[axis] * smaller_speed_factor, v_entry = current_speed[axis]; @@ -3033,7 +3033,7 @@ void Planner::reset_acceleration_rates() { #define AXIS_CONDITION true #endif uint32_t highest_rate = 1; - LOOP_XYZE_N(i) { + LOOP_DISTINCT_AXES(i) { max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i]; if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } @@ -3046,7 +3046,7 @@ void Planner::reset_acceleration_rates() { * Must be called whenever settings.axis_steps_per_mm changes! */ void Planner::refresh_positioning() { - LOOP_XYZE_N(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i]; + LOOP_DISTINCT_AXES(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i]; set_position_mm(current_position); reset_acceleration_rates(); } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 30eeb758a4..db83792b45 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -268,10 +268,10 @@ typedef struct block_t { #endif typedef struct { - uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE + uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES], // (mm/s^2) M201 XYZE min_segment_time_us; // (µs) M205 B - float axis_steps_per_mm[XYZE_N]; // (steps) M92 XYZE - Steps per millimeter - feedRate_t max_feedrate_mm_s[XYZE_N]; // (mm/s) M203 XYZE - Max speeds + float axis_steps_per_mm[DISTINCT_AXES]; // (steps) M92 XYZE - Steps per millimeter + feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves. retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. @@ -360,13 +360,13 @@ class Planner { static laser_state_t laser_inline; #endif - static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 - static float steps_to_mm[XYZE_N]; // Millimeters per step + static uint32_t max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 + static float steps_to_mm[DISTINCT_AXES]; // Millimeters per step #if HAS_JUNCTION_DEVIATION - static float junction_deviation_mm; // (mm) M205 J + static float junction_deviation_mm; // (mm) M205 J #if HAS_LINEAR_E_JERK - static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm + static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm #endif #endif @@ -1014,13 +1014,13 @@ class Planner { FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) { float magnitude_sq = 0; - LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); + LOOP_LOGICAL_AXES(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); vector *= RSQRT(magnitude_sq); } FORCE_INLINE static float limit_value_by_axis_maximum(const_float_t max_value, xyze_float_t &unit_vec) { float limit_value = max_value; - LOOP_XYZE(idx) { + LOOP_LOGICAL_AXES(idx) { if (unit_vec[idx]) { if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx]) limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]); diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index e058804c90..b0544c7791 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -254,7 +254,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE // Do this here all at once for Delta, because // XYZ isn't ABC. Applying this per-tower would // give the impression that they are the same. - LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i); + LOOP_LINEAR_AXES(i) set_axis_is_at_home((AxisEnum)i); sync_plan_position(); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 0ef382a71c..56e3c86fd4 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -194,7 +194,7 @@ typedef struct SettingsDataStruct { // // DISTINCT_E_FACTORS // - uint8_t esteppers; // XYZE_N - XYZ + uint8_t esteppers; // DISTINCT_AXES - LINEAR_AXES planner_settings_t planner_settings; @@ -385,7 +385,7 @@ typedef struct SettingsDataStruct { // HAS_MOTOR_CURRENT_PWM // #ifndef MOTOR_CURRENT_COUNT - #define MOTOR_CURRENT_COUNT 3 + #define MOTOR_CURRENT_COUNT LINEAR_AXES #endif uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E @@ -516,7 +516,7 @@ void MarlinSettings::postprocess() { #endif // Software endstops depend on home_offset - LOOP_XYZ(i) { + LOOP_LINEAR_AXES(i) { update_workspace_offset((AxisEnum)i); update_software_endstops((AxisEnum)i); } @@ -637,9 +637,8 @@ void MarlinSettings::postprocess() { working_crc = 0; // clear before first "real data" + const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES; _FIELD_TEST(esteppers); - - const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - XYZ; EEPROM_WRITE(esteppers); // @@ -1513,16 +1512,16 @@ void MarlinSettings::postprocess() { { // Get only the number of E stepper parameters previously stored // Any steppers added later are set to their defaults - uint32_t tmp1[XYZ + esteppers]; - float tmp2[XYZ + esteppers]; - feedRate_t tmp3[XYZ + esteppers]; + uint32_t tmp1[LINEAR_AXES + esteppers]; + float tmp2[LINEAR_AXES + esteppers]; + feedRate_t tmp3[LINEAR_AXES + esteppers]; EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2 EEPROM_READ(planner.settings.min_segment_time_us); EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s - if (!validating) LOOP_XYZE_N(i) { - const bool in = (i < esteppers + XYZ); + if (!validating) LOOP_DISTINCT_AXES(i) { + const bool in = (i < esteppers + LINEAR_AXES); planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]); planner.settings.axis_steps_per_mm[i] = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]); planner.settings.max_feedrate_mm_s[i] = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]); @@ -1540,7 +1539,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummyf); #endif #else - for (uint8_t q = XYZE; q--;) EEPROM_READ(dummyf); + for (uint8_t q = LOGICAL_AXES; q--;) EEPROM_READ(dummyf); #endif EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); @@ -2582,7 +2581,7 @@ void MarlinSettings::postprocess() { * M502 - Reset Configuration */ void MarlinSettings::reset() { - LOOP_XYZE_N(i) { + LOOP_DISTINCT_AXES(i) { planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]); planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]); planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]); @@ -2706,7 +2705,7 @@ void MarlinSettings::reset() { constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z."); #if HAS_PROBE_XY_OFFSET - LOOP_XYZ(a) probe.offset[a] = dpo[a]; + LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a]; #else probe.offset.set(0, 0, dpo[Z_AXIS]); #endif @@ -3856,7 +3855,7 @@ void MarlinSettings::reset() { ); #elif HAS_MOTOR_CURRENT_SPI SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: - LOOP_XYZE(q) { // X Y Z E (map to X Y Z E0 by default) + LOOP_LOGICAL_AXES(q) { // X Y Z E (map to X Y Z E0 by default) SERIAL_CHAR(' ', axis_codes[q]); SERIAL_ECHO(stepper.motor_current_setting[q]); } diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 5ddd762aa9..020f72e9e6 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -250,7 +250,7 @@ class Stepper { #ifndef PWM_MOTOR_CURRENT #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT #endif - #define MOTOR_CURRENT_COUNT XYZ + #define MOTOR_CURRENT_COUNT LINEAR_AXES #elif HAS_MOTOR_CURRENT_SPI static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT; #define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 559caa7f98..03e85fdd84 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1181,7 +1181,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { sync_plan_position(); #if ENABLED(DELTA) - //LOOP_XYZ(i) update_software_endstops(i); // or modify the constrain function + //LOOP_LINEAR_AXES(i) update_software_endstops(i); // or modify the constrain function const bool safe_to_move = current_position.z < delta_clip_start_height - 1; #else constexpr bool safe_to_move = true; From 926a7f27c66e777b5a838a87ee8931d35095fd03 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:52:10 -0500 Subject: [PATCH 0133/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Simplify=20TMC?= =?UTF-8?q?=20utilities=20for=20more=20axes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/feature/tmc_util.cpp | 6 +++--- Marlin/src/feature/tmc_util.h | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5cd0269bac..5ef575a30f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1488,7 +1488,7 @@ void setup() { #endif #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) - SETUP_RUN(test_tmc_connection(true, true, true, true)); + SETUP_RUN(test_tmc_connection()); #endif #if HAS_DRIVER_SAFE_POWER_PROTECT diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index a4f71414a6..9c4fbf08df 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -211,7 +211,7 @@ SERIAL_PRINTLN(data.drv_status, HEX); if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); - TERN_(TMC_DEBUG, tmc_report_all(true, true, true, true)); + TERN_(TMC_DEBUG, tmc_report_all()); kill(PSTR("Driver error")); } #endif @@ -889,7 +889,7 @@ * M122 report functions */ - void tmc_report_all(bool print_x, const bool print_y, const bool print_z, const bool print_e) { + void tmc_report_all(const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/, const bool print_e/*=true*/) { #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) TMC_REPORT("\t", TMC_CODES); @@ -1214,7 +1214,7 @@ static bool test_connection(TMC &st) { return test_result; } -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e) { +void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/, const bool test_e/*=true*/) { uint8_t axis_connection = 0; if (test_x) { diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 1767313ba2..a0e07ab8a8 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -341,13 +341,13 @@ void tmc_print_current(TMC &st) { #endif void monitor_tmc_drivers(); -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e); +void test_tmc_connection(const bool test_x=true, const bool test_y=true, const bool test_z=true, const bool test_e=true); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(const bool print_x, const bool print_y, const bool print_z, const bool print_e); + void tmc_report_all(const bool print_x=true, const bool print_y=true, const bool print_z=true, const bool print_e=true); void tmc_get_registers(const bool print_x, const bool print_y, const bool print_z, const bool print_e); #endif From 18b1ccda276d0474fa3d71912cd0921857ac5cf8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:52:41 -0500 Subject: [PATCH 0134/2168] =?UTF-8?q?=E2=9C=85=20Fix=20tests=20for=20EXTRU?= =?UTF-8?q?DERS=200?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/mega2560 | 10 ++++++++-- buildroot/tests/rambo | 10 +++++++++- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 7bbf29e630..8e63c6e7b1 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -171,7 +171,10 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # Test Laser features with 12864 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 @@ -181,7 +184,10 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air As # Test Laser features with 44780 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 87772a988b..9869b96b34 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -45,6 +45,10 @@ restore_configs opt_set MOTHERBOARD BOARD_RAMBO \ EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 Z_HOME_DIR 1 \ DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' \ LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ @@ -58,7 +62,11 @@ exec_test $1 $2 "Rambo CNC Configuration" "$3" # Rambo heated bed only # restore_configs -opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 +opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "Rambo heated bed only" "$3" From 02f904dbf9df999264099a26c563b07b1d163df4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:53:52 -0500 Subject: [PATCH 0135/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Minimize=20endst?= =?UTF-8?q?op=20bits?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/endstops.cpp | 17 ++++--- Marlin/src/module/endstops.h | 87 ++++++++++++++++++++++------------ Marlin/src/module/stepper.cpp | 8 ++-- 3 files changed, 68 insertions(+), 44 deletions(-) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 2ac20c92ef..d0befe71fb 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -56,12 +56,12 @@ Endstops endstops; // private: bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load() -volatile uint8_t Endstops::hit_state; -Endstops::esbits_t Endstops::live_state = 0; +volatile Endstops::endstop_mask_t Endstops::hit_state; +Endstops::endstop_mask_t Endstops::live_state = 0; #if ENDSTOP_NOISE_THRESHOLD - Endstops::esbits_t Endstops::validated_live_state; + Endstops::endstop_mask_t Endstops::validated_live_state; uint8_t Endstops::endstop_poll_count; #endif @@ -356,7 +356,7 @@ void Endstops::resync() { #endif void Endstops::event_handler() { - static uint8_t prev_hit_state; // = 0 + static endstop_mask_t prev_hit_state; // = 0 if (hit_state == prev_hit_state) return; prev_hit_state = hit_state; if (hit_state) { @@ -364,15 +364,14 @@ void Endstops::event_handler() { char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else - #define _SET_STOP_CHAR(A,C) ; + #define _SET_STOP_CHAR(A,C) NOOP #endif #define _ENDSTOP_HIT_ECHO(A,C) do{ \ - SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); \ - _SET_STOP_CHAR(A,C); }while(0) + SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); _SET_STOP_CHAR(A,C); }while(0) #define _ENDSTOP_HIT_TEST(A,C) \ - if (TEST(hit_state, A ##_MIN) || TEST(hit_state, A ##_MAX)) \ + if (TERN0(HAS_##A##_MIN, TEST(hit_state, A##_MIN)) || TERN0(HAS_##A##_MAX, TEST(hit_state, A##_MAX))) \ _ENDSTOP_HIT_ECHO(A,C) #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X') @@ -659,7 +658,7 @@ void Endstops::update() { * still exist. The only way to reduce them further is to increase the number of samples. * To reduce the chance to 1% (1/128th) requires 7 samples (adding 7ms of delay). */ - static esbits_t old_live_state; + static endstop_mask_t old_live_state; if (old_live_state != live_state) { endstop_poll_count = ENDSTOP_NOISE_THRESHOLD; old_live_state = live_state; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 13e814aa1f..7d18aaf850 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -28,50 +28,75 @@ #include "../inc/MarlinConfig.h" #include +#define __ES_ITEM(N) N, +#define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) + enum EndstopEnum : char { - X_MIN, Y_MIN, Z_MIN, Z_MIN_PROBE, - X_MAX, Y_MAX, Z_MAX, - X2_MIN, X2_MAX, - Y2_MIN, Y2_MAX, - Z2_MIN, Z2_MAX, - Z3_MIN, Z3_MAX, - Z4_MIN, Z4_MAX + _ES_ITEM(HAS_X_MIN, X_MIN) + _ES_ITEM(HAS_X_MAX, X_MAX) + _ES_ITEM(HAS_Y_MIN, Y_MIN) + _ES_ITEM(HAS_Y_MAX, Y_MAX) + _ES_ITEM(HAS_Z_MIN, Z_MIN) + _ES_ITEM(HAS_Z_MAX, Z_MAX) + #if ENABLED(X_DUAL_ENDSTOPS) + _ES_ITEM(HAS_X_MIN, X2_MIN) + _ES_ITEM(HAS_X_MAX, X2_MAX) + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + _ES_ITEM(HAS_Y_MIN, Y2_MIN) + _ES_ITEM(HAS_Y_MAX, Y2_MAX) + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + _ES_ITEM(HAS_Z_MIN, Z2_MIN) + _ES_ITEM(HAS_Z_MAX, Z2_MAX) + #if NUM_Z_STEPPER_DRIVERS >= 3 + _ES_ITEM(HAS_Z_MIN, Z3_MIN) + _ES_ITEM(HAS_Z_MAX, Z3_MAX) + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + _ES_ITEM(HAS_Z_MIN, Z4_MIN) + _ES_ITEM(HAS_Z_MAX, Z4_MAX) + #endif + #endif + _ES_ITEM(HAS_Z_MIN_PROBE_PIN, Z_MIN_PROBE) + NUM_ENDSTOP_STATES }; #define X_ENDSTOP (x_home_dir(active_extruder) < 0 ? X_MIN : X_MAX) #define Y_ENDSTOP (Y_HOME_DIR < 0 ? Y_MIN : Y_MAX) #define Z_ENDSTOP (Z_HOME_DIR < 0 ? TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE) : Z_MAX) +#undef __ES_ITEM +#undef _ES_ITEM + class Endstops { public: - #if HAS_EXTRA_ENDSTOPS - typedef uint16_t esbits_t; - #if ENABLED(X_DUAL_ENDSTOPS) - static float x2_endstop_adj; - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - static float y2_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - static float z2_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 - static float z3_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 - static float z4_endstop_adj; - #endif - #else - typedef uint8_t esbits_t; + + typedef IF<(NUM_ENDSTOP_STATES > 8), uint16_t, uint8_t>::type endstop_mask_t; + + #if ENABLED(X_DUAL_ENDSTOPS) + static float x2_endstop_adj; + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + static float y2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + static float z2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + static float z3_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + static float z4_endstop_adj; #endif private: static bool enabled, enabled_globally; - static esbits_t live_state; - static volatile uint8_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index + static endstop_mask_t live_state; + static volatile endstop_mask_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index #if ENDSTOP_NOISE_THRESHOLD - static esbits_t validated_live_state; + static endstop_mask_t validated_live_state; static uint8_t endstop_poll_count; // Countdown from threshold for polling #endif @@ -107,12 +132,12 @@ class Endstops { /** * Get Endstop hit state. */ - FORCE_INLINE static uint8_t trigger_state() { return hit_state; } + FORCE_INLINE static endstop_mask_t trigger_state() { return hit_state; } /** * Get current endstops state */ - FORCE_INLINE static esbits_t state() { + FORCE_INLINE static endstop_mask_t state() { return #if ENDSTOP_NOISE_THRESHOLD validated_live_state diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ff2be0c356..e8f578ae91 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -260,12 +260,12 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ if (A##_HOME_DIR < 0) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (TERN0(HAS_##A##_MAX, !(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MAX, !(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ } \ else { \ From 458677c63a3f9ae32c988e2ab10d8f3a0935bf50 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 22:56:05 -0500 Subject: [PATCH 0136/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20axis?= =?UTF-8?q?=20homing/trusted=20state=20bits?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/motion.cpp | 18 ++++++++++-------- Marlin/src/module/motion.h | 21 +++++++++++---------- 2 files changed, 21 insertions(+), 18 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 427aea80b1..52d9dec904 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1181,18 +1181,20 @@ void prepare_line_to_destination() { #if HAS_ENDSTOPS - uint8_t axis_homed, axis_trusted; // = 0 + linear_axis_bits_t axis_homed, axis_trusted; // = 0 - uint8_t axes_should_home(uint8_t axis_bits/*=0x07*/) { - #define SHOULD_HOME(A) TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(A) - // Clear test bits that are trusted - if (TEST(axis_bits, X_AXIS) && SHOULD_HOME(X_AXIS)) CBI(axis_bits, X_AXIS); - if (TEST(axis_bits, Y_AXIS) && SHOULD_HOME(Y_AXIS)) CBI(axis_bits, Y_AXIS); - if (TEST(axis_bits, Z_AXIS) && SHOULD_HOME(Z_AXIS)) CBI(axis_bits, Z_AXIS); + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits/*=linear_bits*/) { + auto set_should = [](linear_axis_bits_t &b, AxisEnum a) { + if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) + CBI(b, a); + }; + set_should(axis_bits, X_AXIS); // Clear test bits that are trusted + set_should(axis_bits, Y_AXIS); + set_should(axis_bits, Z_AXIS); return axis_bits; } - bool homing_needed_error(uint8_t axis_bits/*=0x07*/) { + bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { if ((axis_bits = axes_should_home(axis_bits))) { PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[strlen_P(home_first)+1]; diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index e01978c852..15713e6d4d 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -326,7 +326,8 @@ void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); /** * Homing and Trusted Axes */ -constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS); +typedef IF<(LINEAR_AXES>8), uint16_t, uint8_t>::type linear_axis_bits_t; +constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1; void set_axis_is_at_home(const AxisEnum axis); @@ -340,23 +341,23 @@ void set_axis_is_at_home(const AxisEnum axis); * Flags that the position is trusted in each linear axis. Set when homed. * Cleared whenever a stepper powers off, potentially losing its position. */ - extern uint8_t axis_homed, axis_trusted; + extern linear_axis_bits_t axis_homed, axis_trusted; void homeaxis(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); - uint8_t axes_should_home(uint8_t axis_bits=0x07); - bool homing_needed_error(uint8_t axis_bits=0x07); + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits); + bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits); FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; } FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } - FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = xyz_bits; } + FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = linear_bits; } #else - constexpr uint8_t axis_homed = xyz_bits, axis_trusted = xyz_bits; // Zero-endstop machines are always homed and trusted + constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted FORCE_INLINE void homeaxis(const AxisEnum axis) {} FORCE_INLINE void set_axis_never_homed(const AxisEnum) {} - FORCE_INLINE uint8_t axes_should_home(uint8_t=0x07) { return false; } - FORCE_INLINE bool homing_needed_error(uint8_t=0x07) { return false; } + FORCE_INLINE linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } + FORCE_INLINE bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) {} FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) {} FORCE_INLINE void set_all_unhomed() {} @@ -369,9 +370,9 @@ FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_h FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return xyz_bits == (axis_homed & xyz_bits); } +FORCE_INLINE bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } FORCE_INLINE bool homing_needed() { return !all_axes_homed(); } -FORCE_INLINE bool all_axes_trusted() { return xyz_bits == (axis_trusted & xyz_bits); } +FORCE_INLINE bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) From 0dae140080c611089f8cb7e937c9f48516eb944d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 May 2021 23:30:49 -0500 Subject: [PATCH 0137/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20DELTA=20with=20S?= =?UTF-8?q?ENSORLESS=5FPROBING?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/module/probe.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ccfe30947c..de97712a08 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -818,7 +818,7 @@ #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 #endif - #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) #define HAS_CUSTOM_PROBE_PIN 1 #endif #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index be991c1d52..655b8cc249 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -507,7 +507,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { // Check to see if the probe was triggered const bool probe_triggered = #if BOTH(DELTA, SENSORLESS_PROBING) - endstops.trigger_state() & (_BV(X_MIN) | _BV(Y_MIN) | _BV(Z_MIN)) + endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)) #endif From 49771c4a9ed2afa1e572f82a24b5edb3de120f78 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 19 May 2021 00:21:34 -0500 Subject: [PATCH 0138/2168] =?UTF-8?q?=F0=9F=8E=A8=20Flags=20for=20homing?= =?UTF-8?q?=20directions?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 2 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 21 ++++++++- Marlin/src/inc/Conditionals_adv.h | 6 +++ Marlin/src/inc/Conditionals_post.h | 16 +++---- Marlin/src/inc/SanityCheck.h | 46 +++++++++---------- .../screens/move_axis_screen.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 4 +- Marlin/src/module/endstops.cpp | 22 ++++----- Marlin/src/module/endstops.h | 6 +-- Marlin/src/module/motion.cpp | 10 ++-- Marlin/src/module/motion.h | 4 +- Marlin/src/module/scara.cpp | 6 +-- Marlin/src/module/stepper.cpp | 6 +-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 6 +-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 6 +-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 6 +-- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 6 +-- Marlin/src/pins/pins_postprocess.h | 32 ++++++------- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 4 +- Marlin/src/pins/sam/pins_ARCHIM2.h | 4 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 6 +-- .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 6 +-- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 6 +-- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 6 +-- 27 files changed, 131 insertions(+), 114 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index a6286ba6f4..46a876a836 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -144,7 +144,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (2) conflict with Z4 pins!" #elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with other pins!" - #elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN) + #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" #elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index db78e7331b..a7474794de 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -375,7 +375,7 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX float z_now = z_raised; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 23eafe4bb6..aacfcfa42f 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -73,7 +73,7 @@ current_position.set(0.0, 0.0); sync_plan_position(); - const int x_axis_home_dir = x_home_dir(active_extruder); + const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index de97712a08..545ee403a1 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -814,6 +814,23 @@ #endif #endif // FILAMENT_RUNOUT_SENSOR +// Homing to Min or Max +#if X_HOME_DIR > 0 + #define X_HOME_TO_MAX 1 +#elif X_HOME_DIR < 0 + #define X_HOME_TO_MIN 1 +#endif +#if Y_HOME_DIR > 0 + #define Y_HOME_TO_MAX 1 +#elif Y_HOME_DIR < 0 + #define Y_HOME_TO_MIN 1 +#endif +#if Z_HOME_DIR > 0 + #define Z_HOME_TO_MAX 1 +#elif Z_HOME_DIR < 0 + #define Z_HOME_TO_MIN 1 +#endif + #if HAS_BED_PROBE #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 @@ -821,7 +838,7 @@ #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) #define HAS_CUSTOM_PROBE_PIN 1 #endif - #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT @@ -843,7 +860,7 @@ #undef USE_PROBE_FOR_Z_HOMING #endif -#if Z_HOME_DIR > 0 +#if Z_HOME_TO_MAX #define HOME_Z_FIRST // If homing away from BED do Z first #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 44ea34a490..95a7ada83f 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -391,6 +391,12 @@ #define POLL_JOG #endif +#if X2_HOME_DIR > 0 + #define X2_HOME_TO_MAX 1 +#elif X2_HOME_DIR < 0 + #define X2_HOME_TO_MIN 1 +#endif + #ifndef HOMING_BUMP_MM #define HOMING_BUMP_MM { 0, 0, 0 } #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 46c1e59020..d86b02bdc2 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -155,7 +155,7 @@ #ifdef MANUAL_X_HOME_POS #define X_HOME_POS MANUAL_X_HOME_POS #else - #define X_END_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) + #define X_END_POS TERN(X_HOME_TO_MIN, X_MIN_POS, X_MAX_POS) #if ENABLED(BED_CENTER_AT_0_0) #define X_HOME_POS TERN(DELTA, 0, X_END_POS) #else @@ -166,7 +166,7 @@ #ifdef MANUAL_Y_HOME_POS #define Y_HOME_POS MANUAL_Y_HOME_POS #else - #define Y_END_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) + #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) #if ENABLED(BED_CENTER_AT_0_0) #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) #else @@ -177,7 +177,7 @@ #ifdef MANUAL_Z_HOME_POS #define Z_HOME_POS MANUAL_Z_HOME_POS #else - #define Z_HOME_POS (Z_HOME_DIR < 0 ? Z_MIN_POS : Z_MAX_POS) + #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) #endif /** @@ -798,7 +798,7 @@ * X_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(X_DUAL_ENDSTOPS) - #if X_HOME_DIR > 0 + #if X_HOME_TO_MAX #ifndef X2_MAX_ENDSTOP_INVERTING #if X2_USE_ENDSTOP == _XMIN_ #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -921,7 +921,7 @@ * Y_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(Y_DUAL_ENDSTOPS) - #if Y_HOME_DIR > 0 + #if Y_HOME_TO_MAX #ifndef Y2_MAX_ENDSTOP_INVERTING #if Y2_USE_ENDSTOP == _XMIN_ #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1045,7 +1045,7 @@ */ #if ENABLED(Z_MULTI_ENDSTOPS) - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z2_MAX_ENDSTOP_INVERTING #if Z2_USE_ENDSTOP == _XMIN_ #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1164,7 +1164,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 3 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z3_MAX_ENDSTOP_INVERTING #if Z3_USE_ENDSTOP == _XMIN_ #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1284,7 +1284,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 4 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z4_MAX_ENDSTOP_INVERTING #if Z4_USE_ENDSTOP == _XMIN_ #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 04f8a45c3b..b9eacd0a1a 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1682,7 +1682,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal * Allen Key * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ -#if BOTH(Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && Z_HOME_DIR < 0 +#if ALL(Z_HOME_TO_MIN, Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #error "You can't home to a Z min endstop with a Z_PROBE_ALLEN_KEY." #endif @@ -1700,7 +1700,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop." #elif !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) #error "DUAL_X_CARRIAGE requires X2_HOME_POS, X2_MIN_POS, and X2_MAX_POS." - #elif X_HOME_DIR != -1 || X2_HOME_DIR != 1 + #elif X_HOME_TO_MAX || X2_HOME_TO_MIN #error "DUAL_X_CARRIAGE requires X_HOME_DIR -1 and X2_HOME_DIR 1." #endif #endif @@ -2089,25 +2089,25 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal // Delta and Cartesian use 3 homing endstops #if NONE(IS_SCARA, SPI_ENDSTOPS) - #if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG) + #if X_HOME_TO_MIN && DISABLED(USE_XMIN_PLUG) #error "Enable USE_XMIN_PLUG when homing X to MIN." - #elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG) + #elif X_HOME_TO_MAX && DISABLED(USE_XMAX_PLUG) #error "Enable USE_XMAX_PLUG when homing X to MAX." - #elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG) + #elif Y_HOME_TO_MIN && DISABLED(USE_YMIN_PLUG) #error "Enable USE_YMIN_PLUG when homing Y to MIN." - #elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG) + #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) #error "Enable USE_YMAX_PLUG when homing Y to MAX." #endif #endif // Z homing direction and plug usage flags - #if Z_HOME_DIR < 0 && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) + #if Z_HOME_TO_MIN && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) #error "Enable USE_ZMIN_PLUG when homing Z to MIN." - #elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING) + #elif Z_HOME_TO_MAX && ENABLED(USE_PROBE_FOR_Z_HOMING) #error "Z_HOME_DIR must be -1 when homing Z with the probe." #elif BOTH(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) #error "Z_MULTI_ENDSTOPS is incompatible with USE_PROBE_FOR_Z_HOMING." - #elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG) + #elif Z_HOME_TO_MAX && DISABLED(USE_ZMAX_PLUG) #error "Enable USE_ZMAX_PLUG when homing Z to MAX." #endif #endif @@ -2630,17 +2630,17 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS) - #if X_SENSORLESS && X_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_XMIN) + #if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMIN (or ENDSTOPPULLUPS) when homing to X_MIN." - #elif X_SENSORLESS && X_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_XMAX) + #elif X_SENSORLESS && X_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_XMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) when homing to X_MAX." - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_YMIN) + #elif Y_SENSORLESS && Y_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_YMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) when homing to Y_MIN." - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_YMAX) + #elif Y_SENSORLESS && Y_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_YMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) when homing to Y_MAX." - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_ZMIN) + #elif Z_SENSORLESS && Z_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_ZMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_ZMAX) + #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." #endif #endif @@ -2650,37 +2650,37 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #warning "SPI_ENDSTOPS may be unreliable with QUICK_HOME. Adjust back-offs for better results." #endif #else - #if X_SENSORLESS && X_HOME_DIR < 0 && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #if X_SENSORLESS && X_HOME_TO_MIN && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING #if X_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = true when homing to X_MIN." #else #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to X_MIN." #endif - #elif X_SENSORLESS && X_HOME_DIR > 0 && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #elif X_SENSORLESS && X_HOME_TO_MAX && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING #if X_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = true when homing to X_MAX." #else #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to X_MAX." #endif - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #elif Y_SENSORLESS && Y_HOME_TO_MIN && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING #if Y_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = true when homing to Y_MIN." #else #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MIN." #endif - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #elif Y_SENSORLESS && Y_HOME_TO_MAX && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING #if Y_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = true when homing to Y_MAX." #else #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MAX." #endif - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #elif Z_SENSORLESS && Z_HOME_TO_MIN && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING #if Z_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = true when homing to Z_MIN." #else #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MIN." #endif - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #elif Z_SENSORLESS && Z_HOME_TO_MAX && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING #if Z_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = true when homing to Z_MAX." #else @@ -2918,9 +2918,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING." #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." - #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR > 0 + #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX #error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX." - #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR < 0 && !defined(POWER_LOSS_ZHOME_POS) + #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." #endif #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp index 67ea002d34..9406572c33 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp @@ -66,7 +66,7 @@ void MoveAxisScreen::onRedraw(draw_mode_t what) { w.adjuster( 14, GET_TEXT_F(MSG_AXIS_E4), mydata.e_rel[3], canMove(E3)); #endif #endif - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN w.button(24, GET_TEXT_F(MSG_MOVE_Z_TO_TOP), !axis_should_home(Z_AXIS)); #endif w.increments(); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index acc3b63ac0..1d312535c9 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -488,12 +488,12 @@ bool MarlinUI::get_blink() { if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); - #if DISABLED(DELTA) && Z_HOME_DIR < 0 + #if NONE(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (homed) { - #if ENABLED(DELTA) || Z_HOME_DIR != -1 + #if EITHER(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index d0befe71fb..7a452f1fdd 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -513,14 +513,8 @@ void Endstops::update() { #endif // With Dual X, endstops are only checked in the homing direction for the active extruder - #if ENABLED(DUAL_X_CARRIAGE) - #define E0_ACTIVE stepper.last_moved_extruder == 0 - #define X_MIN_TEST() ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE)) - #define X_MAX_TEST() ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE)) - #else - #define X_MIN_TEST() true - #define X_MAX_TEST() true - #endif + #define X_MIN_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MIN, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MIN, stepper.last_moved_extruder != 0)) + #define X_MAX_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MAX, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MAX, stepper.last_moved_extruder != 0)) // Use HEAD for core axes, AXIS for others #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) @@ -765,7 +759,7 @@ void Endstops::update() { if (stepper.axis_is_moving(X_AXIS)) { if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction - #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_DIR < 0) + #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_TO_MIN) PROCESS_ENDSTOP_X(MIN); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MIN); @@ -779,7 +773,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_DIR > 0) + #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_TO_MAX) PROCESS_ENDSTOP_X(MAX); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MAX); @@ -796,7 +790,7 @@ void Endstops::update() { if (stepper.axis_is_moving(Y_AXIS)) { if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_DIR < 0) + #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) PROCESS_ENDSTOP_Y(MIN); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); @@ -810,7 +804,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_DIR > 0) + #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) PROCESS_ENDSTOP_Y(MAX); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); @@ -828,7 +822,7 @@ void Endstops::update() { if (stepper.axis_is_moving(Z_AXIS)) { if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. - #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0) + #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); @@ -849,7 +843,7 @@ void Endstops::update() { #endif } else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0) + #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) #if ENABLED(Z_MULTI_ENDSTOPS) PROCESS_ENDSTOP_Z(MAX); #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 7d18aaf850..acd241d432 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -62,9 +62,9 @@ enum EndstopEnum : char { NUM_ENDSTOP_STATES }; -#define X_ENDSTOP (x_home_dir(active_extruder) < 0 ? X_MIN : X_MAX) -#define Y_ENDSTOP (Y_HOME_DIR < 0 ? Y_MIN : Y_MAX) -#define Z_ENDSTOP (Z_HOME_DIR < 0 ? TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE) : Z_MAX) +#define X_ENDSTOP TERN(X_HOME_TO_MAX, X_MAX, X_MIN) +#define Y_ENDSTOP TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) +#define Z_ENDSTOP TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE)) #undef __ES_ITEM #undef _ES_ITEM diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 52d9dec904..69aed1e192 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1378,7 +1378,7 @@ void prepare_line_to_destination() { // Only do some things when moving towards an endstop const int8_t axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); const bool is_home_dir = (axis_home_dir > 0) == (distance > 0); #if ENABLED(SENSORLESS_HOMING) @@ -1562,8 +1562,8 @@ void prepare_line_to_destination() { #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ ENABLED(A##_SPI_SENSORLESS) \ || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ - || (A##_MIN_PIN > -1 && A##_HOME_DIR < 0) \ - || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0) \ + || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ + || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ )) if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; #endif @@ -1571,7 +1571,7 @@ void prepare_line_to_destination() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(axis_codes[axis]), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); // // Homing Z with a probe? Raise Z (maybe) and deploy the Z probe. @@ -1916,7 +1916,7 @@ void set_axis_is_at_home(const AxisEnum axis) { /** * Z Probe Z Homing? Account for the probe's Z offset. */ - #if HAS_BED_PROBE && Z_HOME_DIR < 0 + #if HAS_BED_PROBE && Z_HOME_TO_MIN if (axis == Z_AXIS) { #if HOMING_Z_WITH_PROBE diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 15713e6d4d..3c6f044b21 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -517,7 +517,7 @@ FORCE_INLINE bool all_axes_trusted() { return linear_bits float x_home_pos(const uint8_t extruder); - FORCE_INLINE int x_home_dir(const uint8_t extruder) { return extruder ? X2_HOME_DIR : X_HOME_DIR; } + #define TOOL_X_HOME_DIR(T) ((T) ? X2_HOME_DIR : X_HOME_DIR) void set_duplication_enabled(const bool dupe, const int8_t tool_index=-1); void idex_set_mirrored_mode(const bool mirr); @@ -531,7 +531,7 @@ FORCE_INLINE bool all_axes_trusted() { return linear_bits FORCE_INLINE void set_duplication_enabled(const bool dupe) { extruder_duplication_enabled = dupe; } #endif - FORCE_INLINE int x_home_dir(const uint8_t) { return X_HOME_DIR; } + #define TOOL_X_HOME_DIR(T) X_HOME_DIR #endif diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index b0544c7791..07f714a997 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -221,10 +221,10 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); #endif - // const int x_axis_home_dir = x_home_dir(active_extruder); + //const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); - // const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) }; - // const float mlz = max_length(X_AXIS), + //const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) }; + //const float mlz = max_length(X_AXIS), // Move all carriages together linearly until an endstop is hit. //do_blocking_move_to_xy_z(pos, mlz, homing_feedrate(Z_AXIS)); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index e8f578ae91..2e2afaeb90 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -259,7 +259,7 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (A##_HOME_TO_MIN) { \ if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ @@ -285,7 +285,7 @@ xyze_int8_t Stepper::count_direction{0}; #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (A##_HOME_TO_MIN) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ @@ -316,7 +316,7 @@ xyze_int8_t Stepper::count_direction{0}; #define QUAD_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (A##_HOME_TO_MIN) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 625de05996..b262212b7e 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -38,7 +38,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -50,7 +50,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -62,7 +62,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index ba60db472e..0508c5b5a9 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -50,7 +50,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_26 // E0DET #else #define X_MIN_PIN P1_26 // E0DET @@ -68,7 +68,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_25 // E1DET #else #define Y_MIN_PIN P1_25 // E1DET @@ -86,7 +86,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_00 // PWRDET #else #define Z_MIN_PIN P1_00 // PWRDET diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 40fac4e7fa..f998ecde4e 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -50,7 +50,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -62,7 +62,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -74,7 +74,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index a616079403..1057147498 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -60,7 +60,7 @@ // #if X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -72,7 +72,7 @@ #if Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -84,7 +84,7 @@ #if Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index d71b79ca95..37ebbd47ad 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -385,7 +385,7 @@ // Assign endstop pins for boards with only 3 connectors // #ifdef X_STOP_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_STOP_PIN #ifndef X_MAX_PIN #define X_MAX_PIN -1 @@ -396,14 +396,14 @@ #define X_MIN_PIN -1 #endif #endif -#elif X_HOME_DIR < 0 +#elif X_HOME_TO_MIN #define X_STOP_PIN X_MIN_PIN #else #define X_STOP_PIN X_MAX_PIN #endif #ifdef Y_STOP_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_STOP_PIN #ifndef Y_MAX_PIN #define Y_MAX_PIN -1 @@ -414,14 +414,14 @@ #define Y_MIN_PIN -1 #endif #endif -#elif Y_HOME_DIR < 0 +#elif Y_HOME_TO_MIN #define Y_STOP_PIN Y_MIN_PIN #else #define Y_STOP_PIN Y_MAX_PIN #endif #ifdef Z_STOP_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MIN_PIN Z_STOP_PIN #ifndef Z_MAX_PIN #define Z_MAX_PIN -1 @@ -432,7 +432,7 @@ #define Z_MIN_PIN -1 #endif #endif -#elif Z_HOME_DIR < 0 +#elif Z_HOME_TO_MIN #define Z_STOP_PIN Z_MIN_PIN #else #define Z_STOP_PIN Z_MAX_PIN @@ -489,34 +489,34 @@ #undef Z_MIN_PIN #define Z_MIN_PIN -1 #endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR > 0 +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX #undef X2_MIN_PIN #endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR < 0 +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MIN #undef X2_MAX_PIN #endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR > 0 +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MAX #undef Y2_MIN_PIN #endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR < 0 +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MIN #undef Y2_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MAX #undef Z2_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MIN #undef Z2_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MAX #undef Z3_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN #undef Z3_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX #undef Z4_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN #undef Z4_MAX_PIN #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index ee537495ea..0c072745d5 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -61,7 +61,7 @@ #else - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 81 // X+ #else @@ -69,7 +69,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 57 // Y+ #else diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 3776cf8bb5..ecff888ff0 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -71,7 +71,7 @@ #define E0_DIAG_PIN 78 // PB23 #define E1_DIAG_PIN 25 // PD0 - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 32 #else @@ -79,7 +79,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 15 #else diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index f808278510..621b136e17 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -55,7 +55,7 @@ #define X2_DIR_PIN FPC10_PIN // X2DIR #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN FPC2_PIN // X2-STOP #else #define X_MIN_PIN FPC2_PIN // X2-STOP diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 70d502f68a..70ac9a13c3 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -69,7 +69,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN E0_DIAG_PIN // X+ #else #define X_MIN_PIN E0_DIAG_PIN // X+ @@ -81,7 +81,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN E1_DIAG_PIN // Y+ #else #define Y_MIN_PIN E1_DIAG_PIN // Y+ @@ -93,7 +93,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN E2_DIAG_PIN // Z+ #else #define Z_MIN_PIN E2_DIAG_PIN // Z+ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 6de3c544d3..34fe1a824b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -71,7 +71,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN E0_DIAG_PIN // E0DET #else #define X_MIN_PIN E0_DIAG_PIN // E0DET @@ -89,7 +89,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN E1_DIAG_PIN // E1DET #else #define Y_MIN_PIN E1_DIAG_PIN // E1DET @@ -107,7 +107,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN E2_DIAG_PIN // PWRDET #else #define Z_MIN_PIN E2_DIAG_PIN // PWRDET diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 67907affa7..fe6d8740bd 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -71,7 +71,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN PE15 // E0 #else #define X_MIN_PIN PE15 // E0 @@ -83,7 +83,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN PE10 // E1 #else #define Y_MIN_PIN PE10 // E1 @@ -95,7 +95,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN PG5 // E2 #else #define Z_MIN_PIN PG5 // E2 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index a69041e2d4..5e2f88190d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -72,7 +72,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN PC2 // E0DET #else #define X_MIN_PIN PC2 // E0DET @@ -90,7 +90,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN PA0 // E1DET #else #define Y_MIN_PIN PA0 // E1DET @@ -108,7 +108,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN PC15 // PWRDET #else #define Z_MIN_PIN PC15 // PWRDET From e018f041bad46d6fb03a6c53f99fb7c7c494b721 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 19 May 2021 23:07:09 -0500 Subject: [PATCH 0139/2168] =?UTF-8?q?=F0=9F=8E=A8=20Move=20switch=20sensor?= =?UTF-8?q?=20strings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/language.h | 44 ++++++++++++++++++++++---------------- 1 file changed, 25 insertions(+), 19 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index cabdde983b..df6821cb1c 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -140,25 +140,7 @@ #define STR_RESEND "Resend: " #define STR_UNKNOWN_COMMAND "Unknown command: \"" #define STR_ACTIVE_EXTRUDER "Active Extruder: " -#define STR_X_MIN "x_min" -#define STR_X_MAX "x_max" -#define STR_X2_MIN "x2_min" -#define STR_X2_MAX "x2_max" -#define STR_Y_MIN "y_min" -#define STR_Y_MAX "y_max" -#define STR_Y2_MIN "y2_min" -#define STR_Y2_MAX "y2_max" -#define STR_Z_MIN "z_min" -#define STR_Z_MAX "z_max" -#define STR_Z2_MIN "z2_min" -#define STR_Z2_MAX "z2_max" -#define STR_Z3_MIN "z3_min" -#define STR_Z3_MAX "z3_max" -#define STR_Z4_MIN "z4_min" -#define STR_Z4_MAX "z4_max" -#define STR_Z_PROBE "z_probe" -#define STR_PROBE_EN "probe_en" -#define STR_FILAMENT_RUNOUT_SENSOR "filament" + #define STR_PROBE_OFFSET "Probe Offset" #define STR_SKEW_MIN "min_skew_factor: " #define STR_SKEW_MAX "max_skew_factor: " @@ -277,6 +259,30 @@ #define STR_REMINDER_SAVE_SETTINGS "Remember to save!" #define STR_PASSWORD_SET "Password is " +// +// Endstop Names used by Endstops::report_states +// +#define STR_X_MIN "x_min" +#define STR_X_MAX "x_max" +#define STR_X2_MIN "x2_min" +#define STR_X2_MAX "x2_max" +#define STR_Y_MIN "y_min" +#define STR_Y_MAX "y_max" +#define STR_Y2_MIN "y2_min" +#define STR_Y2_MAX "y2_max" +#define STR_Z_MIN "z_min" +#define STR_Z_MAX "z_max" +#define STR_Z2_MIN "z2_min" +#define STR_Z2_MAX "z2_max" +#define STR_Z3_MIN "z3_min" +#define STR_Z3_MAX "z3_max" +#define STR_Z4_MIN "z4_min" +#define STR_Z4_MAX "z4_max" +#define STR_Z_PROBE "z_probe" +#define STR_PROBE_EN "probe_en" +#define STR_FILAMENT_RUNOUT_SENSOR "filament" + +// General axis names #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" From 29ad42e54e88b2117581987aecc811177285eea2 Mon Sep 17 00:00:00 2001 From: charlespick Date: Thu, 20 May 2021 04:06:26 -0700 Subject: [PATCH 0140/2168] =?UTF-8?q?=E2=9C=A8=20Independent=20baud=20rate?= =?UTF-8?q?s=20(#21949)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 35 ++++++++++++++++------------- Marlin/Configuration_adv.h | 3 --- Marlin/src/MarlinCore.cpp | 10 +++++++-- buildroot/tests/STM32F103RC_btt_USB | 2 +- 4 files changed, 29 insertions(+), 21 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 78c2dc9160..dd6abd5629 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -105,21 +105,9 @@ #define SERIAL_PORT 0 /** - * Select a secondary serial port on the board to use for communication with the host. - * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. - * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_2 -1 - -/** - * Select a third serial port on the board to use for communication with the host. - * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_3 1 - -/** - * This setting determines the communication speed of the printer. + * Serial Port Baud Rate + * This is the default communication speed for all serial ports. + * Set the baud rate defaults for additional serial ports below. * * 250000 works in most cases, but you might try a lower speed if * you commonly experience drop-outs during host printing. @@ -128,6 +116,23 @@ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] */ #define BAUDRATE 250000 +//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate + +/** + * Select a secondary serial port on the board to use for communication with the host. + * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. + * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_2 -1 +//#define BAUDRATE_2 250000 // Enable to override BAUDRATE + +/** + * Select a third serial port on the board to use for communication with the host. + * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_3 1 +//#define BAUDRATE_3 250000 // Enable to override BAUDRATE // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5335fa012a..5db36d9cbb 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2114,9 +2114,6 @@ //#define SERIAL_XON_XOFF #endif -// Add M575 G-code to change the baud rate -//#define BAUD_RATE_GCODE - #if ENABLED(SDSUPPORT) // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5ef575a30f..4fca64ba6b 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1073,11 +1073,17 @@ void setup() { while (!MYSERIAL1.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #if HAS_MULTI_SERIAL && !HAS_ETHERNET - MYSERIAL2.begin(BAUDRATE); + #ifndef BAUDRATE_2 + #define BAUDRATE_2 BAUDRATE + #endif + MYSERIAL2.begin(BAUDRATE_2); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL2.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #ifdef SERIAL_PORT_3 - MYSERIAL3.begin(BAUDRATE); + #ifndef BAUDRATE_3 + #define BAUDRATE_3 BAUDRATE + #endif + MYSERIAL3.begin(BAUDRATE_3); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL3.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #endif diff --git a/buildroot/tests/STM32F103RC_btt_USB b/buildroot/tests/STM32F103RC_btt_USB index 8381de0ea6..fb0f2f5bd2 100755 --- a/buildroot/tests/STM32F103RC_btt_USB +++ b/buildroot/tests/STM32F103RC_btt_USB @@ -10,7 +10,7 @@ set -e # Build with the default configurations # restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 BAUDRATE_2 115200 exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" # clean up From 7da4ed7340044a2457846af9a1709232f7eb0037 Mon Sep 17 00:00:00 2001 From: Moonglow Date: Thu, 20 May 2021 14:09:10 +0300 Subject: [PATCH 0141/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Toshiba=20FlashA?= =?UTF-8?q?ir=20(SDCARD=5FCOMMANDS=5FSPLIT)=20(#21944)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/Sd2Card.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 3e714fe9fe..a81932d494 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -89,6 +89,11 @@ // Send command and return error code. Return zero for OK uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) { + + #if ENABLED(SDCARD_COMMANDS_SPLIT) + if (cmd != CMD12) chipDeselect(); + #endif + // Select card chipSelect(); From 781b34709bae404368b095ccc33d7ceeffc30adb Mon Sep 17 00:00:00 2001 From: Pascal de Bruijn Date: Thu, 20 May 2021 13:35:38 +0200 Subject: [PATCH 0142/2168] =?UTF-8?q?=E2=9C=A8=20MEDIA=5FMENU=5FAT=5FTOP?= =?UTF-8?q?=20for=20MarlinUI=20(#21925)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 + Marlin/src/lcd/menu/menu_main.cpp | 101 +++++++++++------------------- buildroot/tests/mega2560 | 4 +- 3 files changed, 42 insertions(+), 65 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5db36d9cbb..4511aa49c7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1301,6 +1301,8 @@ //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted + //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu + #define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27") #if ENABLED(PRINTER_EVENT_LEDS) diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 34d1d6c6f4..17c9b1fe6a 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -254,6 +254,38 @@ void menu_main() { START_MENU(); BACK_ITEM(MSG_INFO_SCREEN); + #if ENABLED(SDSUPPORT) + + #if !defined(MEDIA_MENU_AT_TOP) && !HAS_ENCODER_WHEEL + #define MEDIA_MENU_AT_TOP + #endif + + auto sdcard_menu_items = [&]{ + #if ENABLED(MENU_ADDAUTOSTART) + ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files + #endif + + if (card_detected) { + if (!card_open) { + #if PIN_EXISTS(SD_DETECT) + GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); // M21 Change Media + #else // - or - + GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); // M22 Release Media + #endif + SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); // Media Menu (or Password First) + } + } + else { + #if PIN_EXISTS(SD_DETECT) + ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); // M21 Attach Media + #endif + } + }; + + #endif + if (busy) { #if MACHINE_CAN_PAUSE ACTION_ITEM(MSG_PAUSE_PRINT, ui.pause_print); @@ -281,36 +313,9 @@ void menu_main() { } else { - #if !HAS_ENCODER_WHEEL && ENABLED(SDSUPPORT) - - // *** IF THIS SECTION IS CHANGED, REPRODUCE BELOW *** - - // - // Run Auto Files - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); - #endif - - if (card_detected) { - if (!card_open) { - SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); - #endif - } - - #endif // !HAS_ENCODER_WHEEL && SDSUPPORT + #if BOTH(SDSUPPORT, MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); @@ -387,39 +392,9 @@ void menu_main() { GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif - #if BOTH(HAS_ENCODER_WHEEL, SDSUPPORT) - - if (!busy) { - - // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** - - // - // Autostart - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); - #endif - - if (card_detected) { - if (!card_open) { - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); - #endif - } - } - - #endif // HAS_ENCODER_WHEEL && SDSUPPORT + #if ENABLED(SDSUPPORT) && DISABLED(MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif #if HAS_SERVICE_INTERVALS static auto _service_reset = [](const int index) { diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 8e63c6e7b1..fc445c0532 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -20,8 +20,8 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ - SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES CANCEL_OBJECTS SOUND_MENU_ITEM \ - EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE \ + SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES MEDIA_MENU_AT_TOP \ + EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE CANCEL_OBJECTS SOUND_MENU_ITEM \ MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE EXTRA_LIN_ADVANCE_K QUICK_HOME \ LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL From 000388b1d9e38a2678e8235a5d4dc3163f853c02 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 20 May 2021 17:12:18 -0500 Subject: [PATCH 0143/2168] =?UTF-8?q?=F0=9F=8E=A8=20MULTI=5FMANUAL=20=3D>?= =?UTF-8?q?=20MULTI=5FE=5FMANUAL?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 6 +++--- Marlin/src/lcd/marlinui.h | 6 +++--- Marlin/src/lcd/menu/menu_motion.cpp | 12 ++++++------ Marlin/src/lcd/tft/ui_1024x600.cpp | 2 +- Marlin/src/lcd/tft/ui_320x240.cpp | 2 +- Marlin/src/lcd/tft/ui_480x320.cpp | 2 +- 6 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1d312535c9..544cc5eb2c 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -681,7 +681,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { xyze_pos_t ManualMove::all_axes_destination = { 0 }; bool ManualMove::processing = false; #endif - #if ENABLED(MULTI_MANUAL) + #if ENABLED(MULTI_E_MANUAL) int8_t ManualMove::e_index = 0; #endif AxisEnum ManualMove::axis = NO_AXIS_MASK; @@ -758,11 +758,11 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Tell ui.update() to start a move to current_position after a short delay. // void ManualMove::soon(const AxisEnum move_axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , const int8_t eindex/*=-1*/ #endif ) { - #if MULTI_MANUAL + #if MULTI_E_MANUAL if (move_axis == E_AXIS) e_index = eindex >= 0 ? eindex : active_extruder; #endif start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 085e2e0b7e..ba0221713b 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -48,7 +48,7 @@ #endif #if E_MANUAL > 1 - #define MULTI_MANUAL 1 + #define MULTI_E_MANUAL 1 #endif #if HAS_DISPLAY @@ -129,7 +129,7 @@ class ManualMove { private: static AxisEnum axis; - #if MULTI_MANUAL + #if MULTI_E_MANUAL static int8_t e_index; #else static int8_t constexpr e_index = 0; @@ -183,7 +183,7 @@ #endif static void task(); static void soon(const AxisEnum axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , const int8_t eindex=-1 #endif ); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 6bf6df1897..06d635ffc8 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -94,14 +94,14 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } #if E_MANUAL - static void lcd_move_e(TERN_(MULTI_MANUAL, const int8_t eindex=-1)) { + static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=-1)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.manual_move.processing) { const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; TERN(IS_KINEMATIC, ui.manual_move.offset, current_position.e) += diff; ui.manual_move.soon(E_AXIS - #if MULTI_MANUAL + #if MULTI_E_MANUAL , eindex #endif ); @@ -110,9 +110,9 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } ui.encoderPosition = 0; } if (ui.should_draw()) { - TERN_(MULTI_MANUAL, MenuItemBase::init(eindex)); + TERN_(MULTI_E_MANUAL, MenuItemBase::init(eindex)); MenuEditItemBase::draw_edit_screen( - GET_TEXT(TERN(MULTI_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), + GET_TEXT(TERN(MULTI_E_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), ftostr41sign(current_position.e PLUS_TERN0(IS_KINEMATIC, ui.manual_move.offset) MINUS_TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) @@ -188,7 +188,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_MANUAL, active_extruder)); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_E_MANUAL, active_extruder)); }, -1); }); } inline void _menu_move_distance_e_maybe() { @@ -283,7 +283,7 @@ void menu_move() { SUBMENU_MOVE_E(E_MANUAL - 1); #endif - #elif MULTI_MANUAL + #elif MULTI_E_MANUAL // Independent extruders with one E-stepper per hotend LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 3b12ab2b60..87b016b1ec 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -725,7 +725,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 31665fdc33..89a127b01e 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -710,7 +710,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index a5539990d5..6923bdd71c 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -712,7 +712,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); From 67f08ef07f6419b5cca78226de75f2b14bde6d0c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 21 May 2021 01:07:03 +0000 Subject: [PATCH 0144/2168] [cron] Bump distribution date (2021-05-21) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4bb0f19a8a..0209b9377e 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 "2021-05-20" + #define STRING_DISTRIBUTION_DATE "2021-05-21" #endif /** From 8f0f6c1ac117bff0b5f2c2140479b93ea9cd138b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 20 May 2021 21:47:05 -0500 Subject: [PATCH 0145/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20compile=20with?= =?UTF-8?q?=20PREVENT=5FCOLD=5FEXTRUSION=20off?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 11 ++++++++-- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 22 +++++++++++-------- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 4 +++- 3 files changed, 25 insertions(+), 12 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 525b781599..3d68df7b7f 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -691,7 +691,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_X_PARK_POS, &mks_park_pos.x, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Y_PARK_POS, &mks_park_pos.y, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Z_PARK_POS, &mks_park_pos.z, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting #if AXIS_HAS_STEALTHCHOP(X) @@ -743,7 +746,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZOffset_Distance,nullptr ,ScreenHandler.GetZoffsetDistance, nullptr), VPHELPER(VP_MESH_LEVEL_ADJUST, nullptr, ScreenHandler.MeshLevelDistanceConfig, nullptr), VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), - VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + VPHELPER(VP_AutoTurnOffSw, nullptr, &ScreenHandler.GetTurnOffCtrl, nullptr), #if HOTENDS >= 1 diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index c0b3b60a16..6d12d529a9 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -342,7 +342,7 @@ void DGUSScreenHandler::GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) { void DGUSScreenHandler::GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("GetMinExtrudeTemp"); const uint16_t value = swap16(*(uint16_t *)val_ptr); - thermalManager.extrude_min_temp = value; + TERN_(PREVENT_COLD_EXTRUSION, thermalManager.extrude_min_temp = value); mks_min_extrusion_temp = value; settings.save(); } @@ -1083,11 +1083,13 @@ void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandler::HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr) { - const uint16_t value_ex_min_temp = swap16(*(uint16_t*)val_ptr); - thermalManager.extrude_min_temp = value_ex_min_temp; - skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel -} +#if ENABLED(PREVENT_COLD_EXTRUSION) + void DGUSScreenHandler::HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t value_ex_min_temp = swap16(*(uint16_t*)val_ptr); + thermalManager.extrude_min_temp = value_ex_min_temp; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { @@ -1231,7 +1233,7 @@ void DGUSScreenHandler::MKS_FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ break; } - #if HAS_HOTEND + #if BOTH(HAS_HOTEND, PREVENT_COLD_EXTRUSION) if (hotend_too_cold) { if (thermalManager.targetTooColdToExtrude(hotend_too_cold - 1)) thermalManager.setTargetHotend(thermalManager.extrude_min_temp, hotend_too_cold - 1); sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please wait."), PSTR("Nozzle heating!"), true, true, true, true); @@ -1428,8 +1430,10 @@ bool DGUSScreenHandler::loop() { #endif #endif - if (mks_min_extrusion_temp != 0) - thermalManager.extrude_min_temp = mks_min_extrusion_temp; + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (mks_min_extrusion_temp != 0) + thermalManager.extrude_min_temp = mks_min_extrusion_temp; + #endif DGUS_ExtrudeLoadInit(); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 6713debd83..4a67b4afda 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -82,7 +82,9 @@ public: static void GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr); static void GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr); static void GetParkPos_MKS(DGUS_VP_Variable &var, void *val_ptr); - static void HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(PREVENT_COLD_EXTRUSION) + static void HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr); + #endif static void DGUS_LanguageDisplay(uint8_t var); static void TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr); static void GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr); From 2db640ea801d40af05dc598d168380a48b1ec1c8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 00:26:54 -0500 Subject: [PATCH 0146/2168] Add a test for SAVED_POSITIONS --- buildroot/tests/mega2560 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index fc445c0532..a3711ca076 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -16,7 +16,7 @@ set -e # Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders # use_example_configs AnimationExample -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr \ +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ From f4951ed56b3fe7b2f85c039677dc9a499d537e8f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 08:25:54 -0500 Subject: [PATCH 0147/2168] =?UTF-8?q?=F0=9F=8E=A8=20Rename=20all/no=20axis?= =?UTF-8?q?=20enums?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/types.h | 2 +- Marlin/src/gcode/calibrate/M852.cpp | 2 +- Marlin/src/gcode/probe/G38.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 12 ++++++------ Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/module/motion.cpp | 4 ++-- 7 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 98e2bedb00..b7ae85eb2e 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -54,7 +54,7 @@ enum AxisEnum : uint8_t { X_HEAD, Y_HEAD, Z_HEAD, E0_AXIS = E_AXIS, E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS, - ALL_AXES_MASK = 0xFE, NO_AXIS_MASK = 0xFF + ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; // diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index a038dc59fd..6f1e984bc3 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -86,7 +86,7 @@ void GcodeSuite::M852() { // When skew is changed the current position changes if (setval) { - set_current_from_steppers_for_axis(ALL_AXES_MASK); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); report_current_position(); } diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 606776f402..6906805fca 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -38,7 +38,7 @@ inline void G38_single_probe(const uint8_t move_value) { planner.synchronize(); G38_move = 0; endstops.hit_on_purpose(); - set_current_from_steppers_for_axis(ALL_AXES_MASK); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 544cc5eb2c..c99fa41657 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -684,7 +684,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #if ENABLED(MULTI_E_MANUAL) int8_t ManualMove::e_index = 0; #endif - AxisEnum ManualMove::axis = NO_AXIS_MASK; + AxisEnum ManualMove::axis = NO_AXIS_ENUM; /** * If a manual move has been posted and its time has arrived, and if the planner @@ -695,7 +695,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { * * To post a manual move: * - Update current_position to the new place you want to go. - * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_MASK for diagonal moves. + * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. * * For kinematic machines: @@ -710,7 +710,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { if (processing) return; // Prevent re-entry from idle() calls // Add a manual move to the queue? - if (axis != NO_AXIS_MASK && ELAPSED(millis(), start_time) && !planner.is_full()) { + if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; @@ -722,7 +722,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #endif // Apply a linear offset to a single axis - if (axis == ALL_AXES_MASK) + if (axis == ALL_AXES_ENUM) destination = all_axes_destination; else if (axis <= XYZE) { destination = current_position; @@ -731,7 +731,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Reset for the next move offset = 0; - axis = NO_AXIS_MASK; + axis = NO_AXIS_ENUM; // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to // move_to_destination. This will cause idle() to be called, which can then call this function while the @@ -748,7 +748,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); - axis = NO_AXIS_MASK; + axis = NO_AXIS_ENUM; #endif } diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 70de53dab5..62cf8cf1c1 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -206,7 +206,7 @@ #if ENABLED(MESH_EDIT_MENU) inline void refresh_planner() { - set_current_from_steppers_for_axis(ALL_AXES_MASK); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); } diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index f923f98c78..880b76ff76 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -430,7 +430,7 @@ void ubl_map_move_to_xy() { // Use the built-in manual move handler to move to the mesh point. ui.manual_move.set_destination(xy); - ui.manual_move.soon(ALL_AXES_MASK); + ui.manual_move.soon(ALL_AXES_ENUM); } inline int32_t grid_index(const uint8_t x, const uint8_t y) { diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 69aed1e192..ec57b37a71 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -282,7 +282,7 @@ void report_current_position_projected() { void quickstop_stepper() { planner.quick_stop(); planner.synchronize(); - set_current_from_steppers_for_axis(ALL_AXES_MASK); + set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); } @@ -360,7 +360,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { planner.unapply_modifiers(pos, true); #endif - if (axis == ALL_AXES_MASK) + if (axis == ALL_AXES_ENUM) current_position = pos; else current_position[axis] = pos[axis]; From ad30909a2d45a37c3a689a7080ca346f3cb75c5f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 08:24:38 -0500 Subject: [PATCH 0148/2168] =?UTF-8?q?=F0=9F=8E=A8=20Update=20a=20condition?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index c99fa41657..14959851fa 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -681,7 +681,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { xyze_pos_t ManualMove::all_axes_destination = { 0 }; bool ManualMove::processing = false; #endif - #if ENABLED(MULTI_E_MANUAL) + #if MULTI_E_MANUAL int8_t ManualMove::e_index = 0; #endif AxisEnum ManualMove::axis = NO_AXIS_ENUM; From 2de54dab84d82ef69fb9ac3bd9025444f4f84813 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 08:23:09 -0500 Subject: [PATCH 0149/2168] =?UTF-8?q?=F0=9F=8E=A8=20Move=20HAS=5FEXTRUDERS?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/gcode/config/M221.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 10 ++++++---- Marlin/src/gcode/gcode.h | 13 ++++++++----- Marlin/src/gcode/host/M360.cpp | 4 ++-- Marlin/src/gcode/temp/M104_M109.cpp | 2 +- Marlin/src/gcode/units/M82_M83.cpp | 6 ++++++ Marlin/src/inc/Conditionals_LCD.h | 11 +++++++---- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 2 +- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 2 +- Marlin/src/lcd/menu/menu_info.cpp | 6 +++--- Marlin/src/lcd/menu/menu_tune.cpp | 2 +- Marlin/src/module/motion.cpp | 6 +++--- Marlin/src/module/motion.h | 2 +- Marlin/src/module/planner.cpp | 18 +++++++++--------- Marlin/src/module/planner.h | 4 ++-- Marlin/src/module/settings.cpp | 6 +++--- Marlin/src/module/tool_change.cpp | 2 +- Marlin/src/pins/ramps/pins_3DRAG.h | 2 +- Marlin/src/pins/sensitive_pins.h | 2 +- .../PlatformIO/scripts/common-dependencies.h | 4 ---- ini/features.ini | 2 +- platformio.ini | 1 + 25 files changed, 63 insertions(+), 52 deletions(-) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index a7474794de..a512022320 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -197,7 +197,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #endif #endif - #if EXTRUDERS + #if HAS_EXTRUDERS HOTEND_LOOP() info.target_temperature[e] = thermalManager.degTargetHotend(e); #endif diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp index 7ba22d1901..e380bfb1c7 100644 --- a/Marlin/src/gcode/config/M221.cpp +++ b/Marlin/src/gcode/config/M221.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/planner.h" -#if EXTRUDERS +#if HAS_EXTRUDERS /** * M221: Set extrusion percentage (M221 T0 S95) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 33877cd61c..30151b3bd0 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -520,7 +520,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 100: M100(); break; // M100: Free Memory Report #endif - #if EXTRUDERS + #if HAS_EXTRUDERS case 104: M104(); break; // M104: Set hot end temperature case 109: M109(); break; // M109: Wait for hotend temperature to reach target #endif @@ -596,8 +596,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif case 81: M81(); break; // M81: Turn off Power, including Power Supply, if possible - case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) - case 83: M83(); break; // M83: Set E axis relative mode + #if HAS_EXTRUDERS + case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) + case 83: M83(); break; // M83: Set E axis relative mode + #endif case 18: case 84: M18_M84(); break; // M18/M84: Disable Steppers / Set Timeout case 85: M85(); break; // M85: Set inactivity stepper shutdown timeout case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes @@ -674,7 +676,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 220: M220(); break; // M220: Set Feedrate Percentage: S ("FR" on your LCD) - #if EXTRUDERS + #if HAS_EXTRUDERS case 221: M221(); break; // M221: Set Flow Percentage #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index cdf04cd0f2..c32575e81e 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -633,10 +633,13 @@ private: #if ENABLED(PSU_CONTROL) static void M80(); #endif - static void M81(); - static void M82(); - static void M83(); + + #if HAS_EXTRUDERS + static void M82(); + static void M83(); + #endif + static void M85(); static void M92(); @@ -644,7 +647,7 @@ private: static void M100(); #endif - #if EXTRUDERS + #if HAS_EXTRUDERS static void M104(); static void M109(); #endif @@ -776,7 +779,7 @@ private: static void M220(); - #if EXTRUDERS + #if HAS_EXTRUDERS static void M221(); #endif diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index f3c242526d..7a0b8e3ab0 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -28,7 +28,7 @@ #include "../../module/motion.h" #include "../../module/planner.h" -#if EXTRUDERS +#if HAS_EXTRUDERS #include "../../module/temperature.h" #endif @@ -171,7 +171,7 @@ void GcodeSuite::M360() { // Per-Extruder settings // config_line(PSTR("NumExtruder"), EXTRUDERS); - #if EXTRUDERS + #if HAS_EXTRUDERS LOOP_L_N(e, EXTRUDERS) { config_line_e(e, JERK_STR, TERN(HAS_LINEAR_E_JERK, planner.max_e_jerk[E_INDEX_N(e)], TERN(HAS_CLASSIC_JERK, planner.max_jerk.e, DEFAULT_EJERK))); config_line_e(e, PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index e54f784153..eb350a577a 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -28,7 +28,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EXTRUDERS +#if HAS_EXTRUDERS #include "../gcode.h" #include "../../module/temperature.h" diff --git a/Marlin/src/gcode/units/M82_M83.cpp b/Marlin/src/gcode/units/M82_M83.cpp index d93f0ea5ad..c1767e8057 100644 --- a/Marlin/src/gcode/units/M82_M83.cpp +++ b/Marlin/src/gcode/units/M82_M83.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_EXTRUDERS + #include "../gcode.h" /** @@ -31,3 +35,5 @@ void GcodeSuite::M82() { set_e_absolute(); } * M83: Set E codes relative while in Absolute Coordinates (G90) mode */ void GcodeSuite::M83() { set_e_relative(); } + +#endif // HAS_EXTRUDERS diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 545ee403a1..8001674dc4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -538,7 +538,12 @@ * E_MANUAL - Number of E steppers for LCD move options */ -#if EXTRUDERS == 0 +#if EXTRUDERS + #define HAS_EXTRUDERS 1 + #if EXTRUDERS > 1 + #define HAS_MULTI_EXTRUDER 1 + #endif +#else #undef EXTRUDERS #define EXTRUDERS 0 #undef SINGLENOZZLE @@ -546,8 +551,6 @@ #undef SWITCHING_NOZZLE #undef MIXING_EXTRUDER #undef HOTEND_IDLE_TIMEOUT -#elif EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER 1 #endif #if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS @@ -663,7 +666,7 @@ * All the logical axes that can be commanded directly by G-code. * Delta maps stepper-specific values to ABC steppers. */ -#if EXTRUDERS +#if HAS_EXTRUDERS #define LOGICAL_AXES INCREMENT(LINEAR_AXES) #else #define LOGICAL_AXES LINEAR_AXES diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 95a7ada83f..1d3253b1cc 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -75,7 +75,7 @@ #define SERVO_DELAY { 50 } #endif -#if EXTRUDERS == 0 +#if !HAS_EXTRUDERS #define NO_VOLUMETRICS #undef TEMP_SENSOR_0 #undef TEMP_SENSOR_1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index b9eacd0a1a..23201bb387 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1555,7 +1555,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if ENABLED(G26_MESH_VALIDATION) - #if !EXTRUDERS + #if !HAS_EXTRUDERS #error "G26_MESH_VALIDATION requires at least one extruder." #elif !HAS_MESH #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 85430c18b0..50c80c9fa0 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -954,7 +954,7 @@ void MarlinUI::draw_status_screen() { else #endif { - #if EXTRUDERS + #if HAS_EXTRUDERS c = 'E'; per = planner.flow_percentage[0]; #endif diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 5b3bb9e0f3..a1de499f46 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -422,7 +422,7 @@ void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *va } void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { - #if EXTRUDERS + #if HAS_EXTRUDERS uint16_t newvalue = swap16(*(uint16_t*)val_ptr); uint8_t target_extruder; switch (var.VP) { diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index d00909c7b3..cecccd115d 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -100,7 +100,7 @@ void menu_info_thermistors() { START_SCREEN(); - #if EXTRUDERS + #if HAS_EXTRUDERS #define THERMISTOR_ID TEMP_SENSOR_0 #include "../thermistornames.h" STATIC_ITEM_P(PSTR(LCD_STR_E0 ": " THERMISTOR_NAME), SS_INVERT); @@ -171,7 +171,7 @@ void menu_info_thermistors() { PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); #endif - #if EXTRUDERS + #if HAS_EXTRUDERS STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif @@ -278,7 +278,7 @@ void menu_info() { #else SUBMENU(MSG_INFO_PRINTER_MENU, menu_info_printer); // Printer Info > SUBMENU(MSG_INFO_BOARD_MENU, menu_info_board); // Board Info > - #if EXTRUDERS + #if HAS_EXTRUDERS SUBMENU(MSG_INFO_THERMISTOR_MENU, menu_info_thermistors); // Thermistors > #endif #endif diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 1a972f63f2..3a0d0c81ca 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -195,7 +195,7 @@ void menu_tune() { // // Flow: // - #if EXTRUDERS + #if HAS_EXTRUDERS EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: #if HAS_MULTI_EXTRUDER diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index ec57b37a71..235a969f66 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -374,7 +374,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { planner.buffer_line(current_position, fr_mm_s, active_extruder); } -#if EXTRUDERS +#if HAS_EXTRUDERS void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s) { TERN_(HAS_FILAMENT_SENSOR, runout.reset()); current_position.e += length / planner.e_factor[active_extruder]; @@ -421,7 +421,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ const uint16_t old_pct = feedrate_percentage; feedrate_percentage = 100; - #if EXTRUDERS + #if HAS_EXTRUDERS const float old_fac = planner.e_factor[active_extruder]; planner.e_factor[active_extruder] = 1.0f; #endif @@ -433,7 +433,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ feedrate_mm_s = old_feedrate; feedrate_percentage = old_pct; - #if EXTRUDERS + #if HAS_EXTRUDERS planner.e_factor[active_extruder] = old_fac; #endif } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 3c6f044b21..a43af6446b 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -272,7 +272,7 @@ void sync_plan_position_e(); */ void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s); -#if EXTRUDERS +#if HAS_EXTRUDERS void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s); #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index dde6e89a1f..714be8019e 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -164,7 +164,7 @@ float Planner::steps_to_mm[DISTINCT_AXES]; // (mm) Millimeters per step xyze_bool_t Planner::last_page_dir{0}; #endif -#if EXTRUDERS +#if HAS_EXTRUDERS int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -1836,7 +1836,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, db = target.b - position.b, dc = target.c - position.c; - #if EXTRUDERS + #if HAS_EXTRUDERS int32_t de = target.e - position.e; #else constexpr int32_t de = 0; @@ -1848,7 +1848,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, " A:", target.a, " (", da, " steps)" " B:", target.b, " (", db, " steps)" " C:", target.c, " (", dc, " steps)" - #if EXTRUDERS + #if HAS_EXTRUDERS " E:", target.e, " (", de, " steps)" #endif ); @@ -1921,7 +1921,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif if (de < 0) SBI(dm, E_AXIS); - #if EXTRUDERS + #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; const uint32_t esteps = ABS(esteps_float) + 0.5f; #else @@ -2003,7 +2003,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; #endif - #if EXTRUDERS + #if HAS_EXTRUDERS steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; #else steps_dist_mm.e = 0.0f; @@ -2013,7 +2013,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 - #if EXTRUDERS + #if HAS_EXTRUDERS + ABS(steps_dist_mm.e) #endif ); @@ -2046,7 +2046,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } - #if EXTRUDERS + #if HAS_EXTRUDERS block->steps.e = esteps; #endif @@ -2107,7 +2107,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Enable extruder(s) - #if EXTRUDERS + #if HAS_EXTRUDERS if (esteps) { TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); @@ -2209,7 +2209,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } // Limit speed on extruders, if any - #if EXTRUDERS + #if HAS_EXTRUDERS { current_speed.e = steps_dist_mm.e * inverse_secs; #if HAS_MIXER_SYNC_CHANNEL diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index db83792b45..2ec90e1fa2 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -337,7 +337,7 @@ class Planner { static xyze_bool_t last_page_dir; // Last page direction given #endif - #if EXTRUDERS + #if HAS_EXTRUDERS static int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -494,7 +494,7 @@ class Planner { static inline void set_max_jerk(const AxisEnum, const_float_t ) {} #endif - #if EXTRUDERS + #if HAS_EXTRUDERS FORCE_INLINE static void refresh_e_factor(const uint8_t e) { e_factor[e] = flow_percentage[e] * 0.01f * TERN(NO_VOLUMETRICS, 1.0f, volumetric_multiplier[e]); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 56e3c86fd4..eae4728793 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -402,7 +402,7 @@ typedef struct SettingsDataStruct { // // ADVANCED_PAUSE_FEATURE // - #if EXTRUDERS + #if HAS_EXTRUDERS fil_change_settings_t fc_settings[EXTRUDERS]; // M603 T U L #endif @@ -1321,7 +1321,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) const fil_change_settings_t fc_settings[EXTRUDERS] = { 0, 0 }; @@ -2235,7 +2235,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) fil_change_settings_t fc_settings[EXTRUDERS]; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 03e85fdd84..cc34acc14f 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -822,7 +822,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #endif // ELECTROMAGNETIC_SWITCHING_TOOLHEAD -#if EXTRUDERS +#if HAS_EXTRUDERS inline void invalid_extruder_error(const uint8_t e) { SERIAL_ECHO_START(); SERIAL_CHAR('T'); SERIAL_ECHO(e); diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 6c7f7f4db6..08354ce2ff 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -144,7 +144,7 @@ #undef SPINDLE_DIR_PIN #if HAS_CUTTER - #if !EXTRUDERS + #if !HAS_EXTRUDERS #undef E0_DIR_PIN #undef E0_ENABLE_PIN #undef E0_STEP_PIN diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 1c811601ca..21ba87e8f6 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -353,7 +353,7 @@ #define _E6_PINS #define _E7_PINS -#if EXTRUDERS +#if HAS_EXTRUDERS #undef _E0_PINS #define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, _E0_CS _E0_MS1 _E0_MS2 _E0_MS3 #endif diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index 18a7303be6..a88e708467 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -49,10 +49,6 @@ #define HAS_GCODE_M876 #endif -#if EXTRUDERS - #define HAS_EXTRUDERS -#endif - #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) #define HAS_SMART_EFF_MOD #endif diff --git a/ini/features.ini b/ini/features.ini index 6a2ccbedac..2b69daa88a 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -198,7 +198,7 @@ MAGNETIC_PARKING_EXTRUDER = src_filter=+ SDSUPPORT = src_filter=+ + + + + + + HAS_MEDIA_SUBCALLS = src_filter=+ GCODE_REPEAT_MARKERS = src_filter=+ + -HAS_EXTRUDERS = src_filter=+ + +HAS_EXTRUDERS = src_filter=+ + + HAS_COOLER = src_filter=+ + AUTO_REPORT_TEMPERATURES = src_filter=+ INCH_MODE_SUPPORT = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 4d69ca12df..0516149da9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -222,6 +222,7 @@ default_src_filter = + - - + - - - + - - - - - - - From 7985f7f11679113de6d1d83f930e926a310b768d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 22 May 2021 01:06:28 +0000 Subject: [PATCH 0150/2168] [cron] Bump distribution date (2021-05-22) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0209b9377e..e78166461b 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 "2021-05-21" + #define STRING_DISTRIBUTION_DATE "2021-05-22" #endif /** From 4ea4fa78aa6fcafc6f270bb543c2f8dc8ae695cd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 22:45:54 -0500 Subject: [PATCH 0151/2168] =?UTF-8?q?=F0=9F=93=9D=20Document=20diveToFile,?= =?UTF-8?q?=20printListing?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/sd/cardreader.cpp | 102 +++++++++++++++++++---------------- Marlin/src/sd/cardreader.h | 21 ++++++-- 3 files changed, 73 insertions(+), 52 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 23201bb387..897cb2824f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2304,7 +2304,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ - + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY,DGUS_LCD_UI_MKS) \ + + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY, DWIN_CREALITY_LCD) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 3f6b50dd4b..405da103de 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -261,7 +261,14 @@ void CardReader::selectByName(SdFile dir, const char * const match) { } // -// Recursive method to list all files within a folder +// Recursive method to print all files within a folder in flat +// DOS 8.3 format. This style of listing is the most compatible +// with legacy hosts. +// +// This method recurses to unlimited depth and lists every +// G-code file within the given parent. If the hierarchy is +// very deep this can blow up the stack, so a 'depth' parameter +// (as with printListingJSON) would be a good addition. // void CardReader::printListing(SdFile parent, const char * const prepend/*=nullptr*/) { dir_t p; @@ -288,17 +295,17 @@ void CardReader::printListing(SdFile parent, const char * const prepend/*=nullpt // Get a new directory object using the full path // and dive recursively into it. - SdFile child; - if (!child.open(&parent, dosFilename, O_READ)) + SdFile child; // child.close() in destructor + if (child.open(&parent, dosFilename, O_READ)) + printListing(child, path); + else { SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); - - printListing(child, path); - // close() is done automatically by destructor of SdFile + return; + } } else if (is_dir_or_gcode(p)) { - createFilename(filename, p); if (prepend) SERIAL_ECHO(prepend); - SERIAL_ECHO(filename); + SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); SERIAL_ECHOLN(p.fileSize); } @@ -342,7 +349,7 @@ void CardReader::ls() { // Go to the next segment while (path[++i]) { } - // SERIAL_ECHOPGM("Looking for segment: "); SERIAL_ECHOLN(segment); + //SERIAL_ECHOLNPAIR("Looking for segment: ", segment); // Find the item, setting the long filename diveDir.rewind(); @@ -720,14 +727,14 @@ void CardReader::removeFile(const char * const name) { //abortFilePrintNow(); - SdFile *curDir; - const char * const fname = diveToFile(false, curDir, name); + SdFile *itsDirPtr; + const char * const fname = diveToFile(false, itsDirPtr, name); if (!fname) return; #if ENABLED(SDCARD_READONLY) SERIAL_ECHOLNPAIR("Deletion failed (read-only), File: ", fname, "."); #else - if (file.remove(curDir, fname)) { + if (file.remove(itsDirPtr, fname)) { SERIAL_ECHOLNPAIR("File deleted:", fname); sdpos = 0; TERN_(SDCARD_SORT_ALPHA, presort()); @@ -870,98 +877,101 @@ uint16_t CardReader::countFilesInWorkDir() { * - If update_cwd was 'true' the workDir now points to the file's directory. * * Returns a pointer to the last segment (filename) of the given DOS 8.3 path. + * On exit, inDirPtr contains an SdFile reference to the file's directory. * * A nullptr result indicates an unrecoverable error. + * + * NOTE: End the path with a slash to dive to a folder. In this case the + * returned filename will be blank (points to the end of the path). */ -const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, const char * const path, const bool echo/*=false*/) { +const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo/*=false*/) { DEBUG_SECTION(est, "diveToFile", true); // Track both parent and subfolder static SdFile newDir1, newDir2; - SdFile *sub = &newDir1, *startDir; + SdFile *sub = &newDir1, *startDirPtr; // Parsing the path string - const char *item_name_adr = path; + const char *atom_ptr = path; DEBUG_ECHOLNPAIR(" path = '", path, "'"); if (path[0] == '/') { // Starting at the root directory? - diveDir = &root; - item_name_adr++; - DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)diveDir)); + inDirPtr = &root; + atom_ptr++; + DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)inDirPtr)); if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else - diveDir = &workDir; // Dive from workDir (as set by the UI) + inDirPtr = &workDir; // Dive from workDir (as set by the UI) - startDir = diveDir; + startDirPtr = inDirPtr; - DEBUG_ECHOLNPAIR(" startDir = ", hex_address((void*)startDir)); + DEBUG_ECHOLNPAIR(" startDirPtr = ", hex_address((void*)startDirPtr)); - while (item_name_adr) { + while (atom_ptr) { // Find next subdirectory delimiter - char * const name_end = strchr(item_name_adr, '/'); + char * const name_end = strchr(atom_ptr, '/'); // Last atom in the path? Item found. - if (name_end <= item_name_adr) break; + if (name_end <= atom_ptr) break; - // Set subDirName - const uint8_t len = name_end - item_name_adr; + // Isolate the next subitem name + const uint8_t len = name_end - atom_ptr; char dosSubdirname[len + 1]; - strncpy(dosSubdirname, item_name_adr, len); + strncpy(dosSubdirname, atom_ptr, len); dosSubdirname[len] = 0; if (echo) SERIAL_ECHOLN(dosSubdirname); DEBUG_ECHOLNPAIR(" sub = ", hex_address((void*)sub)); - // Open diveDir (closing first) + // Open inDirPtr (closing first) sub->close(); - if (!sub->open(diveDir, dosSubdirname, O_READ)) { + if (!sub->open(inDirPtr, dosSubdirname, O_READ)) { openFailed(dosSubdirname); - item_name_adr = nullptr; + atom_ptr = nullptr; break; } - // Close diveDir if not at starting-point - if (diveDir != startDir) { - DEBUG_ECHOLNPAIR(" closing diveDir: ", hex_address((void*)diveDir)); - diveDir->close(); + // Close inDirPtr if not at starting-point + if (inDirPtr != startDirPtr) { + DEBUG_ECHOLNPAIR(" closing inDirPtr: ", hex_address((void*)inDirPtr)); + inDirPtr->close(); } - // diveDir now subDir - diveDir = sub; - DEBUG_ECHOLNPAIR(" diveDir = sub: ", hex_address((void*)diveDir)); + // inDirPtr now subDir + inDirPtr = sub; + DEBUG_ECHOLNPAIR(" inDirPtr = sub: ", hex_address((void*)inDirPtr)); // Update workDirParents and workDirDepth if (update_cwd) { DEBUG_ECHOLNPAIR(" update_cwd"); if (workDirDepth < MAX_DIR_DEPTH) - workDirParents[workDirDepth++] = *diveDir; + workDirParents[workDirDepth++] = *inDirPtr; } // Point sub at the other scratch object - sub = (diveDir != &newDir1) ? &newDir1 : &newDir2; + sub = (inDirPtr != &newDir1) ? &newDir1 : &newDir2; DEBUG_ECHOLNPAIR(" swapping sub = ", hex_address((void*)sub)); // Next path atom address - item_name_adr = name_end + 1; + atom_ptr = name_end + 1; } if (update_cwd) { - workDir = *diveDir; - DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)diveDir)); + workDir = *inDirPtr; + DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)inDirPtr)); flag.workDirIsRoot = (workDirDepth == 0); TERN_(SDCARD_SORT_ALPHA, presort()); } - DEBUG_ECHOLNPAIR(" returning string ", item_name_adr ?: "nullptr"); - return item_name_adr; + DEBUG_ECHOLNPAIR(" returning string ", atom_ptr ?: "nullptr"); + return atom_ptr; } void CardReader::cd(const char * relpath) { - SdFile newDir; - SdFile *parent = workDir.isOpen() ? &workDir : &root; + SdFile newDir, *parent = &getWorkDir(); if (newDir.open(parent, relpath, O_READ)) { workDir = newDir; diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 6f1633d30e..35d7627421 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -111,7 +111,6 @@ public: static void mount(); static void release(); static inline bool isMounted() { return flag.mounted; } - static void ls(); // Handle media insert/remove static void manage_media(); @@ -176,21 +175,32 @@ public: return 0; } - // Helper for open and remove - static const char* diveToFile(const bool update_cwd, SdFile* &curDir, const char * const path, const bool echo=false); + /** + * Dive down to a relative or absolute path. + * Relative paths apply to the workDir. + * + * update_cwd: Pass 'true' to update the workDir on success. + * inDirPtr: On exit your pointer points to the target SdFile. + * A nullptr indicates failure. + * path: Start with '/' for abs path. End with '/' to get a folder ref. + * echo: Set 'true' to print the path throughout the loop. + */ + static const char* diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo=false); #if ENABLED(SDCARD_SORT_ALPHA) static void presort(); static void getfilename_sorted(const uint16_t nr); #if ENABLED(SDSORT_GCODE) - FORCE_INLINE static void setSortOn(bool b) { sort_alpha = b; presort(); } - FORCE_INLINE static void setSortFolders(int i) { sort_folders = i; presort(); } + FORCE_INLINE static void setSortOn(bool b) { sort_alpha = b; presort(); } + FORCE_INLINE static void setSortFolders(int i) { sort_folders = i; presort(); } //FORCE_INLINE static void setSortReverse(bool b) { sort_reverse = b; } #endif #else FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } #endif + static void ls(); + #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); static void openJobRecoveryFile(const bool read); @@ -199,6 +209,7 @@ public: // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } + static inline SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } // Print File stats static inline uint32_t getFileSize() { return filesize; } From 8af4d70922cede7b3e7a6720959c4e2c2d807012 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 22:55:13 -0500 Subject: [PATCH 0152/2168] =?UTF-8?q?=F0=9F=8E=A8=20Shorten=20lcd=20relati?= =?UTF-8?q?ve=20paths?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 3 ++- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/lcd/menu/menu_main.cpp | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index a9ad9c189c..52a877031f 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -28,11 +28,12 @@ #include "wifi_upload.h" #include "SPI_TFT.h" +#include "../../marlinui.h" + #include "../../../MarlinCore.h" #include "../../../module/temperature.h" #include "../../../gcode/queue.h" #include "../../../gcode/gcode.h" -#include "../../../lcd/marlinui.h" #include "../../../sd/cardreader.h" #include "../../../module/planner.h" #include "../../../module/servo.h" diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index b857b62de5..195afecc1b 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extui/ui_api.h" + #include "../extui/ui_api.h" #endif void _man_probe_pt(const xy_pos_t &xy) { diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 17c9b1fe6a..921c2435b5 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -47,7 +47,7 @@ #endif #if ENABLED(MMU2_MENUS) - #include "../../lcd/menu/menu_mmu2.h" + #include "menu_mmu2.h" #endif #if ENABLED(PASSWORD_FEATURE) From 464a9f0ab6adf51bd988936cf6284488c4e797cd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 May 2021 23:03:49 -0500 Subject: [PATCH 0153/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20ExtUI=20examp?= =?UTF-8?q?le?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/example/example.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 959d750872..0e7d71ff4d 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -119,6 +119,12 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result + switch (rst) { + case PID_BAD_EXTRUDER_NUM: break; + case PID_TEMP_TOO_HIGH: break; + case PID_TUNING_TIMEOUT: break; + case PID_DONE: break; + } } #endif From 7c2834c33c488accb0a937e1bacf320889379e1d Mon Sep 17 00:00:00 2001 From: Alvaro Segura Del Barco Date: Sat, 22 May 2021 14:52:41 -0600 Subject: [PATCH 0154/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Teensy=20PINS=5F?= =?UTF-8?q?DEBUG=20compile=20(#21958)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to 84a11cfedc --- Marlin/src/HAL/AVR/pinsDebug.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 6bf9f33a0c..55fddb05b8 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -38,7 +38,7 @@ // portModeRegister takes a different argument #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) #define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin)) #elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70 From 43b736906ae4895b9dca37784743b0b9ea3740a3 Mon Sep 17 00:00:00 2001 From: Danol Date: Sun, 23 May 2021 00:35:07 +0200 Subject: [PATCH 0155/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20wrong=20Z=5FENDS?= =?UTF-8?q?TOP=20flag=20bit=20(#21963)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bug introduced in #18424 --- Marlin/src/module/endstops.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index acd241d432..c3819417e5 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -64,7 +64,7 @@ enum EndstopEnum : char { #define X_ENDSTOP TERN(X_HOME_TO_MAX, X_MAX, X_MIN) #define Y_ENDSTOP TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) -#define Z_ENDSTOP TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE)) +#define Z_ENDSTOP TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) #undef __ES_ITEM #undef _ES_ITEM From 6689e5ed75b5a777273ae3e6a82617349a76e833 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 22 May 2021 17:41:29 -0500 Subject: [PATCH 0156/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Selena=20Compact?= =?UTF-8?q?=20probe=20pin?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 32 ++++++++++--------- 1 file changed, 17 insertions(+), 15 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 29fe3b528c..78cf7a84fc 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -44,7 +44,9 @@ #define Y_MAX_PIN -1 #define Z_MIN_PIN P1_27 #define Z_MAX_PIN -1 -#define Z_PROBE P1_22 +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_22 +#endif // // Steppers @@ -95,22 +97,22 @@ // #if IS_RRD_FG_SC - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define LCD_PINS_D5 P1_00 - #define LCD_PINS_D6 P1_01 - #define LCD_PINS_D7 P1_04 - #define BEEPER_PIN P1_31 + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + #define LCD_PINS_D5 P1_00 + #define LCD_PINS_D6 P1_01 + #define LCD_PINS_D7 P1_04 + #define BEEPER_PIN P1_31 - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P1_30 + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P1_30 - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif // IS_RRD_FG_SC From aee971bcaf2d8b7157985f36f6705015ef334238 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 22 May 2021 17:02:21 -0500 Subject: [PATCH 0157/2168] =?UTF-8?q?=F0=9F=8E=A8=20Combine=20M104/M109=20?= =?UTF-8?q?and=20M140/M190=20code?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.h | 10 ++-- Marlin/src/gcode/temp/M104_M109.cpp | 78 ++++------------------------- Marlin/src/gcode/temp/M140_M190.cpp | 57 +++++---------------- 3 files changed, 27 insertions(+), 118 deletions(-) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index c32575e81e..6f8568730b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -648,8 +648,9 @@ private: #endif #if HAS_EXTRUDERS - static void M104(); - static void M109(); + static void M104_M109(const bool isM109); + FORCE_INLINE static void M104() { M104_M109(false); } + FORCE_INLINE static void M109() { M104_M109(true); } #endif static void M105(); @@ -699,8 +700,9 @@ private: #endif #if HAS_HEATED_BED - static void M140(); - static void M190(); + static void M140_M190(const bool isM190); + FORCE_INLINE static void M140() { M140_M190(false); } + FORCE_INLINE static void M190() { M140_M190(true); } #endif #if HAS_HEATED_CHAMBER diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index eb350a577a..b6a3fa8507 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -51,89 +51,29 @@ /** * M104: Set Hotend Temperature target and return immediately - * - * Parameters: - * I : Material Preset index (if material presets are defined) - * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units - */ -void GcodeSuite::M104() { - - if (DEBUGGING(DRYRUN)) return; - - #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 - constexpr int8_t target_extruder = 0; - #else - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - #endif - - bool got_temp = false; - celsius_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].hotend_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - thermalManager.singlenozzle_temp[target_extruder] = temp; - if (target_extruder != active_extruder) return; - #endif - thermalManager.setTargetHotend(temp, target_extruder); - - #if ENABLED(DUAL_X_CARRIAGE) - if (idex_is_duplicating() && target_extruder == 0) - thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); - #endif - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Start is managed by 'heat and wait' M109. - * Hotends use EXTRUDE_MINTEMP / 2 to allow nozzles to be put into hot standby - * mode, for instance in a dual extruder setup, without affecting the running - * print timer. - */ - thermalManager.auto_job_check_timer(false, true); - #endif - } - - TERN_(AUTOTEMP, planner.autotemp_M104_M109()); -} - -/** * M109: Set Hotend Temperature target and wait * * Parameters * I : Material Preset index (if material presets are defined) * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units. Wait for heating only. - * R : The target temperature in current units. Wait for heating and cooling. + * S : The target temperature in current units. For M109, only wait when heating up. * * With AUTOTEMP... * F : Autotemp Scaling Factor. Set non-zero to enable Auto-temp. * S : Minimum temperature, in current units. * B : Maximum temperature, in current units. * + * M109 Parameters + * R : The target temperature in current units. Wait for heating and cooling. + * * Examples - * M109 S100 : Set target to 100°. Wait until the hotend is at or above 100°. + * M104 S100 : Set target to 100° and return. * M109 R150 : Set target to 150°. Wait until the hotend gets close to 150°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M109() { +void GcodeSuite::M104_M109(const bool isM109) { if (DEBUGGING(DRYRUN)) return; @@ -160,7 +100,7 @@ void GcodeSuite::M109() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); + got_temp = no_wait_for_cooling || (isM109 && parser.seenval('R')); if (got_temp) temp = parser.value_celsius(); } @@ -182,7 +122,7 @@ void GcodeSuite::M109() { * standby mode, (e.g., in a dual extruder setup) without affecting * the running print timer. */ - thermalManager.auto_job_check_timer(true, true); + thermalManager.auto_job_check_timer(isM109, true); #endif #if HAS_STATUS_MESSAGE @@ -193,7 +133,7 @@ void GcodeSuite::M109() { TERN_(AUTOTEMP, planner.autotemp_M104_M109()); - if (got_temp) + if (isM109 && got_temp) (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); } diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 3aed878a03..ddab003973 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -35,62 +35,28 @@ #include "../../lcd/marlinui.h" /** - * M140: Set bed temperature + * M140 - Set Bed Temperature target and return immediately + * M190 - Set Bed Temperature target and wait * * I : Preset index (if material presets are defined) * S : The target temperature in current units - */ -void GcodeSuite::M140() { - if (DEBUGGING(DRYRUN)) return; - - bool got_temp = false; - celsius_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].bed_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - thermalManager.setTargetBed(temp); - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Hotend, bed target, and chamber - * temperatures need to be set below mintemp. Order of M140, M104, and M141 - * at the end of the print does not matter. - */ - thermalManager.auto_job_check_timer(false, true); - #endif - } -} - -/** - * M190 - Set Bed Temperature target and wait * - * Parameters: + * Parameters * I : Preset index (if material presets are defined) * S : The target temperature in current units. Wait for heating only. + * + * M190 Parameters * R : The target temperature in current units. Wait for heating and cooling. * - * Examples: - * M190 S60 : Set target to 60°. Wait until the bed is at or above 60°. + * Examples + * M140 S60 : Set target to 60° and return right away. * M190 R40 : Set target to 40°. Wait until the bed gets close to 40°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M190() { +void GcodeSuite::M140_M190(const bool isM190) { + if (DEBUGGING(DRYRUN)) return; bool got_temp = false; @@ -109,7 +75,7 @@ void GcodeSuite::M190() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); + got_temp = no_wait_for_cooling || (isM190 && parser.seenval('R')); if (got_temp) temp = parser.value_celsius(); } @@ -121,7 +87,8 @@ void GcodeSuite::M190() { ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); - thermalManager.wait_for_bed(no_wait_for_cooling); + if (isM190) + thermalManager.wait_for_bed(no_wait_for_cooling); } #endif // HAS_HEATED_BED From d8c4be375c24f0cda27ff8079b78985e5b8afa97 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 22 May 2021 17:56:31 -0500 Subject: [PATCH 0158/2168] =?UTF-8?q?=F0=9F=8E=A8=20Null=20heating=20messa?= =?UTF-8?q?ge=20method?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/temp/M104_M109.cpp | 6 ++---- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/module/temperature.h | 4 +++- Marlin/src/module/tool_change.cpp | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index b6a3fa8507..efda04def5 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -125,10 +125,8 @@ void GcodeSuite::M104_M109(const bool isM109) { thermalManager.auto_job_check_timer(isM109, true); #endif - #if HAS_STATUS_MESSAGE - if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) - thermalManager.set_heating_message(target_extruder); - #endif + if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) + thermalManager.set_heating_message(target_extruder); } TERN_(AUTOTEMP, planner.autotemp_M104_M109()); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 03c0195085..f9ff9e5fa6 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2526,7 +2526,7 @@ void Temperature::disable_all_heaters() { if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { setTargetHotend(singlenozzle_temp[new_tool], 0); TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_STATUS_MESSAGE, set_heating_message(0)); + set_heating_message(0); (void)wait_for_hotend(0, false); // Wait for heating or cooling } #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 83fbc8fd46..2fd2b639ec 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -869,8 +869,10 @@ class Temperature { #endif #endif - #if HAS_STATUS_MESSAGE + #if HAS_HOTEND && HAS_STATUS_MESSAGE static void set_heating_message(const uint8_t e); + #else + static inline void set_heating_message(const uint8_t) {} #endif #if HAS_LCD_MENU && HAS_TEMPERATURE diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index cc34acc14f..3abab802ab 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1382,7 +1382,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if HAS_MULTI_HOTEND thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_STATUS_MESSAGE, thermalManager.set_heating_message(0)); + thermalManager.set_heating_message(0); thermalManager.wait_for_hotend(active_extruder); #endif From e1921f808cf4d2a392a9c033d3182773d5292b12 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 23 May 2021 01:15:23 +0000 Subject: [PATCH 0159/2168] [cron] Bump distribution date (2021-05-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e78166461b..163b9284cc 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 "2021-05-22" + #define STRING_DISTRIBUTION_DATE "2021-05-23" #endif /** From 92dea8e6ccd26950eed817fce6f574fcfe866489 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 May 2021 01:09:46 -0500 Subject: [PATCH 0160/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor,=20comm?= =?UTF-8?q?ent=20endstop/probe=20enums?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/module/endstops.cpp | 9 ++++++++ Marlin/src/module/endstops.h | 26 ++++++++++++++++++------ Marlin/src/module/probe.cpp | 2 +- 4 files changed, 31 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index d28ef1182e..0ab82a9b16 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -225,7 +225,7 @@ static void _lcd_level_bed_corners_get_next_position() { if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed TERN_(BLTOUCH_SLOW_MODE, bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance - if (TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE))) { // check if probe triggered + if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7a452f1fdd..dff0b6832a 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -403,12 +403,21 @@ void Endstops::event_handler() { } } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { if (label) SERIAL_ECHOPGM_P(label); SERIAL_ECHOPGM(": "); SERIAL_ECHOLNPGM_P(is_hit ? PSTR(STR_ENDSTOP_HIT) : PSTR(STR_ENDSTOP_OPEN)); } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif + void _O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index c3819417e5..5da09f41cf 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -32,12 +32,15 @@ #define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) enum EndstopEnum : char { + // Common XYZ (ABC) endstops. Defined according to USE_[XYZ](MIN|MAX)_PLUG settings. _ES_ITEM(HAS_X_MIN, X_MIN) _ES_ITEM(HAS_X_MAX, X_MAX) _ES_ITEM(HAS_Y_MIN, Y_MIN) _ES_ITEM(HAS_Y_MAX, Y_MAX) _ES_ITEM(HAS_Z_MIN, Z_MIN) _ES_ITEM(HAS_Z_MAX, Z_MAX) + + // Extra Endstops for XYZ #if ENABLED(X_DUAL_ENDSTOPS) _ES_ITEM(HAS_X_MIN, X2_MIN) _ES_ITEM(HAS_X_MAX, X2_MAX) @@ -58,13 +61,24 @@ enum EndstopEnum : char { _ES_ITEM(HAS_Z_MAX, Z4_MAX) #endif #endif - _ES_ITEM(HAS_Z_MIN_PROBE_PIN, Z_MIN_PROBE) - NUM_ENDSTOP_STATES -}; -#define X_ENDSTOP TERN(X_HOME_TO_MAX, X_MAX, X_MIN) -#define Y_ENDSTOP TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) -#define Z_ENDSTOP TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) + // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) + _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(HAS_CUSTOM_PROBE_PIN, = Z_MIN)) + + // The total number of states + NUM_ENDSTOP_STATES + + // Endstops can be either MIN or MAX but not both + #if HAS_X_MIN || HAS_X_MAX + , X_ENDSTOP = TERN(X_HOME_TO_MAX, X_MAX, X_MIN) + #endif + #if HAS_Y_MIN || HAS_Y_MAX + , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) + #endif + #if HAS_Z_MIN || HAS_Z_MAX + , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) + #endif +}; #undef __ES_ITEM #undef _ES_ITEM diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 655b8cc249..6d4a022882 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -509,7 +509,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if BOTH(DELTA, SENSORLESS_PROBING) endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else - TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)) + TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif ; From ff0318c5bd95c6cb18ae9765f1ecb344dc2d6e4e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 22 May 2021 21:08:57 -0500 Subject: [PATCH 0161/2168] =?UTF-8?q?=F0=9F=8E=A8=20pause=20=3D>=20pause?= =?UTF-8?q?=5Fheaters?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/probe.cpp | 2 +- Marlin/src/module/temperature.cpp | 4 ++-- Marlin/src/module/temperature.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 6d4a022882..0042302fc7 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -243,7 +243,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif void Probe::set_probing_paused(const bool dopause) { - TERN_(PROBING_HEATERS_OFF, thermalManager.pause(dopause)); + TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); #if ENABLED(PROBING_STEPPERS_OFF) IF_DISABLED(DELTA, static uint8_t old_trusted); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f9ff9e5fa6..898ffa7d5f 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2439,7 +2439,7 @@ void Temperature::disable_all_heaters() { TERN_(AUTOTEMP, planner.autotemp_enabled = false); // Unpause and reset everything - TERN_(PROBING_HEATERS_OFF, pause(false)); + TERN_(PROBING_HEATERS_OFF, pause_heaters(false)); #if HAS_HOTEND HOTEND_LOOP() { @@ -2498,7 +2498,7 @@ void Temperature::disable_all_heaters() { #if ENABLED(PROBING_HEATERS_OFF) - void Temperature::pause(const bool p) { + void Temperature::pause_heaters(const bool p) { if (p != paused_for_probing) { paused_for_probing = p; if (p) { diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 2fd2b639ec..a80e39cbd8 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -838,7 +838,7 @@ class Temperature { #endif #if ENABLED(PROBING_HEATERS_OFF) - static void pause(const bool p); + static void pause_heaters(const bool p); #endif #if HEATER_IDLE_HANDLER From d71b35c24f5e8d4c40d5e721f3548abfe899592d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 22 May 2021 21:12:53 -0500 Subject: [PATCH 0162/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20shorthand=20an?= =?UTF-8?q?d=20cleanups?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/caselight.cpp | 8 ++------ Marlin/src/feature/dac/stepper_dac.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 21 +++------------------ Marlin/src/module/planner.h | 6 +++--- 5 files changed, 10 insertions(+), 29 deletions(-) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index fb0f6e3bee..5a4e2b2579 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -44,10 +44,6 @@ bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) }; #endif -#ifndef INVERT_CASE_LIGHT - #define INVERT_CASE_LIGHT false -#endif - void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS /** @@ -64,7 +60,7 @@ void CaseLight::update(const bool sflag) { if (sflag && on) brightness = brightness_sav; // Restore last brightness for M355 S1 - const uint8_t i = on ? brightness : 0, n10ct = INVERT_CASE_LIGHT ? 255 - i : i; + const uint8_t i = on ? brightness : 0, n10ct = ENABLED(INVERT_CASE_LIGHT) ? 255 - i : i; UNUSED(n10ct); #endif @@ -86,7 +82,7 @@ void CaseLight::update(const bool sflag) { else #endif { - const bool s = on ? !INVERT_CASE_LIGHT : INVERT_CASE_LIGHT; + const bool s = on ? TERN(INVERT_CASE_LIGHT, LOW, HIGH) : TERN(INVERT_CASE_LIGHT, HIGH, LOW); WRITE(CASE_LIGHT_PIN, s ? HIGH : LOW); } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index bb7954cfe0..1cb0813daa 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -51,7 +51,7 @@ int StepperDAC::init() { mcp4728.setVref_all(DAC_STEPPER_VREF); mcp4728.setGain_all(DAC_STEPPER_GAIN); - if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1 ) { + if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1) { mcp4728.setDrvPct(dac_channel_pct); mcp4728.eepromWrite(); } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 30151b3bd0..fa4682c082 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -566,7 +566,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(AUTO_REPORT_POSITION) - case 154: M154(); break; // M155: Set position auto-report interval + case 154: M154(); break; // M154: Set position auto-report interval #endif #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 45c947e790..a6aed2ad24 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -445,12 +445,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = X_center - displacement; position_max = X_center + displacement; echo_min_max('X', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (X_MIN_POS) - || position_max > (X_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (X_MIN_POS) || position_max > (X_MAX_POS))) { err_out_of_bounds(); return true; } @@ -460,12 +455,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = Y_center - displacement; position_max = Y_center + displacement; echo_min_max('Y', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (Y_MIN_POS) - || position_max > (Y_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { err_out_of_bounds(); return true; } @@ -475,12 +465,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = Z_center - displacement; position_max = Z_center + displacement; echo_min_max('Z', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (Z_MIN_POS) - || position_max > (Z_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { err_out_of_bounds(); return true; } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 2ec90e1fa2..66e98f4a57 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -491,7 +491,7 @@ class Planner { #if HAS_CLASSIC_JERK static void set_max_jerk(const AxisEnum axis, float inMaxJerkMMS); #else - static inline void set_max_jerk(const AxisEnum, const_float_t ) {} + static inline void set_max_jerk(const AxisEnum, const_float_t) {} #endif #if HAS_EXTRUDERS @@ -592,9 +592,9 @@ class Planner { #else - FORCE_INLINE static float fade_scaling_factor_for_z(const_float_t ) { return 1; } + FORCE_INLINE static float fade_scaling_factor_for_z(const_float_t) { return 1; } - FORCE_INLINE static bool leveling_active_at_z(const_float_t ) { return true; } + FORCE_INLINE static bool leveling_active_at_z(const_float_t) { return true; } #endif From 5fde86406fdcf4c9ea21f81c4a834de39dadb3bb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 24 May 2021 01:12:27 +0000 Subject: [PATCH 0163/2168] [cron] Bump distribution date (2021-05-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 163b9284cc..3690ea2c92 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 "2021-05-23" + #define STRING_DISTRIBUTION_DATE "2021-05-24" #endif /** From 731370051de73ad4c92d60ec01563def3da53ddb Mon Sep 17 00:00:00 2001 From: ellensp Date: Mon, 24 May 2021 13:29:19 +1200 Subject: [PATCH 0164/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20PIO=20filters=20?= =?UTF-8?q?for=20M117,=20M300=20and=20M414=20(#21972)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.cpp | 4 +++- Marlin/src/gcode/gcode.h | 6 +++++- Marlin/src/gcode/lcd/M117.cpp | 6 ++++++ ini/features.ini | 4 +++- platformio.ini | 3 +++ 5 files changed, 20 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index fa4682c082..29dbf8d1c2 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -605,7 +605,9 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes case 114: M114(); break; // M114: Report current position case 115: M115(); break; // M115: Report capabilities - case 117: M117(); break; // M117: Set LCD message text, if possible + + case 117: TERN_(HAS_STATUS_MESSAGE, M117()); break; // M117: Set LCD message text, if possible + case 118: M118(); break; // M118: Display a message in the host console case 119: M119(); break; // M119: Report endstop states case 120: M120(); break; // M120: Enable endstops diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6f8568730b..befc328bb9 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -678,7 +678,11 @@ private: static void M114(); static void M115(); - static void M117(); + + #if HAS_STATUS_MESSAGE + static void M117(); + #endif + static void M118(); static void M119(); static void M120(); diff --git a/Marlin/src/gcode/lcd/M117.cpp b/Marlin/src/gcode/lcd/M117.cpp index 59305d94c5..f26694bd64 100644 --- a/Marlin/src/gcode/lcd/M117.cpp +++ b/Marlin/src/gcode/lcd/M117.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfig.h" + +#if HAS_STATUS_MESSAGE + #include "../gcode.h" #include "../../lcd/marlinui.h" @@ -34,3 +38,5 @@ void GcodeSuite::M117() { ui.reset_status(); } + +#endif // HAS_STATUS_MESSAGE diff --git a/ini/features.ini b/ini/features.ini index 2b69daa88a..89df3b99fe 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -61,7 +61,7 @@ HAS_MENU_DELTA_CALIBRATE = src_filter=+ LCD_INFO_MENU = src_filter=+ HAS_MENU_JOB_RECOVERY = src_filter=+ -HAS_MULTI_LANGUAGE = src_filter=+ +HAS_MULTI_LANGUAGE = src_filter=+ + HAS_MENU_LED = src_filter=+ HAS_MENU_MEDIA = src_filter=+ HAS_MENU_MIXER = src_filter=+ @@ -186,7 +186,9 @@ AUTO_REPORT_POSITION = src_filter=+ REPETIER_GCODE_M360 = src_filter=+ HAS_GCODE_M876 = src_filter=+ HAS_RESUME_CONTINUE = src_filter=+ +HAS_STATUS_MESSAGE = src_filter=+ HAS_LCD_CONTRAST = src_filter=+ +HAS_BUZZER = src_filter=+ LCD_SET_PROGRESS_MANUALLY = src_filter=+ TOUCH_SCREEN_CALIBRATION = src_filter=+ ARC_SUPPORT = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 0516149da9..b552eda81d 100644 --- a/platformio.ini +++ b/platformio.ini @@ -202,7 +202,10 @@ default_src_filter = + - - + - - - + - - + - + - - - - From 84fd0eff17d089e3f75f6585d4bba47f15c00ba7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 May 2021 21:33:22 -0500 Subject: [PATCH 0165/2168] =?UTF-8?q?=F0=9F=8E=A8=20Macros=20for=20optiona?= =?UTF-8?q?l=20arguments=20(#21969)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/macros.h | 5 ++ .../feature/bedlevel/mbl/mesh_bed_leveling.h | 4 +- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 8 +- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/fwretract.cpp | 6 +- Marlin/src/feature/fwretract.h | 6 +- Marlin/src/feature/leds/leds.cpp | 4 +- Marlin/src/feature/leds/leds.h | 71 ++++------------- Marlin/src/feature/leds/pca9632.cpp | 8 +- Marlin/src/feature/tmc_util.h | 12 +-- Marlin/src/gcode/bedlevel/G26.cpp | 15 +--- Marlin/src/gcode/motion/G2_G3.cpp | 8 +- Marlin/src/gcode/queue.cpp | 8 +- Marlin/src/gcode/queue.h | 8 +- Marlin/src/lcd/marlinui.cpp | 8 +- Marlin/src/lcd/marlinui.h | 6 +- Marlin/src/lcd/menu/menu_motion.cpp | 12 +-- Marlin/src/lcd/tft/ui_1024x600.cpp | 6 +- Marlin/src/lcd/tft/ui_320x240.cpp | 6 +- Marlin/src/lcd/tft/ui_480x320.cpp | 6 +- Marlin/src/module/motion.cpp | 26 ++----- Marlin/src/module/motion.h | 6 +- Marlin/src/module/planner.cpp | 24 ++---- Marlin/src/module/planner.h | 43 +++-------- Marlin/src/module/temperature.cpp | 77 ++++--------------- Marlin/src/module/temperature.h | 71 +++++++---------- .../sd/usb_flashdrive/lib-uhs2/masstorage.cpp | 10 +-- .../sd/usb_flashdrive/lib-uhs2/masstorage.h | 5 +- 28 files changed, 120 insertions(+), 351 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 566087b76b..7a2d731c01 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -195,6 +195,11 @@ #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 _OPTARG(A) , A +#define OPTARG(O,A) TERN_(O,DEFER4(_OPTARG)(A)) +#define _OPTCODE(A) A; +#define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) + // Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 1ae8135458..cc54695771 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -103,9 +103,7 @@ public: } static float get_z(const xy_pos_t &pos - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , const_float_t factor=1.0f - #endif + OPTARG(ENABLE_LEVELING_FADE_HEIGHT, const_float_t factor=1.0f) ) { #if DISABLED(ENABLE_LEVELING_FADE_HEIGHT) constexpr float factor = 1.0f; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 3ebc5fc2bd..4af608cce4 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -362,15 +362,11 @@ while (--segments) { raw += diff; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); } planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); return false; // Did not set current from destination } diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 5a4e2b2579..ec4ad99c75 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -41,7 +41,7 @@ bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; #if CASE_LIGHT_IS_COLOR_LED #include "leds/leds.h" constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; - LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) }; + LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; #endif void CaseLight::update(const bool sflag) { diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index d133d6060c..41dbf430e8 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -91,11 +91,7 @@ void FWRetract::reset() { * Note: Auto-retract will apply the set Z hop in addition to any Z hop * included in the G-code. Use M207 Z0 to to prevent double hop. */ -void FWRetract::retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping/*=false*/ - #endif -) { +void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping/*=false*/)) { // Prevent two retracts or recovers in a row if (retracted[active_extruder] == retracting) return; diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index 4fa64ad83b..cd93e9cf39 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -74,11 +74,7 @@ public: #endif } - static void retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping = false - #endif - ); + static void retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping = false)); static void M207(); static void M207_report(const bool forReplay=false); diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 8349049a00..c9178effa8 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -75,9 +75,7 @@ void LEDLights::setup() { } void LEDLights::set_color(const LEDColor &incol - #if ENABLED(NEOPIXEL_LED) - , bool isSequence/*=false*/ - #endif + OPTARG(NEOPIXEL_LED, bool isSequence/*=false*/) ) { #if ENABLED(NEOPIXEL_LED) diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index cec95102d7..4157ff816e 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -43,46 +43,21 @@ */ typedef struct LEDColor { uint8_t r, g, b - #if HAS_WHITE_LED - , w - #if ENABLED(NEOPIXEL_LED) - , i - #endif - #endif + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) ; LEDColor() : r(255), g(255), b(255) - #if HAS_WHITE_LED - , w(255) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(255)) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} - LEDColor(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - #endif - #endif - ) : r(r), g(g), b(b) - #if HAS_WHITE_LED - , w(w) - #if ENABLED(NEOPIXEL_LED) - , i(i) - #endif - #endif - {} + LEDColor(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) + : r(r), g(g), b(b) OPTARG(HAS_WHITE_LED, w(w)) OPTARG(NEOPIXEL_LED, i(i)) {} LEDColor(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) - #if HAS_WHITE_LED - , w(rgbw[3]) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(rgbw[3])) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} LEDColor& operator=(const uint8_t (&rgbw)[4]) { @@ -111,15 +86,7 @@ typedef struct LEDColor { /** * Color helpers and presets */ -#if HAS_WHITE_LED - #if ENABLED(NEOPIXEL_LED) - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W, I) - #else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W) - #endif -#else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B) -#endif +#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B OPTARG(HAS_WHITE_LED, W) OPTARG(NEOPIXEL_LED, I)) #define LEDColorOff() LEDColor( 0, 0, 0) #define LEDColorRed() LEDColor(255, 0, 0) @@ -147,25 +114,15 @@ public: static void setup(); // init() static void set_color(const LEDColor &color - #if ENABLED(NEOPIXEL_LED) - , bool isSequence=false - #endif + OPTARG(NEOPIXEL_LED, bool isSequence=false) ); static inline void set_color(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #endif - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - , bool isSequence=false - #endif + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + OPTARG(NEOPIXEL_LED, bool isSequence=false) ) { - set_color(MakeLEDColor(r, g, b, w, i) - #if ENABLED(NEOPIXEL_LED) - , isSequence - #endif - ); + set_color(MakeLEDColor(r, g, b, w, i) OPTARG(NEOPIXEL_LED, isSequence)); } static inline void set_off() { set_color(LEDColorOff()); } diff --git a/Marlin/src/feature/leds/pca9632.cpp b/Marlin/src/feature/leds/pca9632.cpp index bb30e0b48b..abea988004 100644 --- a/Marlin/src/feature/leds/pca9632.cpp +++ b/Marlin/src/feature/leds/pca9632.cpp @@ -93,9 +93,7 @@ static void PCA9632_WriteRegister(const byte addr, const byte regadd, const byte } static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte vr, const byte vg, const byte vb - #if ENABLED(PCA9632_RGBW) - , const byte vw - #endif + OPTARG(PCA9632_RGBW, const byte vw) ) { #if DISABLED(PCA9632_NO_AUTO_INC) uint8_t data[4]; @@ -143,9 +141,7 @@ void PCA9632_set_led_color(const LEDColor &color) { ; PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, color.r, color.g, color.b - #if ENABLED(PCA9632_RGBW) - , color.w - #endif + OPTARG(PCA9632_RGBW, color.w) ); PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_LEDOUT, LEDOUT); } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index a0e07ab8a8..179f38f729 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -70,15 +70,9 @@ class TMCStorage { } struct { - #if ENABLED(HAS_STEALTHCHOP) - bool stealthChop_enabled = false; - #endif - #if ENABLED(HYBRID_THRESHOLD) - uint8_t hybrid_thrs = 0; - #endif - #if ENABLED(USE_SENSORLESS) - int16_t homing_thrs = 0; - #endif + OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false) + OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0) + OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0) } stored; }; diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 1e70652bdc..616f16a58a 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -330,12 +330,8 @@ typedef struct { thermalManager.setTargetBed(bed_temp); // Wait for the temperature to stabilize - if (!thermalManager.wait_for_bed(true - #if G26_CLICK_CAN_CANCEL - , true - #endif - ) - ) return G26_ERR; + if (!thermalManager.wait_for_bed(true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; } #else @@ -352,11 +348,8 @@ typedef struct { thermalManager.setTargetHotend(hotend_temp, active_extruder); // Wait for the temperature to stabilize - if (!thermalManager.wait_for_hotend(active_extruder, true - #if G26_CLICK_CAN_CANCEL - , true - #endif - )) return G26_ERR; + if (!thermalManager.wait_for_hotend(active_extruder, true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; #if HAS_WIRED_LCD ui.reset_status(); diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 41ff7e9765..bafc79bcac 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -249,9 +249,7 @@ void plan_arc( #endif if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) )) break; } @@ -266,9 +264,7 @@ void plan_arc( #endif planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index c007537398..09755fbf21 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -84,9 +84,7 @@ char GCodeQueue::injected_commands[64]; // = { 0 } void GCodeQueue::RingBuffer::commit_command(bool skip_ok - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind/*=-1*/ - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { commands[index_w].skip_ok = skip_ok; TERN_(HAS_MULTI_SERIAL, commands[index_w].port = serial_ind); @@ -100,9 +98,7 @@ void GCodeQueue::RingBuffer::commit_command(bool skip_ok * Return false for a full buffer, or if the 'command' is a comment. */ bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind/*=-1*/ - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { if (*cmd == ';' || length >= BUFSIZE) return false; strcpy(commands[index_w].buffer, cmd); diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 5df4a0104c..ea99ce7a2d 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -80,15 +80,11 @@ public: void advance_pos(uint8_t &p, const int inc) { if (++p >= BUFSIZE) p = 0; length += inc; } void commit_command(bool skip_ok - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind = serial_index_t() - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) ); bool enqueue(const char *cmd, bool skip_ok = true - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind = serial_index_t() - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) ); void ok_to_send(); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 14959851fa..ba3abc0e2d 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -758,13 +758,9 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Tell ui.update() to start a move to current_position after a short delay. // void ManualMove::soon(const AxisEnum move_axis - #if MULTI_E_MANUAL - , const int8_t eindex/*=-1*/ - #endif + OPTARG(MULTI_E_MANUAL, const int8_t eindex/*=active_extruder*/) ) { - #if MULTI_E_MANUAL - if (move_axis == E_AXIS) e_index = eindex >= 0 ? eindex : active_extruder; - #endif + TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves axis = move_axis; //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ba0221713b..766e46c66b 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -182,11 +182,7 @@ static bool constexpr processing = false; #endif static void task(); - static void soon(const AxisEnum axis - #if MULTI_E_MANUAL - , const int8_t eindex=-1 - #endif - ); + static void soon(const AxisEnum axis OPTARG(MULTI_E_MANUAL, const int8_t eindex=active_extruder)); }; #endif diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 06d635ffc8..516f04632e 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -94,17 +94,13 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } #if E_MANUAL - static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=-1)) { + static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=active_extruder)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.manual_move.processing) { const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; TERN(IS_KINEMATIC, ui.manual_move.offset, current_position.e) += diff; - ui.manual_move.soon(E_AXIS - #if MULTI_E_MANUAL - , eindex - #endif - ); + ui.manual_move.soon(E_AXIS OPTARG(MULTI_E_MANUAL, eindex)); ui.refresh(LCDVIEW_REDRAW_NOW); } ui.encoderPosition = 0; @@ -139,7 +135,7 @@ void _goto_manual_move(const_float_t scale) { ui.goto_screen(_manual_move_func_ptr); } -void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=-1) { +void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=active_extruder) { _manual_move_func_ptr = func; START_MENU(); if (LCD_HEIGHT >= 4) { @@ -188,7 +184,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_E_MANUAL, active_extruder)); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(); }); }); } inline void _menu_move_distance_e_maybe() { diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 87b016b1ec..631d6d8582 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -724,11 +724,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 89a127b01e..f7b6ffc75d 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -709,11 +709,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 6923bdd71c..93df6eb961 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -711,11 +711,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 235a969f66..6801b210af 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -411,9 +411,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { * - Extrude the specified length regardless of flow percentage. */ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ - #if IS_KINEMATIC - , const bool is_fast/*=false*/ - #endif + OPTARG(IS_KINEMATIC, const bool is_fast/*=false*/) ) { const feedRate_t old_feedrate = feedrate_mm_s; if (fr_mm_s) feedrate_mm_s = fr_mm_s; @@ -433,9 +431,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ feedrate_mm_s = old_feedrate; feedrate_percentage = old_pct; - #if HAS_EXTRUDERS - planner.e_factor[active_extruder] = old_fac; - #endif + TERN_(HAS_EXTRUDERS, planner.e_factor[active_extruder] = old_fac); } /** @@ -607,10 +603,8 @@ void restore_feedrate_and_scaling() { * at the same positions relative to the machine. */ void update_software_endstops(const AxisEnum axis - #if HAS_HOTEND_OFFSET - , const uint8_t old_tool_index/*=0*/ - , const uint8_t new_tool_index/*=0*/ - #endif + OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index/*=0*/) + OPTARG(HAS_HOTEND_OFFSET, const uint8_t new_tool_index/*=0*/) ) { #if ENABLED(DUAL_X_CARRIAGE) @@ -858,17 +852,13 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { 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 - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) )) break; } // Ensure last segment arrives at target location. planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); return false; // caller will update current_position @@ -929,9 +919,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { 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) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) )) break; } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index a43af6446b..67205a7636 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -278,11 +278,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s); void prepare_line_to_destination(); -void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f - #if IS_KINEMATIC - , const bool is_fast=false - #endif -); +void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f OPTARG(IS_KINEMATIC, const bool is_fast=false)); inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) { _internal_move_to_destination(fr_mm_s); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 714be8019e..09db12cd7a 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1757,12 +1757,8 @@ void Planner::synchronize() { * Returns true if movement was properly queued, false otherwise (if cleaning) */ bool Planner::_buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters ) { @@ -1823,12 +1819,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target */ bool Planner::_populate_block(block_t * const block, bool split_move, const abce_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { @@ -2763,9 +2755,7 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc. */ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { @@ -2857,9 +2847,7 @@ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const_float_t inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration) ) { xyze_pos_t machine = { rx, ry, rz, e }; TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 66e98f4a57..be004dd3f4 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -707,12 +707,8 @@ class Planner { * Returns true if movement was buffered, false otherwise */ static bool _buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); @@ -728,14 +724,9 @@ class Planner { * * Returns true is movement is acceptable, false otherwise */ - static bool _populate_block(block_t * const block, bool split_move, - const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + static bool _populate_block(block_t * const block, bool split_move, const xyze_long_t &target + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); @@ -768,22 +759,16 @@ class Planner { * millimeters - the length of the movement, if known */ static bool buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ) { return buffer_segment(abce.a, abce.b, abce.c, abce.e - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif + OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) , fr_mm_s, extruder, millimeters); } @@ -801,20 +786,14 @@ class Planner { * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ static bool buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const_float_t inv_duration=0.0 - #endif + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ); FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const_float_t inv_duration=0.0 - #endif + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ) { return buffer_line(cart.x, cart.y, cart.z, cart.e, fr_mm_s, extruder, millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); } diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 898ffa7d5f..e2a1899202 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3335,11 +3335,8 @@ void Temperature::isr() { * Extruder: " T0:nnn.nn /nnn.nn" * With ADC: " T0:nnn.nn /nnn.nn (nnn.nn)" */ - static void print_heater_state(const_celsius_float_t c, const_celsius_float_t t - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , const float r - #endif - , const heater_id_t e=INDEX_NONE + static void print_heater_state(const heater_id_t e, const_celsius_float_t c, const_celsius_float_t t + OPTARG(SHOW_TEMP_ADC_VALUES, const float r) ) { char k; switch (e) { @@ -3385,64 +3382,28 @@ void Temperature::isr() { } void Temperature::print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r/*=false*/ - #endif + OPTARG(TEMP_SENSOR_1_AS_REDUNDANT, const bool include_r/*=false*/) ) { #if HAS_TEMP_HOTEND - print_heater_state(degHotend(target_extruder), degTargetHotend(target_extruder) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(target_extruder) - #endif - ); + print_heater_state(H_NONE, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (include_r) print_heater_state(degHotendRedundant(), degTargetHotend(0) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTempRedundant() - #endif - , H_REDUNDANT - ); + if (include_r) print_heater_state(H_REDUNDANT, degHotendRedundant(), degTargetHotend(0) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTempRedundant())); #endif #endif #if HAS_HEATED_BED - print_heater_state(degBed(), degTargetBed() - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawBedTemp() - #endif - , H_BED - ); + print_heater_state(H_BED, degBed(), degTargetBed() OPTARG(SHOW_TEMP_ADC_VALUES, rawBedTemp())); #endif #if HAS_TEMP_CHAMBER - print_heater_state(degChamber(), TERN0(HAS_HEATED_CHAMBER, degTargetChamber()) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawChamberTemp() - #endif - , H_CHAMBER - ); - #endif // HAS_TEMP_CHAMBER + print_heater_state(H_CHAMBER, degChamber(), TERN0(HAS_HEATED_CHAMBER, degTargetChamber()) OPTARG(SHOW_TEMP_ADC_VALUES, rawChamberTemp())); + #endif #if HAS_TEMP_COOLER - print_heater_state(degCooler(), TERN0(HAS_COOLER, degTargetCooler()) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawCoolerTemp() - #endif - , H_COOLER - ); - #endif // HAS_TEMP_COOLER + print_heater_state(H_COOLER, degCooler(), TERN0(HAS_COOLER, degTargetCooler()) OPTARG(SHOW_TEMP_ADC_VALUES, rawCoolerTemp())); + #endif #if HAS_TEMP_PROBE - print_heater_state(degProbe(), 0 - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawProbeTemp() - #endif - , H_PROBE - ); + print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp()) ); #endif #if HAS_MULTI_HOTEND - HOTEND_LOOP() print_heater_state(degHotend(e), degTargetHotend(e) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(e) - #endif - , (heater_id_t)e - ); + HOTEND_LOOP() print_heater_state((heater_id_t)e, degHotend(e), degTargetHotend(e) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(e))); #endif SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED @@ -3465,10 +3426,7 @@ void Temperature::isr() { #if ENABLED(AUTO_REPORT_TEMPERATURES) AutoReporter Temperature::auto_reporter; - void Temperature::AutoReportTemp::report() { - print_heater_states(active_extruder); - SERIAL_EOL(); - } + void Temperature::AutoReportTemp::report() { print_heater_states(active_extruder); SERIAL_EOL(); } #endif #if HAS_HOTEND && HAS_STATUS_MESSAGE @@ -3495,11 +3453,8 @@ void Temperature::isr() { #endif bool Temperature::wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { - #if ENABLED(AUTOTEMP) REMEMBER(1, planner.autotemp_enabled, false); #endif @@ -3638,9 +3593,7 @@ void Temperature::isr() { #endif bool Temperature::wait_for_bed(const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { #if TEMP_BED_RESIDENCY_TIME > 0 millis_t residency_start_ms = 0; diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index a80e39cbd8..660fde8af6 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -46,7 +46,7 @@ // Element identifiers. Positive values are hotends. Negative values are other heaters or coolers. typedef enum : int8_t { - INDEX_NONE = -6, + H_NONE = -6, H_COOLER, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 } heater_id_t; @@ -395,21 +395,21 @@ class Temperature { } heater_idle_t; // Indices and size for the heater_idle array - #define _ENUM_FOR_E(N) IDLE_INDEX_E##N, - enum IdleIndex : uint8_t { - REPEAT(HOTENDS, _ENUM_FOR_E) - #if ENABLED(HAS_HEATED_BED) - IDLE_INDEX_BED, - #endif - NR_HEATER_IDLE + enum IdleIndex : int8_t { + _II = -1 + + #define _IDLE_INDEX_E(N) ,IDLE_INDEX_E##N + REPEAT(HOTENDS, _IDLE_INDEX_E) + #undef _IDLE_INDEX_E + + OPTARG(HAS_HEATED_BED, IDLE_INDEX_BED) + + , NR_HEATER_IDLE }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to idle array index static inline IdleIndex idle_index_for_id(const int8_t heater_id) { - #if HAS_HEATED_BED - if (heater_id == H_BED) return IDLE_INDEX_BED; - #endif + TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); return (IdleIndex)_MAX(heater_id, 0); } @@ -672,9 +672,7 @@ class Temperature { #if HAS_TEMP_HOTEND static bool wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); #if ENABLED(WAIT_FOR_HOTEND) @@ -721,9 +719,7 @@ class Temperature { } static bool wait_for_bed(const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); static void wait_for_bed_heating(); @@ -859,9 +855,7 @@ class Temperature { #if HAS_TEMP_SENSOR static void print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r=false - #endif + OPTARG(TEMP_SENSOR_1_AS_REDUNDANT, const bool include_r=false) ); #if ENABLED(AUTO_REPORT_TEMPERATURES) struct AutoReportTemp { static void report(); }; @@ -925,35 +919,24 @@ class Temperature { #if HAS_THERMAL_PROTECTION // Indices and size for the tr_state_machine array. One for each protected heater. - #define _ENUM_FOR_E(N) RUNAWAY_IND_E##N, - enum RunawayIndex : uint8_t { + enum RunawayIndex : int8_t { + _RI = -1 #if ENABLED(THERMAL_PROTECTION_HOTENDS) - REPEAT(HOTENDS, _ENUM_FOR_E) + #define _RUNAWAY_IND_E(N) ,RUNAWAY_IND_E##N + REPEAT(HOTENDS, _RUNAWAY_IND_E) + #undef _RUNAWAY_IND_E #endif - #if ENABLED(HAS_THERMALLY_PROTECTED_BED) - RUNAWAY_IND_BED, - #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - RUNAWAY_IND_CHAMBER, - #endif - #if ENABLED(THERMAL_PROTECTION_COOLER) - RUNAWAY_IND_COOLER, - #endif - NR_HEATER_RUNAWAY + OPTARG(HAS_THERMALLY_PROTECTED_BED, RUNAWAY_IND_BED) + OPTARG(THERMAL_PROTECTION_CHAMBER, RUNAWAY_IND_CHAMBER) + OPTARG(THERMAL_PROTECTION_COOLER, RUNAWAY_IND_COOLER) + , NR_HEATER_RUNAWAY }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to runaway state array index static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) { - #if HAS_THERMALLY_PROTECTED_CHAMBER - if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER; - #endif - #if HAS_THERMALLY_PROTECTED_CHAMBER - if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER; - #endif - #if HAS_THERMALLY_PROTECTED_BED - if (heater_id == H_BED) return RUNAWAY_IND_BED; - #endif + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); + TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); return (RunawayIndex)_MAX(heater_id, 0); } diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index a84a683204..1aeef1703f 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -956,12 +956,6 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { return ((error && !count) ? MASS_ERR_GENERAL_USB_ERROR : MASS_ERR_SUCCESS); } -#if MS_WANT_PARSER - uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf) { - return Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf, 0); - } -#endif - /** * For driver use only. * @@ -972,9 +966,7 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { * @return */ uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf - #if MS_WANT_PARSER - , uint8_t flags - #endif + OPTARG(MS_WANT_PARSER, uint8_t flags/*=0*/) ) { #if MS_WANT_PARSER uint16_t bytes = (pcbw->dCBWDataTransferLength > buf_size) ? buf_size : pcbw->dCBWDataTransferLength; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index 25df006e51..aafb91624b 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -553,10 +553,7 @@ private: bool IsValidCSW(CommandStatusWrapper *pcsw, CommandBlockWrapperBase *pcbw); uint8_t ClearEpHalt(uint8_t index); - #if MS_WANT_PARSER - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf, uint8_t flags); - #endif - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf); + uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf OPTARG(MS_WANT_PARSER, uint8_t flags=0)); uint8_t HandleUsbError(uint8_t error, uint8_t index); uint8_t HandleSCSIError(uint8_t status); }; From 9398c431128fc92dcd18ac8cf556e266e4692bf4 Mon Sep 17 00:00:00 2001 From: gjdodd <31553294+gjdodd@users.noreply.github.com> Date: Mon, 24 May 2021 07:54:10 +0100 Subject: [PATCH 0166/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20flowmeter=20calc?= =?UTF-8?q?ulation=20(#21959)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/cooler.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/cooler.h b/Marlin/src/feature/cooler.h index 1e24c729f3..9bd98d0b10 100644 --- a/Marlin/src/feature/cooler.h +++ b/Marlin/src/feature/cooler.h @@ -78,10 +78,8 @@ public: // Get the total flow (in liters per minute) since the last reading static void calc_flowrate() { - //flowmeter_interrupt_disable(); - // const uint16_t pulses = flowpulses; - //flowmeter_interrupt_enable(); - flowrate = flowpulses * 60.0f * (1000.0f / (FLOWMETER_INTERVAL)) * (1000.0f / (FLOWMETER_PPL)); + // flowrate = (litres) * (seconds) = litres per minute + flowrate = (flowpulses / (float)FLOWMETER_PPL) * ((1000.0f / (float)FLOWMETER_INTERVAL) * 60.0f); flowpulses = 0; } From 76e80aa40010e7699af3dcaff4af2bbd7e269842 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Mon, 24 May 2021 14:57:45 +0800 Subject: [PATCH 0167/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Octopus=20HS=20U?= =?UTF-8?q?SB=20(#21961)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PeripheralPins.c | 173 +++++++++++------- 1 file changed, 108 insertions(+), 65 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c index 75bbd1cf20..333bef3db2 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c @@ -132,70 +132,96 @@ const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED const PinMap PinMap_PWM[] = { - {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx - // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx - {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N - // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N - {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4 - {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2 - {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // E1 Heater, TIM3_CH1 - {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2 - {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1 - {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2 - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 - // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 - // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BED + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER0 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER2 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER3 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN2 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 FAN3 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 FAN4 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN5 + + /** + * Unused by specifications on Octopus. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + + //176 pins mcu, 140 gpio + //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {NC, NP, 0} }; #endif @@ -367,7 +393,24 @@ const PinMap PinMap_USB_OTG_FS[] = { #endif #ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { +const PinMap PinMap_USB_OTG_HS[] = { + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + + /*#error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + */ {NC, NP, 0} }; From 0d7075b90c225d2f88e1d790b2df4acbdfcfac8b Mon Sep 17 00:00:00 2001 From: LawnMo <81721212+LawnMo@users.noreply.github.com> Date: Mon, 24 May 2021 09:21:21 +0200 Subject: [PATCH 0168/2168] =?UTF-8?q?=F0=9F=A9=B9=20Improved=20SKR2=201286?= =?UTF-8?q?4=20LCD=20Delays=20(#21956)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 5e2f88190d..c46e0f03f0 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -502,13 +502,13 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) #endif #endif From dd4990252e891cdfe56cb7d6e3bbe1e6289be649 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 24 May 2021 16:38:57 -0500 Subject: [PATCH 0169/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20Linea?= =?UTF-8?q?r=20/=20Logical=20/=20Distinct=20Axes=20(#21953)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * More patches supporting EXTRUDERS 0 * Extend types in prep for more axes --- Marlin/src/core/serial.cpp | 7 +- Marlin/src/core/serial.h | 7 +- Marlin/src/core/types.h | 440 ++++++++++-------- Marlin/src/core/utility.h | 8 + Marlin/src/feature/encoder_i2c.cpp | 43 +- Marlin/src/feature/tmc_util.cpp | 34 +- Marlin/src/feature/tmc_util.h | 14 +- Marlin/src/gcode/calibrate/G28.cpp | 27 +- Marlin/src/gcode/calibrate/G425.cpp | 12 +- Marlin/src/gcode/calibrate/M425.cpp | 10 +- Marlin/src/gcode/config/M200-M205.cpp | 27 +- Marlin/src/gcode/config/M92.cpp | 43 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 24 +- Marlin/src/gcode/feature/pause/G61.cpp | 12 +- Marlin/src/gcode/feature/trinamic/M122.cpp | 18 +- Marlin/src/gcode/gcode.cpp | 26 +- Marlin/src/gcode/gcode.h | 37 +- Marlin/src/gcode/geometry/G92.cpp | 39 +- Marlin/src/gcode/host/M114.cpp | 2 +- Marlin/src/gcode/motion/G0_G1.cpp | 10 +- Marlin/src/gcode/motion/G2_G3.cpp | 31 +- Marlin/src/gcode/motion/M290.cpp | 2 +- Marlin/src/gcode/parser.cpp | 3 +- Marlin/src/gcode/parser.h | 2 +- Marlin/src/inc/Conditionals_LCD.h | 94 ++-- Marlin/src/inc/Conditionals_adv.h | 20 + Marlin/src/inc/Conditionals_post.h | 249 +++++----- Marlin/src/inc/SanityCheck.h | 27 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 6 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 8 +- Marlin/src/lcd/marlinui.cpp | 10 +- Marlin/src/lcd/menu/menu_advanced.cpp | 40 +- Marlin/src/module/endstops.cpp | 11 +- Marlin/src/module/motion.cpp | 102 ++-- Marlin/src/module/motion.h | 14 +- Marlin/src/module/planner.cpp | 266 ++++++----- Marlin/src/module/planner.h | 50 +- Marlin/src/module/settings.cpp | 46 +- Marlin/src/module/stepper.cpp | 56 ++- Marlin/src/module/stepper.h | 16 +- Marlin/src/module/stepper/trinamic.cpp | 23 +- buildroot/tests/mega2560 | 12 +- buildroot/tests/rambo | 2 + 43 files changed, 1142 insertions(+), 788 deletions(-) diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index b4184fcd62..60729440e6 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -101,8 +101,11 @@ void print_bin(uint16_t val) { } } -void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { +void print_pos( + LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z) + , PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/ +) { if (prefix) serialprintPGM(prefix); - SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z); + SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z)); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 74b96dbb64..6f893795df 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -310,10 +310,13 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos( + LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z), + PGM_P const prefix=nullptr, PGM_P const suffix=nullptr +); inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_pos(xyz.x, xyz.y, xyz.z, prefix, suffix); + print_pos(LINEAR_AXIS_LIST(xyz.x, xyz.y, xyz.z), prefix, suffix); } #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index b7ae85eb2e..41cb39f163 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -39,6 +39,26 @@ struct IF { typedef R type; }; template struct IF { typedef L type; }; +#define LINEAR_AXIS_GANG(V...) GANG_N(LINEAR_AXES, V) +#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V) +#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V) +#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) } + +#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E) +#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E) +#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E) +#define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } + +#if HAS_EXTRUDERS + #define LIST_ITEM_E(N) , N + #define CODE_ITEM_E(N) ; N + #define GANG_ITEM_E(N) N +#else + #define LIST_ITEM_E(N) + #define CODE_ITEM_E(N) + #define GANG_ITEM_E(N) +#endif + // // Enumerated axis indices // @@ -47,16 +67,43 @@ struct IF { typedef L type; }; // - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics // enum AxisEnum : uint8_t { - X_AXIS = 0, A_AXIS = X_AXIS, - Y_AXIS = 1, B_AXIS = Y_AXIS, - Z_AXIS = 2, C_AXIS = Z_AXIS, - E_AXIS, - X_HEAD, Y_HEAD, Z_HEAD, - E0_AXIS = E_AXIS, - E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS, + + // Linear axes may be controlled directly or indirectly + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS), + + // Extruder axes may be considered distinctly + #define _EN_ITEM(N) E##N##_AXIS, + REPEAT(EXTRUDERS, _EN_ITEM) + #undef _EN_ITEM + + // Core also keeps toolhead directions + #if IS_CORE + X_HEAD, Y_HEAD, Z_HEAD, + #endif + + // Distinct axes, including all E and Core + NUM_AXIS_ENUMS, + + // Most of the time we refer only to the single E_AXIS + #if HAS_EXTRUDERS + E_AXIS = E0_AXIS, + #endif + + // A, B, and C are for DELTA, SCARA, etc. + A_AXIS = X_AXIS, + #if LINEAR_AXES >= 2 + B_AXIS = Y_AXIS, + #endif + #if LINEAR_AXES >= 3 + C_AXIS = Z_AXIS, + #endif + + // To refer to all or none ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; +typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; + // // Loop over axes // @@ -185,7 +232,7 @@ void toNative(xyz_pos_t &raw); void toNative(xyze_pos_t &raw); // -// XY coordinates, counters, etc. +// Paired XY coordinates, counters, flags, etc. // template struct XYval { @@ -197,10 +244,14 @@ 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 DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + #if LINEAR_AXES > XY + FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; } + #endif + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + #endif #endif FI void reset() { x = y = 0; } FI T magnitude() const { return (T)sqrtf(x*x + y*y); } @@ -223,8 +274,8 @@ struct XYval { FI operator XYZval() const { return { x, y }; } FI operator XYZEval() { return { x, y }; } FI operator XYZEval() const { return { x, y }; } - FI T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } FI XYval& operator= (const T v) { set(v, v ); return *this; } FI XYval& operator= (const XYZval &rs) { set(rs.x, rs.y); return *this; } FI XYval& operator= (const XYZEval &rs) { set(rs.x, rs.y); return *this; } @@ -294,219 +345,227 @@ struct XYval { }; // -// XYZ coordinates, counters, etc. +// Linear Axes coordinates, counters, flags, etc. // template struct XYZval { union { - struct { T x, y, z; }; - struct { T a, b, c; }; - T pos[3]; + struct { T LINEAR_AXIS_LIST(x, y, z); }; + struct { T LINEAR_AXIS_LIST(a, b, c); }; + T pos[LINEAR_AXES]; }; 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 px, const T py, const T pz) { x = px; y = py; z = pz; } + FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } 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 DISTINCT_AXES > XYZE - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; } + FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } + #if LINEAR_AXES >= XYZ + FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) + { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } #endif - FI void reset() { x = y = z = 0; } - FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } + FI void set(LOGICAL_AXIS_LIST(const T, const T px, const T py, const T pz)) + { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } + #endif + #endif + FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =) 0; } + FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z)); } FI operator T* () { return pos; } - FI operator bool() { return z || x || y; } + FI operator bool() { return LINEAR_AXIS_GANG(z, || x, || y); } FI XYZval copy() const { XYZval o = *this; return o; } - FI XYZval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)) }; } - FI XYZval asInt() { return { int16_t(x), int16_t(y), int16_t(z) }; } - 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 { static_cast(x), static_cast(y), static_cast(z) }; } - FI XYZval asFloat() const { return { static_cast(x), static_cast(y), static_cast(z) }; } - FI XYZval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z) }; } + FI XYZval ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); } + FI XYZval asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); } + FI XYZval asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); } + FI XYZval asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); } + FI XYZval asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); } + FI XYZval ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } + FI XYZval ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } + FI XYZval asFloat() { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z)); } + FI XYZval asFloat() const { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z)); } + FI XYZval reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z)); } FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } FI operator XYval&() { return *(XYval*)this; } FI operator const XYval&() const { return *(const XYval*)this; } - FI operator XYZEval() const { return { x, y, z }; } - FI T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } - FI XYZval& operator= (const T v) { set(v, v, v ); return *this; } + FI operator XYZEval() const { return LINEAR_AXIS_ARRAY(x, y, z); } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + FI XYZval& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; } FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } - FI XYZval& operator= (const XYZEval &rs) { set(rs.x, rs.y, rs.z); return *this; } - FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZval operator- (const XYval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZval operator* (const XYval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator>>(const int &v) const { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } - FI XYZval operator>>(const int &v) { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } - FI XYZval operator<<(const int &v) const { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } - FI XYZval operator<<(const int &v) { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } - FI XYZval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZval& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } - FI XYZval& operator*=(const int &v) { x *= v; y *= v; z *= v; return *this; } - FI XYZval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); return *this; } - FI XYZval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); return *this; } - FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y && z == rs.z; } + FI XYZval& operator= (const XYZEval &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; } + FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; } + FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; } + FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZval operator>>(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } + FI XYZval operator>>(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } + FI XYZval operator<<(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } + FI XYZval operator<<(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } + FI XYZval& operator+=(const XYval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP ); return *this; } + FI XYZval& operator-=(const XYval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP ); return *this; } + FI XYZval& operator*=(const XYval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP ); return *this; } + FI XYZval& operator/=(const XYval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP ); return *this; } + FI XYZval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; } + FI XYZval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; } + FI XYZval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; } + FI XYZval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; } + FI XYZval& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; } + FI XYZval& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; } + FI XYZval& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z) ); return *this; } + FI XYZval& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z) ); return *this; } + FI bool operator==(const XYZEval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } + FI bool operator==(const XYZEval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } - FI bool operator==(const XYZEval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } - FI XYZval operator-() { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } - FI const XYZval operator-() const { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } + FI XYZval operator-() { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; } + FI const XYZval operator-() const { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; } }; // -// XYZE coordinates, counters, etc. +// Logical Axes coordinates, counters, etc. // template struct XYZEval { union { - struct{ T x, y, z, e; }; - struct{ T a, b, c; }; - T pos[4]; + struct{ T LOGICAL_AXIS_LIST(e, x, y, z); }; + struct{ T LINEAR_AXIS_LIST(a, b, c); }; + T pos[LOGICAL_AXES]; }; - FI void reset() { x = y = z = e = 0; } - FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z + e*e); } + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =) 0; } + FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z)); } FI operator T* () { return pos; } - FI operator bool() { return e || z || x || y; } - 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 px, const T py, const T pz) { x = px; y = py; z = pz; } - FI void set(const T px, const T py, const T pz, const T pe) { x = px; y = py; z = pz; e = pe; } - FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } - FI void set(const XYZval pxyz) { x = pxyz.x; y = pxyz.y; z = pxyz.z; } - 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 DISTINCT_AXES > XYZE - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } + FI operator bool() { return false LOGICAL_AXIS_GANG(|| e, || x, || y, || z); } + 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 XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYZval pxyz) { set(LINEAR_AXIS_LIST(pxyz.x, pxyz.y, pxyz.z)); } + #if LINEAR_AXES >= XYZ + FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) { + LINEAR_AXIS_CODE(x = px, y = py, z = pz); + } #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() { 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 { static_cast(x), static_cast(y), static_cast(z), static_cast(e) }; } - FI XYZEval asFloat() const { return { static_cast(x), static_cast(y), static_cast(z), static_cast(e) }; } - FI XYZEval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(e) }; } + #if LOGICAL_AXES > LINEAR_AXES + FI void set(LOGICAL_AXIS_LIST(const T pe, const T px, const T py, const T pz)) { + LOGICAL_AXIS_CODE(e = pe, x = px, y = py, z = pz); + } + FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } + FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + #endif + FI XYZEval copy() const { XYZEval o = *this; return o; } + FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); } + FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); } + FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); } + FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); } + FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); } + FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } + FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } + FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z)); } + FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z)); } + FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z)); } FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } FI operator XYval&() { return *(XYval*)this; } FI operator const XYval&() const { return *(const XYval*)this; } FI operator XYZval&() { return *(XYZval*)this; } FI operator const XYZval&() const { return *(const XYZval*)this; } - FI T& operator[](const int i) { return pos[i]; } - FI const T& operator[](const int i) const { return pos[i]; } - FI XYZEval& operator= (const T v) { set(v, v, v, v); return *this; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + FI XYZEval& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; } FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } - FI XYZEval& operator= (const XYZval &rs) { set(rs.x, rs.y, rs.z); return *this; } - FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator+ (const XYZval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZEval operator+ (const XYZval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } - FI XYZEval operator- (const XYZval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZEval operator- (const XYZval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } - FI XYZEval operator* (const XYZval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZEval operator* (const XYZval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } - FI XYZEval operator/ (const XYZval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZEval operator/ (const XYZval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } - FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } - FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } - FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } - FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } - FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } - FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } - FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } - FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } - FI XYZEval operator* (const float &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const float &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const int &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator* (const int &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } - FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const float &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator/ (const int &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } - FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } - FI XYZEval operator>>(const int &v) { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } - FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } - FI XYZEval operator<<(const int &v) { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } - FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZEval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } - FI XYZEval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } - FI XYZEval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } - FI XYZEval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } - FI XYZEval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; e += rs.e; return *this; } - FI XYZEval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; e -= rs.e; return *this; } - FI XYZEval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; e *= rs.e; return *this; } - FI XYZEval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; e /= rs.e; return *this; } - FI XYZEval& operator*=(const T &v) { x *= v; y *= v; z *= v; e *= v; return *this; } - FI XYZEval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); _RS(e); return *this; } - FI XYZEval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); _LS(e); return *this; } - FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y && z == rs.z; } + FI XYZEval& operator= (const XYZval &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; } + FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } + FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } + FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } + FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } + FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; } + FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; } + FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; } + FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; } + FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; } + FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; } + FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; } + FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; } + FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } + FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } + FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } + FI XYZEval operator>>(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } + FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } + FI XYZEval operator<<(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } + FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYZEval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z); return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z); return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z); return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z); return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z); return *this; } + FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v); return *this; } + FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z)); return *this; } + FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z)); return *this; } + FI bool operator==(const XYZval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } + FI bool operator==(const XYZval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } FI bool operator!=(const XYZval &rs) { return !operator==(rs); } - FI bool operator==(const XYZval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI XYZEval operator-() { return { -x, -y, -z, -e }; } - FI const XYZEval operator-() const { return { -x, -y, -z, -e }; } + FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); } + FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); } }; #undef _RECIP @@ -514,6 +573,3 @@ struct XYZEval { #undef _LS #undef _RS #undef FI - -const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; -#define AXIS_CHAR(A) ((char)('X' + A)) diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index d774b007b6..31d0ac6ef4 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -76,3 +76,11 @@ public: // Converts from an uint8_t in the range of 0-255 to an uint8_t // in the range 0-100 while avoiding rounding artifacts constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; } + +const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z'); + +#if LINEAR_AXES <= XYZ + #define AXIS_CHAR(A) ((char)('X' + A)) +#else + #define AXIS_CHAR(A) axis_codes[A] +#endif diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index d6c88613fd..c6881591b6 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -327,7 +327,7 @@ int32_t I2CPositionEncoder::get_raw_count() { } bool I2CPositionEncoder::test_axis() { - //only works on XYZ cartesian machines for the time being + // Only works on XYZ Cartesian machines for the time being if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; const float startPosition = soft_endstop.min[encoderAxis] + 10, @@ -345,9 +345,12 @@ bool I2CPositionEncoder::test_axis() { endCoord[encoderAxis] = endPosition; planner.synchronize(); - startCoord.e = planner.get_axis_position_mm(E_AXIS); - planner.buffer_line(startCoord, fr_mm_s, 0); - planner.synchronize(); + + #if HAS_EXTRUDERS + startCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(startCoord, fr_mm_s, 0); + planner.synchronize(); + #endif // if the module isn't currently trusted, wait until it is (or until it should be if things are working) if (!trusted) { @@ -357,7 +360,7 @@ bool I2CPositionEncoder::test_axis() { } if (trusted) { // if trusted, commence test - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); } @@ -402,7 +405,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); LOOP_L_N(i, iter) { - startCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); @@ -411,7 +414,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { //do_blocking_move_to(endCoord); - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); @@ -497,9 +500,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_1_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_1_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 1 @@ -528,9 +529,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_2_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_2_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 2 @@ -557,11 +556,9 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_ec_threshold(I2CPE_ENC_3_EC_THRESH); #endif - encoders[i].set_active(encoders[i].passes_test(true)); + encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_3_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_3_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 3 @@ -590,9 +587,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_4_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_4_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 4 @@ -621,9 +616,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_5_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_5_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 5 @@ -652,9 +645,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_6_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_6_AXIS == E_AXIS) encoders[i].set_homed()); #endif } diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 9c4fbf08df..e244a33eee 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -757,7 +757,10 @@ } } - static void tmc_debug_loop(const TMC_debug_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { + static void tmc_debug_loop( + const TMC_debug_enum i, + LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) + ) { if (print_x) { #if AXIS_IS_TMC(X) tmc_status(stepperX, i); @@ -821,7 +824,10 @@ SERIAL_EOL(); } - static void drv_status_loop(const TMC_drv_status_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { + static void drv_status_loop( + const TMC_drv_status_enum i, + LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) + ) { if (print_x) { #if AXIS_IS_TMC(X) tmc_parse_drv_status(stepperX, i); @@ -889,9 +895,12 @@ * M122 report functions */ - void tmc_report_all(const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/, const bool print_e/*=true*/) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) + void tmc_report_all( + LOGICAL_AXIS_LIST(const bool print_e/*=true*/, const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/) + ) { + #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) + #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) + TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) TMC_REPORT("Address\t", TMC_UART_ADDR); @@ -1015,7 +1024,10 @@ } #endif - static void tmc_get_registers(TMC_get_registers_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { + static void tmc_get_registers( + TMC_get_registers_enum i, + LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) + ) { if (print_x) { #if AXIS_IS_TMC(X) tmc_get_registers(stepperX, i); @@ -1079,8 +1091,10 @@ SERIAL_EOL(); } - void tmc_get_registers(bool print_x, bool print_y, bool print_z, bool print_e) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, print_x, print_y, print_z, print_e); }while(0) + void tmc_get_registers( + LOGICAL_AXIS_LIST(bool print_e, bool print_x, bool print_y, bool print_z) + ) { + #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1214,7 +1228,9 @@ static bool test_connection(TMC &st) { return test_result; } -void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/, const bool test_e/*=true*/) { +void test_tmc_connection( + LOGICAL_AXIS_LIST(const bool test_e/*=true*/, const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/) +) { uint8_t axis_connection = 0; if (test_x) { diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 179f38f729..a07d6ce0ee 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -335,14 +335,20 @@ void tmc_print_current(TMC &st) { #endif void monitor_tmc_drivers(); -void test_tmc_connection(const bool test_x=true, const bool test_y=true, const bool test_z=true, const bool test_e=true); +void test_tmc_connection( + LOGICAL_AXIS_LIST(const bool test_e=true, const bool test_x=true, const bool test_y=true, const bool test_z=true) +); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(const bool print_x=true, const bool print_y=true, const bool print_z=true, const bool print_e=true); - void tmc_get_registers(const bool print_x, const bool print_y, const bool print_z, const bool print_e); + void tmc_report_all( + LOGICAL_AXIS_LIST(const bool print_e=true, const bool print_x=true, const bool print_y=true, const bool print_z=true) + ); + void tmc_get_registers( + LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) + ); #endif /** @@ -355,7 +361,7 @@ void test_tmc_connection(const bool test_x=true, const bool test_y=true, const b #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool x, y, z, x2, y2, z2, z3, z4; }; + struct sensorless_t { bool LINEAR_AXIS_LIST(x, y, z), x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index aacfcfa42f..a71f541593 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -321,12 +321,23 @@ void GcodeSuite::G28() { #else + #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS)))) + const bool homeZ = parser.seen_test('Z'), - needX = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(X_AXIS))), - needY = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(Y_AXIS))), - homeX = needX || parser.seen_test('X'), homeY = needY || parser.seen_test('Y'), - home_all = homeX == homeY && homeX == homeZ, // All or None - doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; + LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing + needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false // UNUSED + ), + LINEAR_AXIS_LIST( // Home each axis if needed or flagged + homeX = needX || parser.seen_test('X'), + homeY = needY || parser.seen_test('Y'), + homeZZ = homeZ // UNUSED + ), + // Home-all if all or none are flagged + home_all = true LINEAR_AXIS_GANG(&& homeX == homeX, && homeX == homeY, && homeX == homeZ), + LINEAR_AXIS_LIST(doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ); + + UNUSED(needZ); + UNUSED(homeZZ); #if ENABLED(HOME_Z_FIRST) @@ -336,7 +347,7 @@ void GcodeSuite::G28() { const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; - if (z_homing_height && (doX || doY || TERN0(Z_SAFE_HOMING, doZ))) { + if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ)))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); @@ -469,7 +480,7 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(Y2) stepperY2.rms_current(tmc_save_current_Y2); #endif - #endif + #endif // HAS_HOMING_CURRENT ui.refresh(); @@ -490,7 +501,7 @@ void GcodeSuite::G28() { static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = { X_AXIS, Y_AXIS, Z_AXIS, X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, - E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS + E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS }; for (uint8_t j = 1; j <= L64XX::chain[0]; j++) { const uint8_t cv = L64XX::chain[j]; diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 2fb4502267..723f1ebd7b 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -307,9 +307,11 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x); - m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y); - m.pos_error.z = true_center.z - m.obj_center.z; + LINEAR_AXIS_CODE( + m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x), + m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y), + m.pos_error.z = true_center.z - m.obj_center.z + ); } #if ENABLED(CALIBRATION_REPORTING) @@ -455,7 +457,9 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 }; + const xyz_float_t move = LINEAR_AXIS_ARRAY( + AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 + ); current_position += move; calibration_move(); current_position -= move; calibration_move(); } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 432144f491..7de33c1f2a 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -48,10 +48,12 @@ void GcodeSuite::M425() { auto axis_can_calibrate = [](const uint8_t a) { switch (a) { - default: - case X_AXIS: return AXIS_CAN_CALIBRATE(X); - case Y_AXIS: return AXIS_CAN_CALIBRATE(Y); - case Z_AXIS: return AXIS_CAN_CALIBRATE(Z); + default: return false; + LINEAR_AXIS_CODE( + case X_AXIS: return AXIS_CAN_CALIBRATE(X), + case Y_AXIS: return AXIS_CAN_CALIBRATE(Y), + case Z_AXIS: return AXIS_CAN_CALIBRATE(Z) + ); } }; diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 06751f41c4..e765fd55b2 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -88,7 +88,7 @@ void GcodeSuite::M201() { LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a)); } } @@ -106,7 +106,7 @@ void GcodeSuite::M203() { LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a)); } } @@ -165,17 +165,16 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); - if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); - if (parser.seenval('Z')) { - planner.set_max_jerk(Z_AXIS, parser.value_linear_units()); - #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) - if (planner.max_jerk.z <= 0.1f) - SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); - #endif - } - #if HAS_CLASSIC_E_JERK - if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); + bool seenZ = false; + LOGICAL_AXIS_CODE( + if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()), + if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()), + if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()), + if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()) + ); + #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) + if (seenZ && planner.max_jerk.z <= 0.1f) + SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); #endif - #endif + #endif // HAS_CLASSIC_JERK } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 06c47b8253..100cf96f15 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -25,10 +25,12 @@ void report_M92(const bool echo=true, const int8_t e=-1) { if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); - SERIAL_ECHOPAIR_P(PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS])); - #if DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]) + )); + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif SERIAL_EOL(); @@ -64,25 +66,28 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL"))) - return report_M92(true, target_extruder); + if (!parser.seen( + LOGICAL_AXIS_GANG("E", "X", "Y", "Z") + TERN_(MAGIC_NUMBERS_GCODE, "HL") + )) return report_M92(true, target_extruder); LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - if (i == E_AXIS) { - const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); - if (value < 20) { - float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. - #if HAS_CLASSIC_JERK && HAS_CLASSIC_E_JERK - planner.max_jerk.e *= factor; - #endif - planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; - planner.max_acceleration_steps_per_s2[E_AXIS_N(target_extruder)] *= factor; - } - planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; - } - else { + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) planner.settings.axis_steps_per_mm[i] = parser.value_per_axis_units((AxisEnum)i); + else { + #if HAS_EXTRUDERS + const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); + if (value < 20) { + float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. + #if HAS_CLASSIC_JERK && HAS_CLASSIC_E_JERK + planner.max_jerk.e *= factor; + #endif + planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; + planner.max_acceleration_steps_per_s2[E_AXIS_N(target_extruder)] *= factor; + } + planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; + #endif } } } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index f02508a901..b7cec2d48d 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -33,11 +33,13 @@ * M17: Enable stepper motors */ void GcodeSuite::M17() { - if (parser.seen("XYZE")) { - if (parser.seen_test('X')) ENABLE_AXIS_X(); - if (parser.seen_test('Y')) ENABLE_AXIS_Y(); - if (parser.seen_test('Z')) ENABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(); + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) { + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), + if (parser.seen_test('X')) ENABLE_AXIS_X(), + if (parser.seen_test('Y')) ENABLE_AXIS_Y(), + if (parser.seen_test('Z')) ENABLE_AXIS_Z() + ); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -54,12 +56,14 @@ void GcodeSuite::M18_M84() { stepper_inactive_time = parser.value_millis_from_seconds(); } else { - if (parser.seen("XYZE")) { + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) { planner.synchronize(); - if (parser.seen_test('X')) DISABLE_AXIS_X(); - if (parser.seen_test('Y')) DISABLE_AXIS_Y(); - if (parser.seen_test('Z')) DISABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), + if (parser.seen_test('X')) DISABLE_AXIS_X(), + if (parser.seen_test('Y')) DISABLE_AXIS_Y(), + if (parser.seen_test('Z')) DISABLE_AXIS_Z() + ); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index a6d7cb3094..14a2e64969 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -69,7 +69,7 @@ void GcodeSuite::G61(void) { SYNC_E(stored_position[slot].e); } else { - if (parser.seen("XYZ")) { + if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) { DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); LOOP_LINEAR_AXES(i) { destination[i] = parser.seen(AXIS_CHAR(i)) @@ -82,10 +82,12 @@ void GcodeSuite::G61(void) { // Move to the saved position prepare_line_to_destination(); } - if (parser.seen_test('E')) { - DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); - SYNC_E(stored_position[slot].e); - } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); + SYNC_E(stored_position[slot].e); + } + #endif } feedrate_mm_s = saved_feedrate; diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 054d145c8c..3b4406705c 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -49,13 +49,21 @@ void GcodeSuite::M122() { tmc_set_report_interval(interval); #endif - if (parser.seen_test('V')) - tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e); - else - tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + if (parser.seen_test('V')) { + tmc_get_registers( + LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) + ); + } + else { + tmc_report_all( + LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) + ); + } #endif - test_tmc_connection(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + test_tmc_connection( + LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) + ); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 29dbf8d1c2..b7a842ece7 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -74,11 +74,11 @@ millis_t GcodeSuite::previous_move_ms = 0, // Relative motion mode for each logical axis static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; -uint8_t GcodeSuite::axis_relative = ( - (ar_init.x ? _BV(REL_X) : 0) - | (ar_init.y ? _BV(REL_Y) : 0) - | (ar_init.z ? _BV(REL_Z) : 0) - | (ar_init.e ? _BV(REL_E) : 0) +uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( + | (ar_init.e << REL_E), + | (ar_init.x << REL_X), + | (ar_init.y << REL_Y), + | (ar_init.z << REL_Z) ); #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) @@ -161,13 +161,15 @@ void GcodeSuite::get_destination_from_command() { destination[i] = current_position[i]; } - // Get new E position, whether absolute or relative - if ( (seen.e = parser.seenval('E')) ) { - const float v = parser.value_axis_units(E_AXIS); - destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; - } - else - destination.e = current_position.e; + #if HAS_EXTRUDERS + // Get new E position, whether absolute or relative + if ( (seen.e = parser.seenval('E')) ) { + const float v = parser.value_axis_units(E_AXIS); + destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; + } + else + destination.e = current_position.e; + #endif #if ENABLED(POWER_LOSS_RECOVERY) && !PIN_EXISTS(POWER_LOSS) // Only update power loss recovery on moves with E diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index befc328bb9..05b6c0cdd5 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -314,7 +314,12 @@ #define HAS_FAST_MOVES 1 #endif -enum AxisRelative : uint8_t { REL_X, REL_Y, REL_Z, REL_E, E_MODE_ABS, E_MODE_REL }; +enum AxisRelative : uint8_t { + LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z) + #if HAS_EXTRUDERS + , E_MODE_ABS, E_MODE_REL + #endif +}; extern const char G28_STR[]; @@ -324,23 +329,27 @@ public: static uint8_t axis_relative; static inline bool axis_is_relative(const AxisEnum a) { - if (a == E_AXIS) { - if (TEST(axis_relative, E_MODE_REL)) return true; - if (TEST(axis_relative, E_MODE_ABS)) return false; - } + #if HAS_EXTRUDERS + if (a == E_AXIS) { + if (TEST(axis_relative, E_MODE_REL)) return true; + if (TEST(axis_relative, E_MODE_ABS)) return false; + } + #endif return TEST(axis_relative, a); } static inline void set_relative_mode(const bool rel) { - axis_relative = rel ? _BV(REL_X) | _BV(REL_Y) | _BV(REL_Z) | _BV(REL_E) : 0; - } - static inline void set_e_relative() { - CBI(axis_relative, E_MODE_ABS); - SBI(axis_relative, E_MODE_REL); - } - static inline void set_e_absolute() { - CBI(axis_relative, E_MODE_REL); - SBI(axis_relative, E_MODE_ABS); + axis_relative = rel ? (0 LOGICAL_AXIS_GANG(| _BV(REL_E), | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z))) : 0; } + #if HAS_EXTRUDERS + static inline void set_e_relative() { + CBI(axis_relative, E_MODE_ABS); + SBI(axis_relative, E_MODE_REL); + } + static inline void set_e_absolute() { + CBI(axis_relative, E_MODE_REL); + SBI(axis_relative, E_MODE_ABS); + } + #endif #if ENABLED(CNC_WORKSPACE_PLANES) /** diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index a9970b1e9c..990236c0e8 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -48,7 +48,10 @@ */ void GcodeSuite::G92() { - bool sync_E = false, sync_XYZE = false; + #if HAS_EXTRUDERS + bool sync_E = false; + #endif + bool sync_XYZE = false; #if USE_GCODE_SUBCODES const uint8_t subcode_G92 = parser.subcode; @@ -72,7 +75,11 @@ void GcodeSuite::G92() { case 9: // G92.9 - Set Current Position directly (like Marlin 1.0) LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - if (i == E_AXIS) sync_E = true; else sync_XYZE = true; + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) + sync_XYZE = true; + else { + TERN_(HAS_EXTRUDERS, sync_E = true); + } current_position[i] = parser.value_axis_units((AxisEnum)i); } } @@ -83,20 +90,26 @@ void GcodeSuite::G92() { LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters - v = i == E_AXIS ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) + v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) d = v - current_position[i]; // How much is the current axis position altered by? if (!NEAR_ZERO(d)) { #if HAS_POSITION_SHIFT && !IS_SCARA // When using workspaces... - if (i == E_AXIS) { - sync_E = true; - current_position.e = v; // ...E is still set directly - } - else { - position_shift[i] += d; // ...but other axes offset the workspace. + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { + position_shift[i] += d; // ...most axes offset the workspace... update_workspace_offset((AxisEnum)i); } + else { + #if HAS_EXTRUDERS + sync_E = true; + current_position.e = v; // ...but E is set directly + #endif + } #else // Without workspaces... - if (i == E_AXIS) sync_E = true; else sync_XYZE = true; + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) + sync_XYZE = true; + else { + TERN_(HAS_EXTRUDERS, sync_E = true); + } current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) #endif } @@ -111,8 +124,10 @@ void GcodeSuite::G92() { coordinate_system[active_coordinate_system] = position_shift; #endif - if (sync_XYZE) sync_plan_position(); - else if (sync_E) sync_plan_position_e(); + if (sync_XYZE) sync_plan_position(); + #if HAS_EXTRUDERS + else if (sync_E) sync_plan_position_e(); + #endif IF_DISABLED(DIRECT_STEPPING, report_current_position()); } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 2d43d33aa1..d28373696a 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -170,7 +170,7 @@ SERIAL_ECHOPGM("FromStp:"); get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) - xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) }; + xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(planner.get_axis_position_mm(E_AXIS), cartes.x, cartes.y, cartes.z); report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 73c5b11714..30f8248037 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -49,9 +49,11 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (IsRunning() #if ENABLED(NO_MOTION_BEFORE_HOMING) && !homing_needed_error( - (parser.seen_test('X') ? _BV(X_AXIS) : 0) - | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0) - | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0) ) + LINEAR_AXIS_GANG( + (parser.seen_test('X') ? _BV(X_AXIS) : 0), + | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0), + | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0)) + ) #endif ) { TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING)); @@ -83,7 +85,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (fwretract.autoretract_enabled && parser.seen('E') && !parser.seen("XYZ")) { + if (fwretract.autoretract_enabled && parser.seen_test('E') && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index bafc79bcac..4d9f5559fe 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -109,23 +109,32 @@ void plan_arc( #endif } - float linear_travel = cart[l_axis] - start_L, - extruder_travel = cart.e - current_position.e; + float linear_travel = cart[l_axis] - start_L; + + #if HAS_EXTRUDERS + float extruder_travel = cart.e - current_position.e; + #endif // If circling around... if (ENABLED(ARC_P_CIRCLES) && circles) { const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder part_per_circle = RADIANS(360) / total_angular, // Each circle's part of the total - l_per_circle = linear_travel * part_per_circle, // L movement per circle - e_per_circle = extruder_travel * part_per_circle; // E movement per circle + l_per_circle = linear_travel * part_per_circle; // L movement per circle + + #if HAS_EXTRUDERS + const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle + #endif + xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position for (uint16_t n = circles; n--;) { - temp_position.e += e_per_circle; // Destination E axis + TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis temp_position[l_axis] += l_per_circle; // Destination L axis plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle } linear_travel = cart[l_axis] - current_position[l_axis]; - extruder_travel = cart.e - current_position.e; + #if HAS_EXTRUDERS + extruder_travel = cart.e - current_position.e; + #endif } const float flat_mm = radius * angular_travel, @@ -179,16 +188,19 @@ void plan_arc( xyze_pos_t raw; const float theta_per_segment = angular_travel / segments, linear_per_segment = linear_travel / segments, - extruder_per_segment = extruder_travel / segments, sq_theta_per_segment = sq(theta_per_segment), sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6, cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation + #if HAS_EXTRUDERS + const float extruder_per_segment = extruder_travel / segments; + #endif + // Initialize the linear axis raw[l_axis] = current_position[l_axis]; // Initialize the extruder axis - raw.e = current_position.e; + TERN_(HAS_EXTRUDERS, raw.e = current_position.e); #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / seg_length; @@ -240,7 +252,8 @@ void plan_arc( #else raw[l_axis] += linear_per_segment; #endif - raw.e += extruder_per_segment; + + TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment); apply_motion_limits(raw); diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 0a858090f9..1f0d494baf 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M290() { } #endif - if (!parser.seen("XYZ") || parser.seen('R')) { + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z")) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 514d6b7a5d..b07e92555c 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -248,7 +248,8 @@ void GCodeParser::parse(char *p) { case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return; #endif - case 'X' ... 'Z': case 'E' ... 'F': + LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':) + case 'F': if (motion_mode_codenum < 0) return; command_letter = 'G'; codenum = motion_mode_codenum; diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 4270e04c9f..dc3f3c35fb 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -226,7 +226,7 @@ public: // Seen any axis parameter static inline bool seen_axis() { - return seen("XYZE"); + return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z")); } #if ENABLED(GCODE_QUOTED_STRINGS) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 8001674dc4..a8bd7a70ac 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -537,12 +537,12 @@ * E_STEPPERS - Number of actual E stepper motors * E_MANUAL - Number of E steppers for LCD move options */ - #if EXTRUDERS #define HAS_EXTRUDERS 1 #if EXTRUDERS > 1 #define HAS_MULTI_EXTRUDER 1 #endif + #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) #else #undef EXTRUDERS #define EXTRUDERS 0 @@ -551,6 +551,7 @@ #undef SWITCHING_NOZZLE #undef MIXING_EXTRUDER #undef HOTEND_IDLE_TIMEOUT + #undef DISABLE_E #endif #if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS @@ -604,6 +605,50 @@ #define E_MANUAL EXTRUDERS #endif +/** + * Number of Linear Axes (e.g., XYZ) + * All the logical axes except for the tool (E) axis + */ +#ifndef LINEAR_AXES + #define LINEAR_AXES XYZ +#endif + +/** + * Number of Logical Axes (e.g., XYZE) + * All the logical axes that can be commanded directly by G-code. + * Delta maps stepper-specific values to ABC steppers. + */ +#if HAS_EXTRUDERS + #define LOGICAL_AXES INCREMENT(LINEAR_AXES) +#else + #define LOGICAL_AXES LINEAR_AXES +#endif + +/** + * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. + * + * DISTINCT_AXES is the number of distinct addressable axes (not steppers). + * Includes all linear axes plus all distinguished extruders. + * The default behavior is to treat all extruders as a single E axis + * with shared motion and temperature settings. + * + * DISTINCT_E is the number of distinguished extruders. By default this + * well be 1 which indicates all extruders share the same settings. + * + * E_INDEX_N(E) should be used to get the E index of any item that might be + * distinguished. + */ +#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 + #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS) + #define DISTINCT_E E_STEPPERS + #define E_INDEX_N(E) (E) +#else + #undef DISTINCT_E_FACTORS + #define DISTINCT_AXES LOGICAL_AXES + #define DISTINCT_E 1 + #define E_INDEX_N(E) 0 +#endif + #if HOTENDS #define HAS_HOTEND 1 #ifndef HOTEND_OVERSHOOT @@ -624,10 +669,6 @@ #define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) #define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) -#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) - #define DO_SWITCH_EXTRUDER 1 -#endif - /** * Default hotend offsets, if not defined */ @@ -653,40 +694,11 @@ #undef SINGLENOZZLE_STANDBY_FAN #endif -/** - * Number of Linear Axes (e.g., XYZ) - * All the logical axes except for the tool (E) axis - */ -#ifndef LINEAR_AXES - #define LINEAR_AXES XYZ +// Switching extruder has its own servo? +#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) + #define DO_SWITCH_EXTRUDER 1 #endif -/** - * Number of Logical Axes (e.g., XYZE) - * All the logical axes that can be commanded directly by G-code. - * Delta maps stepper-specific values to ABC steppers. - */ -#if HAS_EXTRUDERS - #define LOGICAL_AXES INCREMENT(LINEAR_AXES) -#else - #define LOGICAL_AXES LINEAR_AXES -#endif - -/** - * DISTINCT_E_FACTORS affects whether Extruders use different settings - */ -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 - #define DISTINCT_E E_STEPPERS - #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS) - #define E_INDEX_N(E) (E) -#else - #undef DISTINCT_E_FACTORS - #define DISTINCT_E 1 - #define DISTINCT_AXES LOGICAL_AXES - #define E_INDEX_N(E) 0 -#endif -#define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) - /** * The BLTouch Probe emulates a servo probe * and uses "special" angles for its state. @@ -726,6 +738,9 @@ #define HAS_BED_PROBE 1 #endif +/** + * Fill in undefined Filament Sensor options + */ #if ENABLED(FILAMENT_RUNOUT_SENSOR) #if NUM_RUNOUT_SENSORS >= 1 #ifndef FIL_RUNOUT1_STATE @@ -834,6 +849,9 @@ #define Z_HOME_TO_MIN 1 #endif +/** + * Conditionals based on the type of Bed Probe + */ #if HAS_BED_PROBE #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 @@ -868,7 +886,7 @@ #endif /** - * Set granular options based on the specific type of leveling + * Conditionals based on the type of Bed Leveling */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 1d3253b1cc..18082044e0 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -103,6 +103,9 @@ #undef THERMAL_PROTECTION_PERIOD #undef WATCH_TEMP_PERIOD #undef SHOW_TEMP_ADC_VALUES + #undef LCD_SHOW_E_TOTAL + #undef MANUAL_E_MOVES_RELATIVE + #undef STEALTHCHOP_E #endif #if TEMP_SENSOR_BED == 0 @@ -482,6 +485,23 @@ #endif #endif +// Remove unused STEALTHCHOP flags +#if LINEAR_AXES < 6 + #undef STEALTHCHOP_K + #if LINEAR_AXES < 5 + #undef STEALTHCHOP_J + #if LINEAR_AXES < 4 + #undef STEALTHCHOP_I + #if LINEAR_AXES < 3 + #undef STEALTHCHOP_Z + #if LINEAR_AXES < 2 + #undef STEALTHCHOP_Y + #endif + #endif + #endif + #endif +#endif + // // SD Card connection methods // Defined here so pins and sanity checks can use them diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d86b02bdc2..a0e5db301e 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1563,133 +1563,137 @@ #endif // Extruder steppers and solenoids -#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) - #define HAS_E0_ENABLE 1 -#endif -#if PIN_EXISTS(E0_DIR) - #define HAS_E0_DIR 1 -#endif -#if PIN_EXISTS(E0_STEP) - #define HAS_E0_STEP 1 -#endif -#if PIN_EXISTS(E0_MS1) - #define HAS_E0_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL0) - #define HAS_SOLENOID_0 1 -#endif +#if HAS_EXTRUDERS -#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) - #define HAS_E1_ENABLE 1 -#endif -#if PIN_EXISTS(E1_DIR) - #define HAS_E1_DIR 1 -#endif -#if PIN_EXISTS(E1_STEP) - #define HAS_E1_STEP 1 -#endif -#if PIN_EXISTS(E1_MS1) - #define HAS_E1_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL1) - #define HAS_SOLENOID_1 1 -#endif + #if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) + #define HAS_E0_ENABLE 1 + #endif + #if PIN_EXISTS(E0_DIR) + #define HAS_E0_DIR 1 + #endif + #if PIN_EXISTS(E0_STEP) + #define HAS_E0_STEP 1 + #endif + #if PIN_EXISTS(E0_MS1) + #define HAS_E0_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL0) + #define HAS_SOLENOID_0 1 + #endif -#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) - #define HAS_E2_ENABLE 1 -#endif -#if PIN_EXISTS(E2_DIR) - #define HAS_E2_DIR 1 -#endif -#if PIN_EXISTS(E2_STEP) - #define HAS_E2_STEP 1 -#endif -#if PIN_EXISTS(E2_MS1) - #define HAS_E2_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL2) - #define HAS_SOLENOID_2 1 -#endif + #if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) + #define HAS_E1_ENABLE 1 + #endif + #if PIN_EXISTS(E1_DIR) + #define HAS_E1_DIR 1 + #endif + #if PIN_EXISTS(E1_STEP) + #define HAS_E1_STEP 1 + #endif + #if PIN_EXISTS(E1_MS1) + #define HAS_E1_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL1) + #define HAS_SOLENOID_1 1 + #endif -#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) - #define HAS_E3_ENABLE 1 -#endif -#if PIN_EXISTS(E3_DIR) - #define HAS_E3_DIR 1 -#endif -#if PIN_EXISTS(E3_STEP) - #define HAS_E3_STEP 1 -#endif -#if PIN_EXISTS(E3_MS1) - #define HAS_E3_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL3) - #define HAS_SOLENOID_3 1 -#endif + #if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) + #define HAS_E2_ENABLE 1 + #endif + #if PIN_EXISTS(E2_DIR) + #define HAS_E2_DIR 1 + #endif + #if PIN_EXISTS(E2_STEP) + #define HAS_E2_STEP 1 + #endif + #if PIN_EXISTS(E2_MS1) + #define HAS_E2_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL2) + #define HAS_SOLENOID_2 1 + #endif -#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) - #define HAS_E4_ENABLE 1 -#endif -#if PIN_EXISTS(E4_DIR) - #define HAS_E4_DIR 1 -#endif -#if PIN_EXISTS(E4_STEP) - #define HAS_E4_STEP 1 -#endif -#if PIN_EXISTS(E4_MS1) - #define HAS_E4_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL4) - #define HAS_SOLENOID_4 1 -#endif + #if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) + #define HAS_E3_ENABLE 1 + #endif + #if PIN_EXISTS(E3_DIR) + #define HAS_E3_DIR 1 + #endif + #if PIN_EXISTS(E3_STEP) + #define HAS_E3_STEP 1 + #endif + #if PIN_EXISTS(E3_MS1) + #define HAS_E3_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL3) + #define HAS_SOLENOID_3 1 + #endif -#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) - #define HAS_E5_ENABLE 1 -#endif -#if PIN_EXISTS(E5_DIR) - #define HAS_E5_DIR 1 -#endif -#if PIN_EXISTS(E5_STEP) - #define HAS_E5_STEP 1 -#endif -#if PIN_EXISTS(E5_MS1) - #define HAS_E5_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL5) - #define HAS_SOLENOID_5 1 -#endif + #if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) + #define HAS_E4_ENABLE 1 + #endif + #if PIN_EXISTS(E4_DIR) + #define HAS_E4_DIR 1 + #endif + #if PIN_EXISTS(E4_STEP) + #define HAS_E4_STEP 1 + #endif + #if PIN_EXISTS(E4_MS1) + #define HAS_E4_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL4) + #define HAS_SOLENOID_4 1 + #endif -#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) - #define HAS_E6_ENABLE 1 -#endif -#if PIN_EXISTS(E6_DIR) - #define HAS_E6_DIR 1 -#endif -#if PIN_EXISTS(E6_STEP) - #define HAS_E6_STEP 1 -#endif -#if PIN_EXISTS(E6_MS1) - #define HAS_E6_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL6) - #define HAS_SOLENOID_6 1 -#endif + #if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) + #define HAS_E5_ENABLE 1 + #endif + #if PIN_EXISTS(E5_DIR) + #define HAS_E5_DIR 1 + #endif + #if PIN_EXISTS(E5_STEP) + #define HAS_E5_STEP 1 + #endif + #if PIN_EXISTS(E5_MS1) + #define HAS_E5_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL5) + #define HAS_SOLENOID_5 1 + #endif -#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) - #define HAS_E7_ENABLE 1 -#endif -#if PIN_EXISTS(E7_DIR) - #define HAS_E7_DIR 1 -#endif -#if PIN_EXISTS(E7_STEP) - #define HAS_E7_STEP 1 -#endif -#if PIN_EXISTS(E7_MS1) - #define HAS_E7_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL7) - #define HAS_SOLENOID_7 1 -#endif + #if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) + #define HAS_E6_ENABLE 1 + #endif + #if PIN_EXISTS(E6_DIR) + #define HAS_E6_DIR 1 + #endif + #if PIN_EXISTS(E6_STEP) + #define HAS_E6_STEP 1 + #endif + #if PIN_EXISTS(E6_MS1) + #define HAS_E6_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL6) + #define HAS_SOLENOID_6 1 + #endif + + #if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) + #define HAS_E7_ENABLE 1 + #endif + #if PIN_EXISTS(E7_DIR) + #define HAS_E7_DIR 1 + #endif + #if PIN_EXISTS(E7_STEP) + #define HAS_E7_STEP 1 + #endif + #if PIN_EXISTS(E7_MS1) + #define HAS_E7_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL7) + #define HAS_SOLENOID_7 1 + #endif + +#endif // HAS_EXTRUDERS // // Trinamic Stepper Drivers @@ -2348,7 +2352,10 @@ #if PIN_EXISTS(DIGIPOTSS) #define HAS_MOTOR_CURRENT_SPI 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) +#if HAS_EXTRUDERS && PIN_EXISTS(MOTOR_CURRENT_PWM_E) + #define HAS_MOTOR_CURRENT_PWM_E 1 +#endif +#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z) #define HAS_MOTOR_CURRENT_PWM 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 897cb2824f..eea6766148 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1593,11 +1593,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Homing */ constexpr float hbm[] = HOMING_BUMP_MM; -static_assert(COUNT(hbm) == XYZ, "HOMING_BUMP_MM requires X, Y, and Z elements."); -static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."); -static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."); -static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."); - +static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM requires one element per linear axis."); +LINEAR_AXIS_CODE( + static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."), + static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."), + static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0.") +); #if ENABLED(CODEPENDENT_XY_HOMING) #if ENABLED(QUICK_HOME) #error "QUICK_HOME is incompatible with CODEPENDENT_XY_HOMING." @@ -1976,12 +1977,16 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "HEATER_0_PIN not defined for this board." #elif !ANY_PIN(TEMP_0, MAX6675_SS) #error "TEMP_0_PIN or MAX6675_SS not defined for this board." -#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) - #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." -#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) - #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." -#elif EXTRUDERS && TEMP_SENSOR_0 == 0 - #error "TEMP_SENSOR_0 is required if there are any extruders." +#endif + +#if HAS_EXTRUDERS + #if ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) + #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." + #elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) + #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." + #elif EXTRUDERS && TEMP_SENSOR_0 == 0 + #error "TEMP_SENSOR_0 is required if there are any extruders." + #endif #endif /** diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 010d9a6680..f05958e675 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -856,8 +856,10 @@ void MarlinUI::draw_status_screen() { #else if (show_e_total) { - _draw_axis_value(E_AXIS, xstring, true); - lcd_put_u8str_P(PSTR(" ")); + #if ENABLED(LCD_SHOW_E_TOTAL) + _draw_axis_value(E_AXIS, xstring, true); + lcd_put_u8str_P(PSTR(" ")); + #endif } else { _draw_axis_value(X_AXIS, xstring, blink); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 3d68df7b7f..4f9021064d 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -666,10 +666,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), #if HOTENDS >= 1 - VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E0_AXIS], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), #endif #if HOTENDS >= 2 - VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E1_AXIS], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), #endif VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), @@ -677,10 +677,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #if HOTENDS >= 1 - VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E0_AXIS], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif #if HOTENDS >= 2 - VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E1_AXIS], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, ScreenHandler.HandleTravelAccChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index ba3abc0e2d..044a6642fc 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -712,13 +712,15 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Add a manual move to the queue? if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { - const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; #if IS_KINEMATIC #if HAS_MULTI_EXTRUDER REMEMBER(ae, active_extruder); - if (axis == E_AXIS) active_extruder = e_index; + #if MULTI_E_MANUAL + if (axis == E_AXIS) active_extruder = e_index; + #endif #endif // Apply a linear offset to a single axis @@ -744,7 +746,9 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #else // For Cartesian / Core motion simply move to the current_position - planner.buffer_line(current_position, fr_mm_s, axis == E_AXIS ? e_index : active_extruder); + planner.buffer_line(current_position, fr_mm_s, + TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder + ); //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index e751b53446..5c5ec9d3e1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -68,10 +68,7 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }) - EDIT_DAC_PERCENT(X); - EDIT_DAC_PERCENT(Y); - EDIT_DAC_PERCENT(Z); - EDIT_DAC_PERCENT(E); + LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(X), EDIT_DAC_PERCENT(Y), EDIT_DAC_PERCENT(Z), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K)); ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom); END_MENU(); } @@ -359,7 +356,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_FR_EDITING) DEFAULT_MAX_FEEDRATE #else - { 9999, 9999, 9999, 9999 } + LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999) #endif ; #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES) @@ -372,9 +369,7 @@ void menu_backlash(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_VMAX(N) EDIT_ITEM_FAST(float5, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)]) - EDIT_VMAX(A); - EDIT_VMAX(B); - EDIT_VMAX(C); + LINEAR_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K)); #if E_STEPPERS EDIT_ITEM_FAST(float5, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); @@ -404,7 +399,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_ACCEL_EDITING) DEFAULT_MAX_ACCELERATION #else - { 99000, 99000, 99000, 99000 } + LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000) #endif ; #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES) @@ -419,16 +414,19 @@ void menu_backlash(); // M204 P Acceleration EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); - // M204 R Retract Acceleration - EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #if HAS_EXTRUDERS + // M204 R Retract Acceleration + EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #endif // M204 T Travel Acceleration EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); }) - EDIT_AMAX(A, 100); - EDIT_AMAX(B, 100); - EDIT_AMAX(C, 10); + LINEAR_AXIS_CODE( + EDIT_AMAX(A, 100), EDIT_AMAX(B, 100), EDIT_AMAX(C, 10), + EDIT_AMAX(I, 10), EDIT_AMAX(J, 10), EDIT_AMAX(K, 10) + ); #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(); }); @@ -474,14 +472,14 @@ void menu_backlash(); #endif ; #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)]) - EDIT_JERK(A); - EDIT_JERK(B); #if ENABLED(DELTA) - EDIT_JERK(C); + #define EDIT_JERK_C() EDIT_JERK(C) #else - EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c); + #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c) #endif - #if HAS_CLASSIC_E_JERK + LINEAR_AXIS_CODE(EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C()); + + #if HAS_EXTRUDERS EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e); #endif @@ -517,9 +515,7 @@ void menu_advanced_steps_per_mm() { BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) - EDIT_QSTEPS(A); - EDIT_QSTEPS(B); - EDIT_QSTEPS(C); + LINEAR_AXIS_CODE(EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C)); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index dff0b6832a..cf152ff028 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -361,7 +361,8 @@ void Endstops::event_handler() { prev_hit_state = hit_state; if (hit_state) { #if HAS_STATUS_MESSAGE - char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; + char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' '), + chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else #define _SET_STOP_CHAR(A,C) NOOP @@ -390,7 +391,13 @@ void Endstops::event_handler() { #endif SERIAL_EOL(); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); + TERN_(HAS_STATUS_MESSAGE, + ui.status_printf_P(0, + PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), + GET_TEXT(MSG_LCD_ENDSTOPS), + LINEAR_AXIS_LIST(chrX, chrY, chrZ), chrP + ) + ); #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 6801b210af..ad0537b5cf 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -89,7 +89,7 @@ bool relative_mode; // = false; #define Z_INIT_POS Z_HOME_POS #endif -xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_INIT_POS }; +xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS); /** * Cartesian Destination @@ -195,16 +195,25 @@ inline void report_more_positions() { // 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); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z) + #if HAS_EXTRUDERS + , SP_E_LBL, lpos.e + #endif + ); } // 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); + xyze_pos_t npos = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z + ); + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); + report_logical_position(npos); report_more_positions(); } @@ -309,7 +318,9 @@ void sync_plan_position() { planner.set_position_mm(current_position); } -void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#if HAS_EXTRUDERS + void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#endif /** * Get the stepper positions in the cartes[] array. @@ -354,7 +365,10 @@ 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_EXTRUDERS + pos.e = planner.get_axis_position_mm(E_AXIS); + #endif #if HAS_POSITION_MODIFIERS planner.unapply_modifiers(pos, true); @@ -442,9 +456,12 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ * - Delta may lower Z first to get into the free motion zone. * - Before returning, wait for the planner buffer to empty. */ -void do_blocking_move_to(const float rx, const float ry, const float rz, const_feedRate_t fr_mm_s/*=0.0*/) { +void do_blocking_move_to( + LINEAR_AXIS_LIST(const float rx, const float ry, const float rz), + const_feedRate_t fr_mm_s/*=0.0f*/ +) { DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", rx, ry, rz); + if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_LIST(rx, ry, rz)); const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS), xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); @@ -529,34 +546,46 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const_f } void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, current_position.z, fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i), fr_mm_s); } void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s); } void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s); } void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, current_position.y, current_position.z, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, current_position.y, current_position.z), + fr_mm_s + ); } void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position.x, ry, current_position.z, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(current_position.x, ry, current_position.z), + fr_mm_s + ); } void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); } void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, ry, current_position.z, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, ry, current_position.z), + fr_mm_s + ); } void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); } void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, z, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, z), + fr_mm_s + ); } void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { @@ -589,8 +618,8 @@ void restore_feedrate_and_scaling() { // Software Endstops are based on the configured limits. soft_endstops_t soft_endstop = { true, false, - { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, - { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } + LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS), + LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS) }; /** @@ -1176,9 +1205,12 @@ void prepare_line_to_destination() { if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) CBI(b, a); }; - set_should(axis_bits, X_AXIS); // Clear test bits that are trusted - set_should(axis_bits, Y_AXIS); - set_should(axis_bits, Z_AXIS); + // Clear test bits that are trusted + LINEAR_AXIS_CODE( + set_should(axis_bits, X_AXIS), + set_should(axis_bits, Y_AXIS), + set_should(axis_bits, Z_AXIS) + ); return axis_bits; } @@ -1187,9 +1219,11 @@ void prepare_line_to_destination() { PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[strlen_P(home_first)+1]; sprintf_P(msg, home_first, - TEST(axis_bits, X_AXIS) ? "X" : "", - TEST(axis_bits, Y_AXIS) ? "Y" : "", - TEST(axis_bits, Z_AXIS) ? "Z" : "" + LINEAR_AXIS_LIST( + TEST(axis_bits, X_AXIS) ? "X" : "", + TEST(axis_bits, Y_AXIS) ? "Y" : "", + TEST(axis_bits, Z_AXIS) ? "Z" : "" + ) ); SERIAL_ECHO_START(); SERIAL_ECHOLN(msg); @@ -1356,7 +1390,7 @@ void prepare_line_to_destination() { const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("...(", AS_CHAR(axis_codes[axis]), ", ", distance, ", "); + DEBUG_ECHOPAIR("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else @@ -1441,12 +1475,12 @@ void prepare_line_to_destination() { * "trusted" position). */ void set_axis_never_homed(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_untrusted(axis); set_axis_unhomed(axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); } @@ -1507,7 +1541,7 @@ void prepare_line_to_destination() { if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) SERIAL_ECHOLNPAIR("Selected home phase ", home_phase[axis], " too close to endstop trigger phase ", phaseCurrent, - ". Pick a different phase for ", AS_CHAR(axis_codes[axis])); + ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); // Skip to next if target position is behind current. So it only moves away from endstop. if (phaseDelta < 0) phaseDelta += 1024; @@ -1518,7 +1552,7 @@ void prepare_line_to_destination() { // Optional debug messages if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR( - "Endstop ", AS_CHAR(axis_codes[axis]), " hit at Phase:", phaseCurrent, + "Endstop ", AS_CHAR(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, " Delta:", phaseDelta, " Distance:", mmDelta ); } @@ -1556,7 +1590,7 @@ void prepare_line_to_destination() { if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); @@ -1634,7 +1668,7 @@ void prepare_line_to_destination() { case Z_AXIS: es = Z_ENDSTOP; break; } if (TEST(endstops.state(), es)) { - SERIAL_ECHO_MSG("Bad ", AS_CHAR(axis_codes[axis]), " Endstop?"); + SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); } #endif @@ -1856,7 +1890,7 @@ void prepare_line_to_destination() { if (axis == Z_AXIS) fwretract.current_hop = 0.0; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); } // homeaxis() @@ -1881,7 +1915,7 @@ void prepare_line_to_destination() { * Callers must sync the planner position after calling this! */ void set_axis_is_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_trusted(axis); set_axis_homed(axis); @@ -1931,10 +1965,10 @@ void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { #if HAS_HOME_OFFSET - DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(axis_codes[axis]), "] = ", home_offset[axis]); + DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); #endif DEBUG_POS("", current_position); - DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(axis_codes[axis]), ")"); + DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); } } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 67205a7636..0706b721b3 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -124,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P DEFS_PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ + static const XYZval NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); @@ -264,7 +264,10 @@ void quickstop_stepper(); * no kinematic translation. Used for homing axes and cartesian/core syncing. */ void sync_plan_position(); -void sync_plan_position_e(); + +#if HAS_EXTRUDERS + void sync_plan_position_e(); +#endif /** * Move the planner to the current position from wherever it last moved @@ -295,7 +298,10 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) /** * Blocking movement and shorthand functions */ -void do_blocking_move_to(const float rx, const float ry, const float rz, const_feedRate_t fr_mm_s=0.0f); +void do_blocking_move_to( + LINEAR_AXIS_LIST(const float rx, const float ry, const float rz), + const_feedRate_t fr_mm_s=0.0f +); void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); @@ -322,7 +328,7 @@ void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); /** * Homing and Trusted Axes */ -typedef IF<(LINEAR_AXES>8), uint16_t, uint8_t>::type linear_axis_bits_t; +typedef IF<(LINEAR_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t; constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1; void set_axis_is_at_home(const AxisEnum axis); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 09db12cd7a..c06e4be79b 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1345,10 +1345,12 @@ void Planner::check_axes_activity() { #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; - if (ENABLED(DISABLE_X) && block->steps.x) axis_active.x = true; - if (ENABLED(DISABLE_Y) && block->steps.y) axis_active.y = true; - if (ENABLED(DISABLE_Z) && block->steps.z) axis_active.z = true; - if (ENABLED(DISABLE_E) && block->steps.e) axis_active.e = true; + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true, + if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true, + if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true, + if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true + ); } #endif } @@ -1369,10 +1371,12 @@ void Planner::check_axes_activity() { // // Disable inactive axes // - if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(); - if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(); - if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(); - if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(), + if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(), + if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(), + if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z() + ); // // Update Fan speeds @@ -1823,16 +1827,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { - - const int32_t da = target.a - position.a, - db = target.b - position.b, - dc = target.c - position.c; - - #if HAS_EXTRUDERS - int32_t de = target.e - position.e; - #else - constexpr int32_t de = 0; - #endif + int32_t LOGICAL_AXIS_LIST( + de = target.e - position.e, + da = target.a - position.a, + db = target.b - position.b, + dc = target.c - position.c + ); /* <-- add a slash to enable SERIAL_ECHOLNPAIR( @@ -1883,35 +1883,39 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute direction bit-mask for this block uint8_t dm = 0; #if CORE_IS_XY - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction #elif CORE_IS_XZ - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_AXIS); if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif CORE_IS_YZ if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_HEAD); // Save the real Extruder (head) direction in Y Axis + if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif ENABLED(MARKFORGED_XY) - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (db < 0) SBI(dm, B_AXIS); // Motor B direction #else - if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_AXIS); - if (dc < 0) SBI(dm, Z_AXIS); + LINEAR_AXIS_CODE( + if (da < 0) SBI(dm, X_AXIS), + if (db < 0) SBI(dm, Y_AXIS), + if (dc < 0) SBI(dm, Z_AXIS) + ); + #endif + #if HAS_EXTRUDERS + if (de < 0) SBI(dm, E_AXIS); #endif - if (de < 0) SBI(dm, E_AXIS); #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; @@ -1947,7 +1951,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(ABS(da), ABS(db), ABS(dc)); #else // default non-h-bot planning - block->steps.set(ABS(da), ABS(db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc))); #endif /** @@ -1990,41 +1994,51 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.a = (da - db) * steps_to_mm[A_AXIS]; steps_dist_mm.b = db * steps_to_mm[B_AXIS]; #else - steps_dist_mm.a = da * steps_to_mm[A_AXIS]; - steps_dist_mm.b = db * steps_to_mm[B_AXIS]; - steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; + LINEAR_AXIS_CODE( + steps_dist_mm.a = da * steps_to_mm[A_AXIS], + steps_dist_mm.b = db * steps_to_mm[B_AXIS], + steps_dist_mm.c = dc * steps_to_mm[C_AXIS] + ); #endif #if HAS_EXTRUDERS steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; - #else - steps_dist_mm.e = 0.0f; #endif TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); - if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { - block->millimeters = (0 - #if HAS_EXTRUDERS - + ABS(steps_dist_mm.e) - #endif - ); + if (true LINEAR_AXIS_GANG( + && block->steps.a < MIN_STEPS_PER_SEGMENT, + && block->steps.b < MIN_STEPS_PER_SEGMENT, + && block->steps.c < MIN_STEPS_PER_SEGMENT + ) + ) { + block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); } else { if (millimeters) block->millimeters = millimeters; - else + else { block->millimeters = SQRT( #if EITHER(CORE_IS_XY, MARKFORGED_XY) - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z) + ) #elif CORE_IS_XZ - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z) + ) #elif CORE_IS_YZ - sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.head.z) + ) #else - sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z) + ) #endif ); + } /** * At this point at least one of the axes has more steps than @@ -2038,11 +2052,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } - #if HAS_EXTRUDERS - block->steps.e = esteps; - #endif + TERN_(HAS_EXTRUDERS, block->steps.e = esteps); - block->step_event_count = _MAX(block->steps.a, block->steps.b, block->steps.c, esteps); + block->step_event_count = _MAX(LOGICAL_AXIS_LIST( + esteps, block->steps.a, block->steps.b, block->steps.c + )); // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; @@ -2065,8 +2079,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif #if ENABLED(AUTO_POWER_CONTROL) - if (block->steps.x || block->steps.y || block->steps.z) - powerManager.power_on(); + if (LINEAR_AXIS_GANG( + block->steps.x, + || block->steps.y, + || block->steps.z + )) powerManager.power_on(); #endif // Enable active axes @@ -2091,11 +2108,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } if (block->steps.x) ENABLE_AXIS_X(); #else - if (block->steps.x) ENABLE_AXIS_X(); - if (block->steps.y) ENABLE_AXIS_Y(); - #if DISABLED(Z_LATE_ENABLE) - if (block->steps.z) ENABLE_AXIS_Z(); - #endif + LINEAR_AXIS_CODE( + if (block->steps.x) ENABLE_AXIS_X(), + if (block->steps.y) ENABLE_AXIS_Y(), + if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z() + ); #endif // Enable extruder(s) @@ -2281,7 +2298,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute and limit the acceleration rate for the trapezoid generator. const float steps_per_mm = block->step_event_count * inverse_millimeters; uint32_t accel; - if (!block->steps.a && !block->steps.b && !block->steps.c) { // Is this a retract / recover move? + if (LINEAR_AXIS_GANG( + !block->steps.a, && !block->steps.b, && !block->steps.c + )) { // Is this a retract / recover move? accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2 TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover } @@ -2346,16 +2365,20 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Limit acceleration per axis if (block->step_event_count <= acceleration_long_cutoff) { - LIMIT_ACCEL_LONG(A_AXIS, 0); - LIMIT_ACCEL_LONG(B_AXIS, 0); - LIMIT_ACCEL_LONG(C_AXIS, 0); - LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)); + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_LONG(A_AXIS, 0), + LIMIT_ACCEL_LONG(B_AXIS, 0), + LIMIT_ACCEL_LONG(C_AXIS, 0) + ); } else { - LIMIT_ACCEL_FLOAT(A_AXIS, 0); - LIMIT_ACCEL_FLOAT(B_AXIS, 0); - LIMIT_ACCEL_FLOAT(C_AXIS, 0); - LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)); + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_FLOAT(A_AXIS, 0), + LIMIT_ACCEL_FLOAT(B_AXIS, 0), + LIMIT_ACCEL_FLOAT(C_AXIS, 0) + ); } } block->acceleration_steps_per_s2 = accel; @@ -2419,7 +2442,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_DIST_MM_ARG cart_dist_mm #else - { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } + LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z) #endif ; @@ -2438,8 +2461,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. - float junction_cos_theta = (-prev_unit_vec.x * unit_vec.x) + (-prev_unit_vec.y * unit_vec.y) - + (-prev_unit_vec.z * unit_vec.z) + (-prev_unit_vec.e * unit_vec.e); + float junction_cos_theta = LOGICAL_AXIS_GANG( + + (-prev_unit_vec.e * unit_vec.e), + (-prev_unit_vec.x * unit_vec.x), + + (-prev_unit_vec.y * unit_vec.y), + + (-prev_unit_vec.z * unit_vec.z) + ); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). if (junction_cos_theta > 0.999999f) { @@ -2754,7 +2781,8 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ * * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc. */ -bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e +bool Planner::buffer_segment( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { @@ -2773,21 +2801,25 @@ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, // The target position of the tool in absolute steps // Calculate target position in absolute steps const abce_long_t target = { - int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])), - int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])), - int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS])), - int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])) + LOGICAL_AXIS_LIST( + int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])), + int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])), + int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])), + int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS])) + ) }; #if HAS_POSITION_FLOAT - const xyze_pos_t target_float = { a, b, c, e }; + const xyze_pos_t target_float = LOGICAL_AXIS_ARRAY(e, a, b, c); #endif - // DRYRUN prevents E moves from taking place - if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { - position.e = target.e; - TERN_(HAS_POSITION_FLOAT, position_float.e = e); - } + #if HAS_EXTRUDERS + // DRYRUN prevents E moves from taking place + if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { + position.e = target.e; + TERN_(HAS_POSITION_FLOAT, position_float.e = e); + } + #endif /* <-- add a slash to enable SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); @@ -2846,10 +2878,12 @@ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, * millimeters - the length of the movement, if known * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ -bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters +bool Planner::buffer_line( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) + , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration) ) { - xyze_pos_t machine = { rx, ry, rz, e }; + xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz); TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); #if IS_KINEMATIC @@ -2912,16 +2946,12 @@ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif - #if HAS_MULTI_EXTRUDER - block->extruder = extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); block->page_idx = page_idx; block->step_event_count = num_steps; - block->initial_rate = - block->final_rate = - block->nominal_rate = last_page_step_rate; // steps/s + block->initial_rate = block->final_rate = block->nominal_rate = last_page_step_rate; // steps/s block->accelerate_until = 0; block->decelerate_after = block->step_event_count; @@ -2965,13 +2995,19 @@ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, * The provided ABC position is in machine units. */ -void Planner::set_machine_position_mm(const_float_t a, const_float_t b, const_float_t c, const_float_t e) { +void Planner::set_machine_position_mm( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) +) { TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - TERN_(HAS_POSITION_FLOAT, position_float.set(a, b, c, e)); - position.set(LROUND(a * settings.axis_steps_per_mm[A_AXIS]), - LROUND(b * settings.axis_steps_per_mm[B_AXIS]), - LROUND(c * settings.axis_steps_per_mm[C_AXIS]), - LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)])); + TERN_(HAS_POSITION_FLOAT, position_float.set(LOGICAL_AXIS_LIST(e, a, b, c))); + position.set( + LOGICAL_AXIS_LIST( + LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]), + LROUND(a * settings.axis_steps_per_mm[A_AXIS]), + LROUND(b * settings.axis_steps_per_mm[B_AXIS]), + LROUND(c * settings.axis_steps_per_mm[C_AXIS]) + ) + ); if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); @@ -2981,11 +3017,11 @@ void Planner::set_machine_position_mm(const_float_t a, const_float_t b, const_fl stepper.set_position(position); } -void Planner::set_position_mm(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e) { - xyze_pos_t machine = { rx, ry, rz, e }; - #if HAS_POSITION_MODIFIERS - apply_modifiers(machine, true); - #endif +void Planner::set_position_mm( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) +) { + xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz); + TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true)); #if IS_KINEMATIC position_cart.set(rx, ry, rz, e); inverse_kinematics(machine); @@ -2995,23 +3031,27 @@ void Planner::set_position_mm(const_float_t rx, const_float_t ry, const_float_t #endif } -/** - * Setters for planner position (also setting stepper position). - */ -void Planner::set_e_position_mm(const_float_t e) { - const uint8_t axis_index = E_AXIS_N(active_extruder); - TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); +#if HAS_EXTRUDERS - const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); - position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); - TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); - TERN_(IS_KINEMATIC, position_cart.e = e); + /** + * Setters for planner position (also setting stepper position). + */ + void Planner::set_e_position_mm(const_float_t e) { + const uint8_t axis_index = E_AXIS_N(active_extruder); + TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - if (has_blocks_queued()) - buffer_sync_block(); - else - stepper.set_axis_position(E_AXIS, position.e); -} + const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); + position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); + TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); + TERN_(IS_KINEMATIC, position_cart.e = e); + + if (has_blocks_queued()) + buffer_sync_block(); + else + stepper.set_axis_position(E_AXIS, position.e); + } + +#endif // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 void Planner::reset_acceleration_rates() { @@ -3041,11 +3081,11 @@ void Planner::refresh_positioning() { // Apply limits to a variable and give a warning if the value was out of range inline void limit_and_warn(float &val, const uint8_t axis, PGM_P const setting_name, const xyze_float_t &max_limit) { - const uint8_t lim_axis = axis > E_AXIS ? E_AXIS : axis; + const uint8_t lim_axis = TERN_(HAS_EXTRUDERS, axis > E_AXIS ? E_AXIS :) axis; const float before = val; LIMIT(val, 0.1, max_limit[lim_axis]); if (before != val) { - SERIAL_CHAR(axis_codes[lim_axis]); + SERIAL_CHAR(AXIS_CHAR(lim_axis)); SERIAL_ECHOPGM(" Max "); SERIAL_ECHOPGM_P(setting_name); SERIAL_ECHOLNPAIR(" limited to ", val); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index be004dd3f4..edeac9b7f9 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -76,7 +76,7 @@ // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, - manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; + manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f); #endif #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION @@ -758,7 +758,8 @@ class Planner { * extruder - target extruder * millimeters - the length of the movement, if known */ - static bool buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e + static bool buffer_segment( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); @@ -767,9 +768,11 @@ class Planner { OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ) { - return buffer_segment(abce.a, abce.b, abce.c, abce.e + return buffer_segment( + LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c) OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) - , fr_mm_s, extruder, millimeters); + , fr_mm_s, extruder, millimeters + ); } public: @@ -785,14 +788,18 @@ class Planner { * millimeters - the length of the movement, if known * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ - static bool buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 + static bool buffer_line( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) + , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ); FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ) { - return buffer_line(cart.x, cart.y, cart.z, cart.e, fr_mm_s, extruder, millimeters + return buffer_line( + LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z) + , fr_mm_s, extruder, millimeters OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); } @@ -814,9 +821,16 @@ class Planner { * * Clears previous speed values. */ - static void set_position_mm(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e); - FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) { set_position_mm(cart.x, cart.y, cart.z, cart.e); } - static void set_e_position_mm(const_float_t e); + static void set_position_mm( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) + ); + FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) { + set_position_mm(LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z, cart.i, cart.j, cart.k)); + } + + #if HAS_EXTRUDERS + static void set_e_position_mm(const_float_t e); + #endif /** * Set the planner.position and individual stepper positions. @@ -824,8 +838,12 @@ class Planner { * The supplied position is in machine space, and no additional * conversions are applied. */ - static void set_machine_position_mm(const_float_t a, const_float_t b, const_float_t c, const_float_t e); - FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) { set_machine_position_mm(abce.a, abce.b, abce.c, abce.e); } + static void set_machine_position_mm( + LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) + ); + FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) { + set_machine_position_mm(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)); + } /** * Get an axis position according to stepper position(s) @@ -834,12 +852,10 @@ 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) - }; + const abce_pos_t out = LOGICAL_AXIS_ARRAY( + get_axis_position_mm(E_AXIS), + get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS) + ); return out; } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index eae4728793..fc4fdc1f92 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -168,10 +168,10 @@ void M554_report(); #endif -typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; -typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; -typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; +typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; +typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; +typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; +typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) @@ -654,7 +654,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummyf); #endif #else - const xyze_pos_t planner_max_jerk = { 10, 10, 0.4, float(DEFAULT_EJERK) }; + const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4); EEPROM_WRITE(planner_max_jerk); #endif @@ -1188,10 +1188,10 @@ void MarlinSettings::postprocess() { #endif #else const tmc_hybrid_threshold_t tmc_hybrid_threshold = { - .X = 100, .Y = 100, .Z = 3, + LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3), .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3, - .E0 = 30, .E1 = 30, .E2 = 30, - .E3 = 30, .E4 = 30, .E5 = 30 + .E0 = 30, .E1 = 30, .E2 = 30, .E3 = 30, + .E4 = 30, .E5 = 30, .E6 = 30, .E7 = 30 }; #endif EEPROM_WRITE(tmc_hybrid_threshold); @@ -2604,7 +2604,7 @@ void MarlinSettings::reset() { #ifndef DEFAULT_ZJERK #define DEFAULT_ZJERK 0 #endif - planner.max_jerk.set(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK); + planner.max_jerk.set(LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK)); TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); #endif @@ -3142,10 +3142,12 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum feedrates (units/s):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]) - , SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]) - , SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) #endif ); @@ -3162,10 +3164,12 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum Acceleration (units/s2):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]) - , SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]) - , SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) #endif ); @@ -3894,9 +3898,11 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M425 F"), backlash.get_correction() - , SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x) - , SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y) - , SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), + SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), + SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z) + ) #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 2e2afaeb90..bc6dbeaf25 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -498,7 +498,7 @@ void Stepper::set_directions() { MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); count_direction.e = 1; } - #else + #elif HAS_EXTRUDERS if (motor_direction(E_AXIS)) { REV_E_DIR(stepper_extruder); count_direction.e = -1; @@ -1627,7 +1627,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -1660,7 +1660,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -2103,13 +2103,15 @@ uint32_t Stepper::block_phase_isr() { #endif uint8_t axis_bits = 0; - if (X_MOVE_TEST) SBI(axis_bits, A_AXIS); - if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS); - if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS); - //if (!!current_block->steps.e) SBI(axis_bits, E_AXIS); - //if (!!current_block->steps.a) SBI(axis_bits, X_HEAD); - //if (!!current_block->steps.b) SBI(axis_bits, Y_HEAD); - //if (!!current_block->steps.c) SBI(axis_bits, Z_HEAD); + LINEAR_AXIS_CODE( + if (X_MOVE_TEST) SBI(axis_bits, A_AXIS), + if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS), + if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS) + ); + //if (current_block->steps.e) SBI(axis_bits, E_AXIS); + //if (current_block->steps.a) SBI(axis_bits, X_HEAD); + //if (current_block->steps.b) SBI(axis_bits, Y_HEAD); + //if (current_block->steps.c) SBI(axis_bits, Z_HEAD); axis_did_move = axis_bits; // No acceleration / deceleration time elapsed so far @@ -2606,9 +2608,13 @@ void Stepper::init() { #endif // Init direction bits for first moves - set_directions((INVERT_X_DIR ? _BV(X_AXIS) : 0) - | (INVERT_Y_DIR ? _BV(Y_AXIS) : 0) - | (INVERT_Z_DIR ? _BV(Z_AXIS) : 0)); + set_directions(0 + LINEAR_AXIS_GANG( + | TERN0(INVERT_X_DIR, _BV(X_AXIS)), + | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)), + | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)) + ) + ); #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM initialized = true; @@ -2625,7 +2631,9 @@ void Stepper::init() { * This allows get_axis_position_mm to correctly * derive the current XYZ position later on. */ -void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { +void Stepper::_set_position( + LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) +) { #if CORE_IS_XY // corexy positioning // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html @@ -2640,9 +2648,9 @@ void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c count_position.set(a - b, b, c); #else // default non-h-bot planning - count_position.set(a, b, c); + count_position.set(LINEAR_AXIS_LIST(a, b, c)); #endif - count_position.e = e; + TERN_(HAS_EXTRUDERS, count_position.e = e); } /** @@ -2665,10 +2673,13 @@ int32_t Stepper::position(const AxisEnum axis) { } // Set the current position in steps -void Stepper::set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { +//TODO: Test for LINEAR_AXES >= 4 +void Stepper::set_position( + LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) +) { planner.synchronize(); const bool was_enabled = suspend(); - _set_position(a, b, c, e); + _set_position(LOGICAL_AXIS_LIST(e, a, b, c)); if (was_enabled) wake_up(); } @@ -2743,10 +2754,11 @@ void Stepper::report_a_position(const xyz_long_t &pos) { SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y); #endif #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) - SERIAL_ECHOLNPAIR(" C:", pos.z); - #else - SERIAL_ECHOLNPAIR_P(SP_Z_LBL, pos.z); + SERIAL_ECHOPAIR(" C:", pos.z); + #elif LINEAR_AXES >= 3 + SERIAL_ECHOPAIR_P(SP_Z_LBL, pos.z); #endif + SERIAL_EOL(); } void Stepper::report_positions() { @@ -2903,7 +2915,7 @@ void Stepper::report_positions() { DIR_WAIT_BEFORE(); - const xyz_byte_t old_dir = { X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ() }; + const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ()); X_DIR_WRITE(INVERT_X_DIR ^ z_direction); Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 020f72e9e6..67ca6fa433 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -433,8 +433,12 @@ class Stepper { static int32_t position(const AxisEnum axis); // Set the current position in steps - static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e); - static inline void set_position(const xyze_long_t &abce) { set_position(abce.a, abce.b, abce.c, abce.e); } + static void set_position( + LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) + ); + static inline void set_position(const xyze_long_t &abce) { + set_position(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)); + } static void set_axis_position(const AxisEnum a, const int32_t &v); // Report the positions of the steppers, in steps @@ -530,8 +534,12 @@ class Stepper { private: // Set the current position in steps - static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e); - FORCE_INLINE static void _set_position(const abce_long_t &spos) { _set_position(spos.a, spos.b, spos.c, spos.e); } + static void _set_position( + LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) + ); + FORCE_INLINE static void _set_position(const abce_long_t &spos) { + _set_position(LOGICAL_AXIS_LIST(spos.e, spos.a, spos.b, spos.c)); + } FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) { uint32_t timer; diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 8c943048ba..5acc860787 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -35,7 +35,9 @@ #include #include -enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; +enum StealthIndex : uint8_t { + LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z) +}; #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) // IC = TMC model number @@ -351,7 +353,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #endif - enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; void tmc_serial_begin() { #if HAS_TMC_HW_SERIAL @@ -716,19 +718,24 @@ void restore_trinamic_drivers() { } void reset_trinamic_drivers() { - static constexpr bool stealthchop_by_axis[] = { ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), ENABLED(STEALTHCHOP_E) }; + static constexpr bool stealthchop_by_axis[] = LOGICAL_AXIS_ARRAY( + ENABLED(STEALTHCHOP_E), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_Z) + ); #if AXIS_IS_TMC(X) - TMC_INIT(X, STEALTH_AXIS_XY); + TMC_INIT(X, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(X2) - TMC_INIT(X2, STEALTH_AXIS_XY); + TMC_INIT(X2, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(Y) - TMC_INIT(Y, STEALTH_AXIS_XY); + TMC_INIT(Y, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Y2) - TMC_INIT(Y2, STEALTH_AXIS_XY); + TMC_INIT(Y2, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Z) TMC_INIT(Z, STEALTH_AXIS_Z); @@ -792,7 +799,7 @@ void reset_trinamic_drivers() { stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY)); #endif #endif - #endif + #endif // USE SENSORLESS #ifdef TMC_ADV TMC_ADV() diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index a3711ca076..ecf82267f4 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -171,10 +171,12 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # Test Laser features with 12864 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ - DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 @@ -184,10 +186,12 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air As # Test Laser features with 44780 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 \ +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ - DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 9869b96b34..953e7e8efc 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -48,6 +48,7 @@ opt_set MOTHERBOARD BOARD_RAMBO \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' \ LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ @@ -66,6 +67,7 @@ opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "Rambo heated bed only" "$3" From 2dd25938ccba501a9bb74b55dfd0ce7ff4f508cc Mon Sep 17 00:00:00 2001 From: LawnMo <81721212+LawnMo@users.noreply.github.com> Date: Tue, 25 May 2021 00:53:48 +0200 Subject: [PATCH 0170/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20multi=5Fvolume?= =?UTF-8?q?=20+=20SDIO=20onboard=20compile=20(#21975)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 405da103de..3890b08147 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -144,7 +144,7 @@ uint32_t CardReader::filesize, CardReader::sdpos; CardReader::CardReader() { changeMedia(& #if SHARED_VOLUME_IS(SD_ONBOARD) - media_sd_spi + TERN(SDIO_SUPPORT, media_sdio, media_sd_spi) #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) media_usbFlashDrive #else From d051495dec8bbbe07ebcd95eb2e5b9e6d08d1fec Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 25 May 2021 01:09:52 +0000 Subject: [PATCH 0171/2168] [cron] Bump distribution date (2021-05-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3690ea2c92..2c57bad370 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 "2021-05-24" + #define STRING_DISTRIBUTION_DATE "2021-05-25" #endif /** From e60c38b6220678b3b9f3a3b31516852f8d25b3b0 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 26 May 2021 11:38:23 +1200 Subject: [PATCH 0172/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20LEDs=20refactor?= =?UTF-8?q?=20and=20extend=20(#21962)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 11 +-- Marlin/src/feature/caselight.cpp | 4 +- Marlin/src/feature/leds/leds.cpp | 49 ++++++------ Marlin/src/feature/leds/leds.h | 31 ++++--- Marlin/src/feature/leds/neopixel.cpp | 80 +++++++++---------- Marlin/src/feature/leds/neopixel.h | 73 +++++++++-------- .../src/feature/leds/printer_event_leds.cpp | 8 +- Marlin/src/gcode/feature/leds/M150.cpp | 8 +- Marlin/src/inc/Conditionals_LCD.h | 7 ++ Marlin/src/inc/SanityCheck.h | 2 + Marlin/src/lcd/marlinui.cpp | 4 +- Marlin/src/lcd/menu/menu_led.cpp | 12 +-- buildroot/tests/DUE | 2 +- buildroot/tests/LPC1768 | 6 +- buildroot/tests/rambo | 2 +- 15 files changed, 157 insertions(+), 142 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index dd6abd5629..366267aa7e 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2690,7 +2690,7 @@ //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) - #define NEOPIXEL_PIN 4 // LED driving pin + //#define NEOPIXEL_PIN 4 // LED driving pin //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE //#define NEOPIXEL2_PIN 5 #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) @@ -2708,10 +2708,11 @@ //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif - // Use a single NeoPixel LED for static (background) lighting - //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W - //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off + // Use some of the NeoPixel LEDs for static (background) lighting + //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED + //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off #endif /** diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index ec4ad99c75..1baef6d468 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -65,9 +65,7 @@ void CaseLight::update(const bool sflag) { #endif #if CASE_LIGHT_IS_COLOR_LED - - leds.set_color(MakeLEDColor(color.r, color.g, color.b, color.w, n10ct)); - + leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w), n10ct)); #else // !CASE_LIGHT_IS_COLOR_LED #if CASELIGHT_USES_BRIGHTNESS diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index c9178effa8..328daa626d 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -47,9 +47,10 @@ #endif #if ENABLED(LED_COLOR_PRESETS) - const LEDColor LEDLights::defaultLEDColor = MakeLEDColor( - LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, - LED_USER_PRESET_WHITE, LED_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif @@ -75,34 +76,35 @@ void LEDLights::setup() { } void LEDLights::set_color(const LEDColor &incol - OPTARG(NEOPIXEL_LED, bool isSequence/*=false*/) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence/*=false*/) ) { #if ENABLED(NEOPIXEL_LED) const uint32_t neocolor = LEDColorWhite() == incol ? neo.Color(NEO_WHITE) - : neo.Color(incol.r, incol.g, incol.b, incol.w); - static uint16_t nextLed = 0; + : neo.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED, incol.w)); - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (NEOPIXEL_BKGD_LED_INDEX == nextLed) { - neo.set_color_background(); - if (++nextLed >= neo.pixels()) { - nextLed = 0; - return; + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + static uint16_t nextLed = 0; + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + while (WITHIN(nextLed, NEOPIXEL_BKGD_INDEX_FIRST, NEOPIXEL_BKGD_INDEX_LAST)) { + neo.reset_background_color(); + if (++nextLed >= neo.pixels()) { nextLed = 0; return; } } - } + #endif #endif neo.set_brightness(incol.i); - if (isSequence) { - neo.set_pixel_color(nextLed, neocolor); - neo.show(); - if (++nextLed >= neo.pixels()) nextLed = 0; - return; - } + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + if (isSequence) { + neo.set_pixel_color(nextLed, neocolor); + neo.show(); + if (++nextLed >= neo.pixels()) nextLed = 0; + return; + } + #endif neo.set_color(neocolor); @@ -167,9 +169,10 @@ void LEDLights::set_color(const LEDColor &incol #if ENABLED(NEOPIXEL2_SEPARATE) #if ENABLED(NEO2_COLOR_PRESETS) - const LEDColor LEDLights2::defaultLEDColor = MakeLEDColor( - NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, - NEO2_USER_PRESET_WHITE, NEO2_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights2::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED2, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif @@ -188,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol void LEDLights2::set_color(const LEDColor &incol) { const uint32_t neocolor = LEDColorWhite() == incol ? neo2.Color(NEO2_WHITE) - : neo2.Color(incol.r, incol.g, incol.b, incol.w); + : neo2.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED2, incol.w)); neo2.set_brightness(incol.i); neo2.set_color(neocolor); diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index 4157ff816e..74964b51a8 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -29,13 +29,15 @@ #include -#if ENABLED(NEOPIXEL_LED) - #include "neopixel.h" +// A white component can be passed +#if EITHER(RGBW_LED, PCA9632_RGBW) + #define HAS_WHITE_LED 1 #endif -// A white component can be passed -#if ANY(RGBW_LED, NEOPIXEL_LED, PCA9632_RGBW) - #define HAS_WHITE_LED 1 +#if ENABLED(NEOPIXEL_LED) + #define _NEOPIXEL_INCLUDE_ + #include "neopixel.h" + #undef _NEOPIXEL_INCLUDE_ #endif /** @@ -84,9 +86,8 @@ typedef struct LEDColor { } LEDColor; /** - * Color helpers and presets + * Color presets */ -#define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B OPTARG(HAS_WHITE_LED, W) OPTARG(NEOPIXEL_LED, I)) #define LEDColorOff() LEDColor( 0, 0, 0) #define LEDColorRed() LEDColor(255, 0, 0) @@ -114,15 +115,15 @@ public: static void setup(); // init() static void set_color(const LEDColor &color - OPTARG(NEOPIXEL_LED, bool isSequence=false) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ); static inline void set_color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) - OPTARG(NEOPIXEL_LED, bool isSequence=false) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ) { - set_color(MakeLEDColor(r, g, b, w, i) OPTARG(NEOPIXEL_LED, isSequence)); + set_color(LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); } static inline void set_off() { set_color(LEDColorOff()); } @@ -180,8 +181,14 @@ extern LEDLights leds; static void set_color(const LEDColor &color); - inline void set_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w=0, uint8_t i=NEOPIXEL2_BRIGHTNESS) { - set_color(MakeLEDColor(r, g, b, w, i)); + static inline void set_color(uint8_t r, uint8_t g, uint8_t b + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + ) { + set_color(LEDColor(r, g, b + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) + )); } static inline void set_off() { set_color(LEDColorOff()); } diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index bdd22837ad..2654e9a1df 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -28,7 +28,7 @@ #if ENABLED(NEOPIXEL_LED) -#include "neopixel.h" +#include "leds.h" #if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" @@ -37,17 +37,21 @@ Marlin_NeoPixel neo; int8_t Marlin_NeoPixel::neoindex; -Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800) - #if CONJOINED_NEOPIXEL - , Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800) - #endif -; +Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800); +#if CONJOINED_NEOPIXEL + Adafruit_NeoPixel Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800); +#endif -#ifdef NEOPIXEL_BKGD_LED_INDEX +#ifdef NEOPIXEL_BKGD_INDEX_FIRST - void Marlin_NeoPixel::set_color_background() { - uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; - set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, adaneo1.Color(background_color[0], background_color[1], background_color[2], background_color[3])); + void Marlin_NeoPixel::set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { + for (int background_led = NEOPIXEL_BKGD_INDEX_FIRST; background_led <= NEOPIXEL_BKGD_INDEX_LAST; background_led++) + set_pixel_color(background_led, adaneo1.Color(r, g, b, w)); + } + + void Marlin_NeoPixel::reset_background_color() { + constexpr uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; + set_background_color(background_color[0], background_color[1], background_color[2], background_color[3]); } #endif @@ -59,9 +63,10 @@ void Marlin_NeoPixel::set_color(const uint32_t color) { } else { for (uint16_t i = 0; i < pixels(); ++i) { - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (i == NEOPIXEL_BKGD_LED_INDEX && TERN(NEOPIXEL_BKGD_ALWAYS_ON, true, color != 0x000000)) { - set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + if (i == NEOPIXEL_BKGD_INDEX_FIRST && TERN(NEOPIXEL_BKGD_ALWAYS_ON, true, color != 0x000000)) { + reset_background_color(); + i += NEOPIXEL_BKGD_INDEX_LAST - (NEOPIXEL_BKGD_INDEX_FIRST); continue; } #endif @@ -90,36 +95,23 @@ void Marlin_NeoPixel::init() { safe_delay(500); set_color_startup(adaneo1.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED + set_color_startup(adaneo1.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #ifdef NEOPIXEL_BKGD_LED_INDEX - set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + reset_background_color(); #endif - #if ENABLED(LED_USER_PRESET_STARTUP) - set_color(adaneo1.Color(LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE)); - #else - set_color(adaneo1.Color(0, 0, 0, 0)); - #endif + set_color(adaneo1.Color + TERN(LED_USER_PRESET_STARTUP, + (LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } -#if 0 -bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p) { - const uint32_t color = adaneo1.Color(r, g, b, w); - set_brightness(p); - #if DISABLED(NEOPIXEL_IS_SEQUENTIAL) - set_color(color); - return false; - #else - static uint16_t nextLed = 0; - set_pixel_color(nextLed, color); - show(); - if (++nextLed >= pixels()) nextLed = 0; - return true; - #endif -} -#endif - #if ENABLED(NEOPIXEL2_SEPARATE) Marlin_NeoPixel2 neo2; @@ -158,13 +150,17 @@ bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint safe_delay(500); set_color_startup(adaneo.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED2 + set_color_startup(adaneo.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #if ENABLED(NEO2_USER_PRESET_STARTUP) - set_color(adaneo.Color(NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE)); - #else - set_color(adaneo.Color(0, 0, 0, 0)); - #endif + set_color(adaneo.Color + TERN(NEO2_USER_PRESET_STARTUP, + (NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } #endif // NEOPIXEL2_SEPARATE diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index acf2e7f54d..e577948cd8 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -25,6 +25,10 @@ * NeoPixel support */ +#ifndef _NEOPIXEL_INCLUDE_ + #error "Always include 'leds.h' and not 'neopixel.h' directly." +#endif + // ------------------------ // Includes // ------------------------ @@ -38,6 +42,18 @@ // Defines // ------------------------ +#define _NEO_IS_RGB(N) (N == NEO_RGB || N == NEO_RBG || N == NEO_GRB || N == NEO_GBR || N == NEO_BRG || N == NEO_BGR) + +#if !_NEO_IS_RGB(NEOPIXEL_TYPE) + #define HAS_WHITE_LED 1 +#endif + +#if HAS_WHITE_LED + #define NEO_WHITE 0, 0, 0, 255 +#else + #define NEO_WHITE 255, 255, 255 +#endif + #if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) #define MULTIPLE_NEOPIXEL_TYPES 1 #endif @@ -46,29 +62,16 @@ #define CONJOINED_NEOPIXEL 1 #endif -#if NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR - #define NEOPIXEL_IS_RGB 1 -#else - #define NEOPIXEL_IS_RGBW 1 -#endif - -#if NEOPIXEL_IS_RGB - #define NEO_WHITE 255, 255, 255, 0 -#else - #define NEO_WHITE 0, 0, 0, 255 -#endif - // ------------------------ // Function prototypes // ------------------------ class Marlin_NeoPixel { private: - static Adafruit_NeoPixel adaneo1 - #if CONJOINED_NEOPIXEL - , adaneo2 - #endif - ; + static Adafruit_NeoPixel adaneo1; + #if CONJOINED_NEOPIXEL + static Adafruit_NeoPixel adaneo2; + #endif public: static int8_t neoindex; @@ -78,8 +81,9 @@ public: static void set_color(const uint32_t c); - #ifdef NEOPIXEL_BKGD_LED_INDEX - static void set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + static void set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w); + static void reset_background_color(); #endif static inline void begin() { @@ -93,9 +97,7 @@ public: else adaneo1.setPixelColor(n, c); #else adaneo1.setPixelColor(n, c); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.setPixelColor(n, c); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setPixelColor(n, c)); #endif } @@ -120,15 +122,13 @@ public: TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); } - #if 0 - bool set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p); - #endif - // Accessors - static inline uint16_t pixels() { TERN(NEOPIXEL2_INSERIES, return adaneo1.numPixels() * 2, return adaneo1.numPixels()); } + static inline uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static inline uint8_t brightness() { return adaneo1.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo1.Color(r, g, b, w); + + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { + return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_LED, w)); } }; @@ -137,15 +137,12 @@ extern Marlin_NeoPixel neo; // Neo pixel channel 2 #if ENABLED(NEOPIXEL2_SEPARATE) - #if NEOPIXEL2_TYPE == NEO_RGB || NEOPIXEL2_TYPE == NEO_RBG || NEOPIXEL2_TYPE == NEO_GRB || NEOPIXEL2_TYPE == NEO_GBR || NEOPIXEL2_TYPE == NEO_BRG || NEOPIXEL2_TYPE == NEO_BGR + #if _NEO_IS_RGB(NEOPIXEL2_TYPE) #define NEOPIXEL2_IS_RGB 1 + #define NEO2_WHITE 255, 255, 255 #else #define NEOPIXEL2_IS_RGBW 1 - #endif - - #if NEOPIXEL2_IS_RGB - #define NEO2_WHITE 255, 255, 255, 0 - #else + #define HAS_WHITE_LED2 1 // A white component can be passed for NEOPIXEL2 #define NEO2_WHITE 0, 0, 0, 255 #endif @@ -172,11 +169,13 @@ extern Marlin_NeoPixel neo; // Accessors static inline uint16_t pixels() { return adaneo.numPixels();} static inline uint8_t brightness() { return adaneo.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo.Color(r, g, b, w); + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { + return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); } }; extern Marlin_NeoPixel2 neo2; #endif // NEOPIXEL2_SEPARATE + +#undef _NEO_IS_RGB diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp index 4765f82e56..e6407a6320 100644 --- a/Marlin/src/feature/leds/printer_event_leds.cpp +++ b/Marlin/src/feature/leds/printer_event_leds.cpp @@ -45,12 +45,10 @@ PrinterEventLEDs printerEventLEDs; return (uint8_t)map(constrain(current, start, target), start, target, 0, 255); } - inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b) { + inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b OPTARG(HAS_WHITE_LED, const uint8_t w=0)) { leds.set_color( - MakeLEDColor(r, g, b, 0, neo.brightness()) - #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) - , true - #endif + LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, neo.brightness())) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, true) ); } diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index cf09bf14ea..5d175ea8f7 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -66,12 +66,12 @@ void GcodeSuite::M150() { #endif #endif - const LEDColor color = MakeLEDColor( + const LEDColor color = LEDColor( parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0, parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness + parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0 + OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0) + OPTARG(NEOPIXEL_LED, parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness) ); #if ENABLED(NEOPIXEL2_SEPARATE) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a8bd7a70ac..c89aaada37 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1321,3 +1321,10 @@ #else #define COORDINATE_OKAY(N,L,H) true #endif + +/** + * LED Backlight INDEX END + */ +#if defined(NEOPIXEL_BKGD_INDEX_FIRST) && !defined(NEOPIXEL_BKGD_INDEX_LAST) + #define NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_INDEX_FIRST +#endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index eea6766148..6ab1fdd3c2 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -562,6 +562,8 @@ #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." #elif defined(MKS_LCD12864) #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." +#elif defined(NEOPIXEL_BKGD_LED_INDEX) + #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." #endif /** diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 044a6642fc..cff6e19354 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -636,8 +636,8 @@ void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { // RED ALERT. RED ALERT. #ifdef LED_BACKLIGHT_TIMEOUT leds.set_color(LEDColorRed()); - #ifdef NEOPIXEL_BKGD_LED_INDEX - neo.set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, 255, 0, 0, 0); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + neo.set_background_color(255, 0, 0, 0); neo.show(); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 5ab5e8a9d8..284e80c931 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -84,18 +84,20 @@ EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); - #if EITHER(RGBW_LED, NEOPIXEL_LED) + #if HAS_WHITE_LED EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); - #if ENABLED(NEOPIXEL_LED) - EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); - #endif + #endif + #if ENABLED(NEOPIXEL_LED) + EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); #endif #if ENABLED(NEOPIXEL2_SEPARATE) STATIC_ITEM_N(MSG_LED_CHANNEL_N, 2, SS_DEFAULT|SS_INVERT); EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #if HAS_WHITE_LED2 + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #endif EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); #endif END_MENU(); diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index d1601edf5a..9931776e00 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -18,7 +18,7 @@ opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ ASSISTED_TRAMMING ASSISTED_TRAMMING_WIZARD REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_DISTANCE_MM FILAMENT_RUNOUT_SENSOR \ AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE CALIBRATION_GCODE \ diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 92fda54483..95a055d695 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -14,8 +14,10 @@ set -e #exec_test $1 $2 "Default Configuration" "$3" restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB NEOPIXEL_PIN P1_16 SERIAL_PORT_3 3 -opt_enable VIKI2 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 NEOPIXEL_LED +opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB SERIAL_PORT_3 3 \ + NEOPIXEL_TYPE NEO_GRB RGB_LED_R_PIN P2_12 RGB_LED_G_PIN P1_23 RGB_LED_B_PIN P1_22 RGB_LED_W_PIN P1_24 +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED \ + NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_ALWAYS_ON exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3" #restore_configs diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 953e7e8efc..df2717c715 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -22,7 +22,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS LEVEL_CENTER_TOO \ NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ From e400ef346a317fe36dd98b821c3b04098d8b7a3c Mon Sep 17 00:00:00 2001 From: Allen Bauer Date: Tue, 25 May 2021 17:08:10 -0700 Subject: [PATCH 0173/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20BTT002=20variant?= =?UTF-8?q?=20MMU2=20serial=20pins=20=F0=9F=A7=A9=20(#21980)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h index ecc319f47c..59a7f24527 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h @@ -264,6 +264,11 @@ extern "C" { #define PIN_SERIAL_RX PA10 #define PIN_SERIAL_TX PA9 +// Serial Pins for the MMU2 +#define ENABLE_HWSERIAL4 +#define PIN_SERIAL4_RX PC11 +#define PIN_SERIAL4_TX PC10 + #ifdef __cplusplus } // extern "C" #endif From 214fe90a3bb840a15affa350a61e54b8bd740f0e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 26 May 2021 01:24:58 +0000 Subject: [PATCH 0174/2168] [cron] Bump distribution date (2021-05-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2c57bad370..4d02ddf997 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 "2021-05-25" + #define STRING_DISTRIBUTION_DATE "2021-05-26" #endif /** From 6a32d87e582af5434061d6413648e6ee1822275e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 27 May 2021 01:36:38 +0000 Subject: [PATCH 0175/2168] [cron] Bump distribution date (2021-05-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4d02ddf997..7f7765515c 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 "2021-05-26" + #define STRING_DISTRIBUTION_DATE "2021-05-27" #endif /** From 5c6a2f4d0d19c786ee00c8a828e150290d793c26 Mon Sep 17 00:00:00 2001 From: Andy Barratt Date: Thu, 27 May 2021 03:07:13 +0100 Subject: [PATCH 0176/2168] =?UTF-8?q?=F0=9F=9A=B8=20cap:HOST=5FACTION=5FCO?= =?UTF-8?q?MMANDS=20(#21987)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index ef4c8983cd..49bb806377 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -119,6 +119,9 @@ void GcodeSuite::M115() { // EMERGENCY_PARSER (M108, M112, M410, M876) cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); + // HOST ACTION COMMANDS (paused, resume, resumed, cancel, etc.) + cap_line(PSTR("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS)); + // PROMPT SUPPORT (M876) cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); From 605b539ecdcaaa54cfaec2317c2fe7eab0ba2680 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 27 May 2021 22:13:43 +1200 Subject: [PATCH 0177/2168] =?UTF-8?q?=F0=9F=A5=85=20Add=20MESH=5FEDIT=5FME?= =?UTF-8?q?NU=20sanity=20check=20(#21922)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 6ab1fdd3c2..9181b24000 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1584,6 +1584,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LCD_BED_LEVELING requires a programmable LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." + #elif ENABLED(MESH_EDIT_MENU) && !HAS_MESH + #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." #endif #endif From b80179d14a23911dc81dfa7fe9d6fca653326798 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 28 May 2021 01:45:42 +0000 Subject: [PATCH 0178/2168] [cron] Bump distribution date (2021-05-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7f7765515c..5c5ff6c31c 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 "2021-05-27" + #define STRING_DISTRIBUTION_DATE "2021-05-28" #endif /** From 25a8bbcbf3c7dbbc68aec9a85a8091488a2011b4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 29 May 2021 02:01:09 +0000 Subject: [PATCH 0179/2168] [cron] Bump distribution date (2021-05-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5c5ff6c31c..1312a07880 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 "2021-05-28" + #define STRING_DISTRIBUTION_DATE "2021-05-29" #endif /** From dbed0090900d3924cf8e30f2afa2e349d7ecbb18 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Krzysztof=20B=C5=82a=C5=BCewicz?= Date: Sat, 29 May 2021 20:48:56 +0200 Subject: [PATCH 0180/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Polish=20lang?= =?UTF-8?q?uage=20(#21993)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_pl.h | 328 ++++++++++++++++++++------ 1 file changed, 259 insertions(+), 69 deletions(-) diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9004722cfc..7b4733b7ba 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -26,6 +26,13 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html + * + * Substitutions are applied for the following characters when used + * in menu items that call lcd_put_u8str_ind_P with an index: + * + * = displays '0'....'10' for indexes 0 - 10 + * ~ displays '1'....'11' for indexes 0 - 10 + * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) */ #define DISPLAY_CHARSET_ISO10646_PL @@ -34,9 +41,10 @@ namespace Language_pl { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Polish"); + PROGMEM Language_Str LANGUAGE = _UxGT("Polski"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); + //PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); PROGMEM Language_Str MSG_YES = _UxGT("TAK"); PROGMEM Language_Str MSG_NO = _UxGT("NIE"); PROGMEM Language_Str MSG_BACK = _UxGT("Wstecz"); @@ -44,9 +52,11 @@ namespace Language_pl { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + //PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menu główne"); @@ -61,14 +71,24 @@ namespace Language_pl { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); + //PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknij by rozp."); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Następny punkt"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); + //PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); + //PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); + //PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Rozgrzej ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Rozgrzej ") PREHEAT_1_LABEL " ~"; @@ -88,10 +108,21 @@ namespace Language_pl { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Rozgrzej własne ust."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Chłodzenie"); + + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Częstotliwość"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Sterowanie Lasera"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); + //PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + //PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + //PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + //PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + //PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + //PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + //PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + //PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + //PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); @@ -101,6 +132,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Narożniki poziomowania"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Good Points: "); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); @@ -112,6 +147,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punky"); + //PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylenie"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Tryb IDEX"); PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); @@ -119,14 +155,16 @@ namespace Language_pl { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); + //PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); + //PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); @@ -143,14 +181,12 @@ namespace Language_pl { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec edycji siati"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Buduj własna siatkę"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Buduj siatkę"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Buduj siatkę na zimno"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Dostrojenie wysokości siatki"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Wartość wysokości"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sprawdzenie siatki"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Sprawdzenie własnej siatki"); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Nagrzewanie stołu"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); @@ -211,6 +247,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Biały"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanał ="); + //PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); + //PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Własne światła"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Czerwony"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zielony"); @@ -226,31 +266,60 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10mm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); PROGMEM Language_Str MSG_SPEED = _UxGT("Predkość"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Stół Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dysza"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dysza ~"); + //PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); PROGMEM Language_Str MSG_BED = _UxGT("Stół"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Obudowa"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wiatraka"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wiatraka ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wiatraka"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wiatraka ~"); + //PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); + //PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + //PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + //PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); + //PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); PROGMEM Language_Str MSG_FLOW = _UxGT("Przepływ"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Przepływ ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Ustawienia"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + //PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + //PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto. temperatura"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Wł."); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Wył."); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); + //PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + //PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + //PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + //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("Wybierz"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Wybierz *"); PROGMEM Language_Str MSG_ACC = _UxGT("Przyspieszenie"); @@ -259,61 +328,83 @@ namespace Language_pl { PROGMEM Language_Str MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Zryw Ve"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + //PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Prędkość (V)"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + //PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + //PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + //PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + //PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + //PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + //PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vskok min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + //PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + //PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + //PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + //PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + //PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-wycofanie"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-przesuń."); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); + //PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("kroki/mm"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("kroki") LCD_STR_A _UxGT("/mm"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("kroki") LCD_STR_B _UxGT("/mm"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("kroki") LCD_STR_C _UxGT("/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("krokiE/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("kroki */mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroki/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroki/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Ruch"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); + //PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); + //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("Kontrast LCD"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); + //PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + //PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Ekran główny"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Przygotuj"); PROGMEM Language_Str MSG_TUNE = _UxGT("Strojenie"); + //PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power monitor"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Natężenie"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Napięcie"); + PROGMEM Language_Str MSG_POWER = _UxGT("Moc"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start wydruku"); PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Następny"); PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inic."); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); + //PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drukuj"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetuj"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Przerwij"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Gotowe"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Wstecz"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Kontynuuj"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Pomiń"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Wstrzymywanie..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Wznowienie"); + //PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop"); + //PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Karta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Brak karty"); @@ -322,6 +413,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druk wstrzymany"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Drukowanie..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druk przerwany"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druk zakończony"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Brak ruchu"); PROGMEM Language_Str MSG_KILLED = _UxGT("Ubity. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("Zatrzymany. "); @@ -331,15 +423,26 @@ namespace Language_pl { PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); + //PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); + //PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); + //PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); @@ -352,31 +455,35 @@ namespace Language_pl { PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + //PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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_STOW = _UxGT("Stow"); + //PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + //PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); - 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_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("Najpierw Home %s%s%s"); + //PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + //PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + //PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); + //PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); + //PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + //PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); @@ -384,19 +491,24 @@ namespace Language_pl { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); + //PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + //PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("Drukarka zatrzym."); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + //PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("g"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only + //PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("Rozgrzewanie..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Chłodzenie..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); + //PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + //PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); + //PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); @@ -414,8 +526,9 @@ namespace Language_pl { PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); + //PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statystyki"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -424,6 +537,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokół"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); + //PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); @@ -443,8 +557,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + //PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + //PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Zasilacz"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Siła %"); @@ -467,7 +581,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + //PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); @@ -482,7 +596,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Wszystko"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + //PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetuj MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); @@ -490,12 +604,41 @@ namespace Language_pl { PROGMEM Language_Str MSG_MIX = _UxGT("Miks"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mikser"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); + //PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient 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("Odwrotny 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("Gry"); + //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"); + + //PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); + //PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Wprowadź cyfrę"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Ustaw/zmień hasło"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Usuń hasło"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Hasło to "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Od nowa"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Pamiętaj by zapisać!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Hasło usunięte"); // // Filament Change screens show up to 3 lines on a 4-line display @@ -526,4 +669,51 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); + //PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); + //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("Korekcja"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); + #else + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + #endif + //PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); + //PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + + //PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Dźwięk"); + + //PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); + //PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + //PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); + //PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); + + //PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); } + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif From dceaeeeaf9591f67135356d0485e4c2936c08f2f Mon Sep 17 00:00:00 2001 From: Timo Date: Sat, 29 May 2021 14:00:39 -0700 Subject: [PATCH 0181/2168] =?UTF-8?q?=E2=9C=A8=20Malyan=20M180=20(#21992)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/mega/pins_MALYAN_M180.h | 100 ++++++++++++++++++++++++ Marlin/src/pins/pins.h | 2 + 3 files changed, 103 insertions(+) create mode 100644 Marlin/src/pins/mega/pins_MALYAN_M180.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 20aeac654d..1f73f04d16 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -159,6 +159,7 @@ #define BOARD_PICA_REVB 1324 // PICA Shield (original version) #define BOARD_PICA 1325 // PICA Shield (rev C or later) #define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) +#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h new file mode 100644 index 0000000000..e244d294f1 --- /dev/null +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -0,0 +1,100 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Malyan M180 pin assignments + * Contributed by Timo Birnschein (timo.birnschein@microforge.de) + */ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Malyan M180 v.2" +// +// Limit Switches +// +#define X_STOP_PIN 48 +#define Y_STOP_PIN 46 +#define Z_STOP_PIN 42 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN -1 +#endif + +// +// Steppers +// +#define X_STEP_PIN 55 +#define X_DIR_PIN 54 +#define X_ENABLE_PIN 56 + +#define Y_STEP_PIN 59 +#define Y_DIR_PIN 58 +#define Y_ENABLE_PIN 60 + +#define Z_STEP_PIN 63 +#define Z_DIR_PIN 62 +#define Z_ENABLE_PIN 64 + +#define E0_STEP_PIN 25 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 26 + +#define E1_STEP_PIN 29 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 39 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN 15 // Analog Input + +// Extruder thermocouples 0 and 1 are read out by two separate ICs using +// SPI for Max6675 Thermocouple +// Uses a separate SPI bus +#define THERMO_SCK_PIN 78 // E2 - SCK +#define THERMO_DO_PIN 3 // E5 - DO +#define THERMO_CS1_PIN 5 // E3 - CS0 +#define THERMO_CS2_PIN 2 // E4 - CS1 + +#define MAX6675_SS_PIN THERMO_CS1_PIN +#define MAX6675_SS2_PIN THERMO_CS2_PIN +#define MAX6675_SCK_PIN THERMO_SCK_PIN +#define MAX6675_DO_PIN THERMO_DO_PIN + +// +// Heaters / Fans +// +#define HEATER_0_PIN 6 +#define HEATER_1_PIN 11 +#define HEATER_BED_PIN 45 + +#ifndef FAN_PIN + #define FAN_PIN 7 // M106 Sxxx command supported and tested. M107 as well. +#endif + +#ifndef FAN_PIN1 + #define FAN_PIN1 12 // Currently Unsupported by Marlin +#endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a8ed35b009..3176b5e832 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -270,6 +270,8 @@ #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 #elif MB(INTAMSYS40) #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 +#elif MB(MALYAN_M180) + #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 From 52ae3e6967bb6e3105d31772a58f820ca71477a9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 30 May 2021 02:14:17 +0000 Subject: [PATCH 0182/2168] [cron] Bump distribution date (2021-05-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 1312a07880..e383f182b3 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 "2021-05-29" + #define STRING_DISTRIBUTION_DATE "2021-05-30" #endif /** From bc6e90f4ab4384b8dd20a10ea4f0e745cda544f0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 31 May 2021 02:26:30 +0000 Subject: [PATCH 0183/2168] [cron] Bump distribution date (2021-05-31) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e383f182b3..21dfffda67 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 "2021-05-30" + #define STRING_DISTRIBUTION_DATE "2021-05-31" #endif /** From da76381605533bd71d9cdce29f0ac3b0e5c11709 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Krzysztof=20B=C5=82a=C5=BCewicz?= Date: Mon, 31 May 2021 08:44:38 +0200 Subject: [PATCH 0184/2168] =?UTF-8?q?=E2=9A=97=EF=B8=8F=2032-bit=20float?= =?UTF-8?q?=20constants=20(STM32F1)=20(#21996)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32F1/build_flags.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py index c51fd4fa58..d0848d1c64 100755 --- a/Marlin/src/HAL/STM32F1/build_flags.py +++ b/Marlin/src/HAL/STM32F1/build_flags.py @@ -11,6 +11,7 @@ if __name__ == "__main__": "-fsigned-char", "-fno-move-loop-invariants", "-fno-strict-aliasing", + "-fsingle-precision-constant", "--specs=nano.specs", "--specs=nosys.specs", From 74be64a1ec40ecdb9d4adb5cc8c72afbb2af1651 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 1 Jun 2021 02:51:06 +0000 Subject: [PATCH 0185/2168] [cron] Bump distribution date (2021-06-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 21dfffda67..32fc8c23d6 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 "2021-05-31" + #define STRING_DISTRIBUTION_DATE "2021-06-01" #endif /** From 82ea06e6a4ffdb0816ab92a5dd721ec5d770015d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 1 Jun 2021 20:23:37 -0500 Subject: [PATCH 0186/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Patches=20for=20?= =?UTF-8?q?Zero=20Extruders=20(with=20TMC)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/types.h | 4 +- Marlin/src/feature/tmc_util.cpp | 88 +-- Marlin/src/gcode/feature/L6470/M906.cpp | 101 +-- Marlin/src/gcode/feature/trinamic/M569.cpp | 99 +-- Marlin/src/gcode/feature/trinamic/M906.cpp | 101 +-- Marlin/src/inc/Conditionals_LCD.h | 4 + Marlin/src/inc/SanityCheck.h | 4 + Marlin/src/module/planner_bezier.cpp | 8 +- Marlin/src/module/stepper.cpp | 6 +- Marlin/src/pins/pins_postprocess.h | 770 +++++++++++---------- 10 files changed, 618 insertions(+), 567 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 41cb39f163..abb709d731 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -360,7 +360,7 @@ struct XYZval { 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)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } - #if LINEAR_AXES >= XYZ + #if HAS_Z_AXIS FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } #endif @@ -475,7 +475,7 @@ struct XYZEval { FI void set(const T px, const T py) { x = px; y = py; } FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } FI void set(const XYZval pxyz) { set(LINEAR_AXIS_LIST(pxyz.x, pxyz.y, pxyz.z)); } - #if LINEAR_AXES >= XYZ + #if HAS_Z_AXIS FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index e244a33eee..021317ea89 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -770,16 +770,18 @@ #endif } - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_status(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_status(stepperY2, i); - #endif - } + #if LINEAR_AXES >= XY + if (print_y) { + #if AXIS_IS_TMC(Y) + tmc_status(stepperY, i); + #endif + #if AXIS_IS_TMC(Y2) + tmc_status(stepperY2, i); + #endif + } + #endif - if (print_z) { + if (TERN0(HAS_Z_AXIS, print_z)) { #if AXIS_IS_TMC(Z) tmc_status(stepperZ, i); #endif @@ -794,7 +796,7 @@ #endif } - if (print_e) { + if (TERN0(HAS_EXTRUDERS, print_e)) { #if AXIS_IS_TMC(E0) tmc_status(stepperE0, i); #endif @@ -837,16 +839,18 @@ #endif } - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_parse_drv_status(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_parse_drv_status(stepperY2, i); - #endif - } + #if LINEAR_AXES >= XY + if (print_y) { + #if AXIS_IS_TMC(Y) + tmc_parse_drv_status(stepperY, i); + #endif + #if AXIS_IS_TMC(Y2) + tmc_parse_drv_status(stepperY2, i); + #endif + } + #endif - if (print_z) { + if (TERN0(HAS_Z_AXIS, print_z)) { #if AXIS_IS_TMC(Z) tmc_parse_drv_status(stepperZ, i); #endif @@ -861,7 +865,7 @@ #endif } - if (print_e) { + if (TERN0(HAS_EXTRUDERS, print_e)) { #if AXIS_IS_TMC(E0) tmc_parse_drv_status(stepperE0, i); #endif @@ -1037,16 +1041,18 @@ #endif } - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_get_registers(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_get_registers(stepperY2, i); - #endif - } + #if LINEAR_AXES >= XY + if (print_y) { + #if AXIS_IS_TMC(Y) + tmc_get_registers(stepperY, i); + #endif + #if AXIS_IS_TMC(Y2) + tmc_get_registers(stepperY2, i); + #endif + } + #endif - if (print_z) { + if (TERN0(HAS_Z_AXIS, print_z)) { #if AXIS_IS_TMC(Z) tmc_get_registers(stepperZ, i); #endif @@ -1061,7 +1067,7 @@ #endif } - if (print_e) { + if (TERN0(HAS_EXTRUDERS, print_e)) { #if AXIS_IS_TMC(E0) tmc_get_registers(stepperE0, i); #endif @@ -1242,16 +1248,18 @@ void test_tmc_connection( #endif } - if (test_y) { - #if AXIS_IS_TMC(Y) - axis_connection += test_connection(stepperY); - #endif - #if AXIS_IS_TMC(Y2) - axis_connection += test_connection(stepperY2); - #endif - } + #if LINEAR_AXES >= XY + if (test_y) { + #if AXIS_IS_TMC(Y) + axis_connection += test_connection(stepperY); + #endif + #if AXIS_IS_TMC(Y2) + axis_connection += test_connection(stepperY2); + #endif + } + #endif - if (test_z) { + if (TERN0(HAS_Z_AXIS, test_z)) { #if AXIS_IS_TMC(Z) axis_connection += test_connection(stepperZ); #endif @@ -1266,7 +1274,7 @@ void test_tmc_connection( #endif } - if (test_e) { + if (TERN0(HAS_EXTRUDERS, test_e)) { #if AXIS_IS_TMC(E0) axis_connection += test_connection(stepperE0); #endif diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 87614e9c73..05631e99d2 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -252,58 +252,67 @@ void GcodeSuite::M906() { if (index == 1) L6470_SET_KVAL_HOLD(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_L64XX(Y) - if (index == 0) L6470_SET_KVAL_HOLD(Y); - #endif - #if AXIS_IS_L64XX(Y2) - if (index == 1) L6470_SET_KVAL_HOLD(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_L64XX(Z) - if (index == 0) L6470_SET_KVAL_HOLD(Z); - #endif - #if AXIS_IS_L64XX(Z2) - if (index == 1) L6470_SET_KVAL_HOLD(Z2); - #endif - #if AXIS_IS_L64XX(Z3) - if (index == 2) L6470_SET_KVAL_HOLD(Z3); - #endif - #if AXIS_DRIVER_TYPE_Z4(L6470) - if (index == 3) L6470_SET_KVAL_HOLD(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_L64XX(E0) - case 0: L6470_SET_KVAL_HOLD(E0); break; + + #if LINEAR_AXES >= XY + case Y_AXIS: + #if AXIS_IS_L64XX(Y) + if (index == 0) L6470_SET_KVAL_HOLD(Y); #endif - #if AXIS_IS_L64XX(E1) - case 1: L6470_SET_KVAL_HOLD(E1); break; + #if AXIS_IS_L64XX(Y2) + if (index == 1) L6470_SET_KVAL_HOLD(Y2); #endif - #if AXIS_IS_L64XX(E2) - case 2: L6470_SET_KVAL_HOLD(E2); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_L64XX(Z) + if (index == 0) L6470_SET_KVAL_HOLD(Z); #endif - #if AXIS_IS_L64XX(E3) - case 3: L6470_SET_KVAL_HOLD(E3); break; + #if AXIS_IS_L64XX(Z2) + if (index == 1) L6470_SET_KVAL_HOLD(Z2); #endif - #if AXIS_IS_L64XX(E4) - case 4: L6470_SET_KVAL_HOLD(E4); break; + #if AXIS_IS_L64XX(Z3) + if (index == 2) L6470_SET_KVAL_HOLD(Z3); #endif - #if AXIS_IS_L64XX(E5) - case 5: L6470_SET_KVAL_HOLD(E5); break; + #if AXIS_DRIVER_TYPE_Z4(L6470) + if (index == 3) L6470_SET_KVAL_HOLD(Z4); #endif - #if AXIS_IS_L64XX(E6) - case 6: L6470_SET_KVAL_HOLD(E6); break; - #endif - #if AXIS_IS_L64XX(E7) - case 7: L6470_SET_KVAL_HOLD(E7); break; - #endif - } - } break; + break; + #endif + + #if HAS_EXTRUDERS + case E_AXIS: { + const int8_t target_extruder = get_target_extruder_from_command(); + if (target_extruder < 0) return; + switch (target_extruder) { + #if AXIS_IS_L64XX(E0) + case 0: L6470_SET_KVAL_HOLD(E0); break; + #endif + #if AXIS_IS_L64XX(E1) + case 1: L6470_SET_KVAL_HOLD(E1); break; + #endif + #if AXIS_IS_L64XX(E2) + case 2: L6470_SET_KVAL_HOLD(E2); break; + #endif + #if AXIS_IS_L64XX(E3) + case 3: L6470_SET_KVAL_HOLD(E3); break; + #endif + #if AXIS_IS_L64XX(E4) + case 4: L6470_SET_KVAL_HOLD(E4); break; + #endif + #if AXIS_IS_L64XX(E5) + case 5: L6470_SET_KVAL_HOLD(E5); break; + #endif + #if AXIS_IS_L64XX(E6) + case 6: L6470_SET_KVAL_HOLD(E6); break; + #endif + #if AXIS_IS_L64XX(E7) + case 7: L6470_SET_KVAL_HOLD(E7); break; + #endif + } + } break; + #endif } } diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 8f1c0ed819..4659616467 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -60,57 +60,66 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder) if (index == 1) TMC_SET_STEALTH(X2); #endif break; - case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index == 0) TMC_SET_STEALTH(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (index == 1) TMC_SET_STEALTH(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index == 0) TMC_SET_STEALTH(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 1) TMC_SET_STEALTH(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 2) TMC_SET_STEALTH(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 3) TMC_SET_STEALTH(Z4); - #endif - break; - case E_AXIS: { - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_STEALTH(E0); break; + + #if LINEAR_AXES >= XY + case Y_AXIS: + #if AXIS_HAS_STEALTHCHOP(Y) + if (index == 0) TMC_SET_STEALTH(Y); #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_STEALTH(E1); break; + #if AXIS_HAS_STEALTHCHOP(Y2) + if (index == 1) TMC_SET_STEALTH(Y2); #endif - #if AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_STEALTH(E2); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_HAS_STEALTHCHOP(Z) + if (index == 0) TMC_SET_STEALTH(Z); #endif - #if AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_STEALTH(E3); break; + #if AXIS_HAS_STEALTHCHOP(Z2) + if (index == 1) TMC_SET_STEALTH(Z2); #endif - #if AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_STEALTH(E4); break; + #if AXIS_HAS_STEALTHCHOP(Z3) + if (index == 2) TMC_SET_STEALTH(Z3); #endif - #if AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_STEALTH(E5); break; + #if AXIS_HAS_STEALTHCHOP(Z4) + if (index == 3) TMC_SET_STEALTH(Z4); #endif - #if AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_STEALTH(E6); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_STEALTH(E7); break; - #endif - } - } break; + break; + #endif + + #if HAS_EXTRUDERS + case E_AXIS: { + if (target_extruder < 0) return; + switch (target_extruder) { + #if AXIS_HAS_STEALTHCHOP(E0) + case 0: TMC_SET_STEALTH(E0); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E1) + case 1: TMC_SET_STEALTH(E1); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E2) + case 2: TMC_SET_STEALTH(E2); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E3) + case 3: TMC_SET_STEALTH(E3); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E4) + case 4: TMC_SET_STEALTH(E4); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E5) + case 5: TMC_SET_STEALTH(E5); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E6) + case 6: TMC_SET_STEALTH(E6); break; + #endif + #if AXIS_HAS_STEALTHCHOP(E7) + case 7: TMC_SET_STEALTH(E7); break; + #endif + } + } break; + #endif } } } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 86e0cd2987..848735b900 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -63,58 +63,67 @@ void GcodeSuite::M906() { if (index == 1) TMC_SET_CURRENT(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_TMC(Y) - if (index == 0) TMC_SET_CURRENT(Y); - #endif - #if AXIS_IS_TMC(Y2) - if (index == 1) TMC_SET_CURRENT(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_TMC(Z) - if (index == 0) TMC_SET_CURRENT(Z); - #endif - #if AXIS_IS_TMC(Z2) - if (index == 1) TMC_SET_CURRENT(Z2); - #endif - #if AXIS_IS_TMC(Z3) - if (index == 2) TMC_SET_CURRENT(Z3); - #endif - #if AXIS_IS_TMC(Z4) - if (index == 3) TMC_SET_CURRENT(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_TMC(E0) - case 0: TMC_SET_CURRENT(E0); break; + + #if LINEAR_AXES >= XY + case Y_AXIS: + #if AXIS_IS_TMC(Y) + if (index == 0) TMC_SET_CURRENT(Y); #endif - #if AXIS_IS_TMC(E1) - case 1: TMC_SET_CURRENT(E1); break; + #if AXIS_IS_TMC(Y2) + if (index == 1) TMC_SET_CURRENT(Y2); #endif - #if AXIS_IS_TMC(E2) - case 2: TMC_SET_CURRENT(E2); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_TMC(Z) + if (index == 0) TMC_SET_CURRENT(Z); #endif - #if AXIS_IS_TMC(E3) - case 3: TMC_SET_CURRENT(E3); break; + #if AXIS_IS_TMC(Z2) + if (index == 1) TMC_SET_CURRENT(Z2); #endif - #if AXIS_IS_TMC(E4) - case 4: TMC_SET_CURRENT(E4); break; + #if AXIS_IS_TMC(Z3) + if (index == 2) TMC_SET_CURRENT(Z3); #endif - #if AXIS_IS_TMC(E5) - case 5: TMC_SET_CURRENT(E5); break; + #if AXIS_IS_TMC(Z4) + if (index == 3) TMC_SET_CURRENT(Z4); #endif - #if AXIS_IS_TMC(E6) - case 6: TMC_SET_CURRENT(E6); break; - #endif - #if AXIS_IS_TMC(E7) - case 7: TMC_SET_CURRENT(E7); break; - #endif - } - } break; + break; + #endif + + #if HAS_EXTRUDERS + case E_AXIS: { + const int8_t target_extruder = get_target_extruder_from_command(); + if (target_extruder < 0) return; + switch (target_extruder) { + #if AXIS_IS_TMC(E0) + case 0: TMC_SET_CURRENT(E0); break; + #endif + #if AXIS_IS_TMC(E1) + case 1: TMC_SET_CURRENT(E1); break; + #endif + #if AXIS_IS_TMC(E2) + case 2: TMC_SET_CURRENT(E2); break; + #endif + #if AXIS_IS_TMC(E3) + case 3: TMC_SET_CURRENT(E3); break; + #endif + #if AXIS_IS_TMC(E4) + case 4: TMC_SET_CURRENT(E4); break; + #endif + #if AXIS_IS_TMC(E5) + case 5: TMC_SET_CURRENT(E5); break; + #endif + #if AXIS_IS_TMC(E6) + case 6: TMC_SET_CURRENT(E6); break; + #endif + #if AXIS_IS_TMC(E7) + case 7: TMC_SET_CURRENT(E7); break; + #endif + } + } break; + #endif } } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index c89aaada37..9b4f832a05 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -624,6 +624,10 @@ #define LOGICAL_AXES LINEAR_AXES #endif +#if LINEAR_AXES >= XYZ + #define HAS_Z_AXIS 1 +#endif + /** * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. * diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 9181b24000..eabe7adbfb 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2956,6 +2956,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_EXTRA_HEIGHT to be set." #elif !defined(GANTRY_CALIBRATION_FEEDRATE) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_FEEDRATE to be set." + #elif ENABLED(Z_MULTI_ENDSTOPS) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_MULTI_ENDSTOPS." + #elif ENABLED(Z_STEPPER_AUTO_ALIGN) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_STEPPER_AUTO_ALIGN." #endif #if defined(GANTRY_CALIBRATION_SAFE_POSITION) && !defined(GANTRY_CALIBRATION_XY_PARK_FEEDRATE) #error "GANTRY_CALIBRATION_SAFE_POSITION Requires GANTRY_CALIBRATION_XY_PARK_FEEDRATE to be set." diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index be5ce4bbb4..a5e7696e0b 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -181,11 +181,11 @@ void cubic_b_spline( t = new_t; // Compute and send new position - xyze_pos_t new_bez = { + xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY( + interp(position.e, target.e, t), // FIXME. These two are wrong, since the parameter t is not linear in the distance. new_pos0, new_pos1, - interp(position.z, target.z, t), // FIXME. These two are wrong, since the parameter t is - interp(position.e, target.e, t) // not linear in the distance. - }; + interp(position.z, target.z, t) + ); apply_motion_limits(new_bez); bez_target = new_bez; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index bc6dbeaf25..05286a6566 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -259,7 +259,7 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ @@ -285,7 +285,7 @@ xyze_int8_t Stepper::count_direction{0}; #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ @@ -316,7 +316,7 @@ xyze_int8_t Stepper::count_direction{0}; #define QUAD_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 37ebbd47ad..8cc19678f1 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -438,6 +438,392 @@ #define Z_STOP_PIN Z_MAX_PIN #endif +// Filament Sensor first pin alias +#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 + #define LCD_PINS_D4 -1 +#endif + +#if HAS_MARLINUI_HD44780 || TOUCH_UI_ULTIPANEL + #ifndef LCD_PINS_D5 + #define LCD_PINS_D5 -1 + #endif + #ifndef LCD_PINS_D6 + #define LCD_PINS_D6 -1 + #endif + #ifndef LCD_PINS_D7 + #define LCD_PINS_D7 -1 + #endif +#endif + +/** + * Auto-Assignment for Dual X, Dual Y, Multi-Z Steppers + * + * By default X2 is assigned to the next open E plug + * on the board, then in order, Y2, Z2, Z3. These can be + * overridden in Configuration.h or Configuration_adv.h. + */ + +#define __PEXI(p,q) PIN_EXISTS(E##p##_##q) +#define _PEXI(p,q) __PEXI(p,q) +#define __EPIN(p,q) E##p##_##q##_PIN +#define _EPIN(p,q) __EPIN(p,q) +#define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) + +// The X2 axis, if any, should be the next open extruder port +#define X2_E_INDEX E_STEPPERS + +#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) + #ifndef X2_STEP_PIN + #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) + #define X2_DIR_PIN _EPIN(X2_E_INDEX, DIR) + #define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE) + #if X2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(X2_STEP) + #error "No E stepper plug left for X2!" + #endif + #endif + #ifndef X2_MS1_PIN + #define X2_MS1_PIN _EPIN(X2_E_INDEX, MS1) + #endif + #ifndef X2_MS2_PIN + #define X2_MS2_PIN _EPIN(X2_E_INDEX, MS2) + #endif + #ifndef X2_MS3_PIN + #define X2_MS3_PIN _EPIN(X2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(X2) && !defined(X2_CS_PIN) + #define X2_CS_PIN _EPIN(X2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(X2) + #ifndef X2_SERIAL_TX_PIN + #define X2_SERIAL_TX_PIN _EPIN(X2_E_INDEX, SERIAL_TX) + #endif + #ifndef X2_SERIAL_RX_PIN + #define X2_SERIAL_RX_PIN _EPIN(X2_E_INDEX, SERIAL_RX) + #endif + #endif + + // + // Auto-assign pins for stallGuard sensorless homing + // + #if !defined(X2_USE_ENDSTOP) && defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) + #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) + #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... + #define X2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(X2, Y_MIN) + #define X2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(X2, Z_MIN) + #define X2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(X2, X_MAX) + #define X2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(X2, Y_MAX) + #define X2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(X2, Z_MAX) + #define X2_USE_ENDSTOP _ZMAX_ + #else // Otherwise use the driver DIAG_PIN directly + #define _X2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define X2_USE_ENDSTOP _X2_USE_ENDSTOP(X2_E_INDEX) + #endif + #undef X2_DIAG_PIN + #endif + + #define Y2_E_INDEX INCREMENT(X2_E_INDEX) +#else + #define Y2_E_INDEX X2_E_INDEX +#endif + +#ifndef X2_CS_PIN + #define X2_CS_PIN -1 +#endif +#ifndef X2_MS1_PIN + #define X2_MS1_PIN -1 +#endif +#ifndef X2_MS2_PIN + #define X2_MS2_PIN -1 +#endif +#ifndef X2_MS3_PIN + #define X2_MS3_PIN -1 +#endif + +// The Y2 axis, if any, should be the next open extruder port +#if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #ifndef Y2_STEP_PIN + #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) + #define Y2_DIR_PIN _EPIN(Y2_E_INDEX, DIR) + #define Y2_ENABLE_PIN _EPIN(Y2_E_INDEX, ENABLE) + #if Y2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Y2_STEP) + #error "No E stepper plug left for Y2!" + #endif + #endif + #ifndef Y2_MS1_PIN + #define Y2_MS1_PIN _EPIN(Y2_E_INDEX, MS1) + #endif + #ifndef Y2_MS2_PIN + #define Y2_MS2_PIN _EPIN(Y2_E_INDEX, MS2) + #endif + #ifndef Y2_MS3_PIN + #define Y2_MS3_PIN _EPIN(Y2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(Y2) && !defined(Y2_CS_PIN) + #define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(Y2) + #ifndef Y2_SERIAL_TX_PIN + #define Y2_SERIAL_TX_PIN _EPIN(Y2_E_INDEX, SERIAL_TX) + #endif + #ifndef Y2_SERIAL_RX_PIN + #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Y2_USE_ENDSTOP) && defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) + #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) + #if DIAG_REMAPPED(Y2, X_MIN) + #define Y2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Y2, Y_MIN) + #define Y2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Y2, Z_MIN) + #define Y2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Y2, X_MAX) + #define Y2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Y2, Y_MAX) + #define Y2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Y2, Z_MAX) + #define Y2_USE_ENDSTOP _ZMAX_ + #else + #define _Y2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Y2_USE_ENDSTOP _Y2_USE_ENDSTOP(Y2_E_INDEX) + #endif + #undef Y2_DIAG_PIN + #endif + #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) +#else + #define Z2_E_INDEX Y2_E_INDEX +#endif + +#ifndef Y2_CS_PIN + #define Y2_CS_PIN -1 +#endif +#ifndef Y2_MS1_PIN + #define Y2_MS1_PIN -1 +#endif +#ifndef Y2_MS2_PIN + #define Y2_MS2_PIN -1 +#endif +#ifndef Y2_MS3_PIN + #define Y2_MS3_PIN -1 +#endif + +// The Z2 axis, if any, should be the next open extruder port +#if NUM_Z_STEPPER_DRIVERS >= 2 + #ifndef Z2_STEP_PIN + #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) + #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) + #define Z2_ENABLE_PIN _EPIN(Z2_E_INDEX, ENABLE) + #if Z2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z2_STEP) + #error "No E stepper plug left for Z2!" + #endif + #endif + #ifndef Z2_MS1_PIN + #define Z2_MS1_PIN _EPIN(Z2_E_INDEX, MS1) + #endif + #ifndef Z2_MS2_PIN + #define Z2_MS2_PIN _EPIN(Z2_E_INDEX, MS2) + #endif + #ifndef Z2_MS3_PIN + #define Z2_MS3_PIN _EPIN(Z2_E_INDEX, MS3) + #endif + #if AXIS_HAS_SPI(Z2) && !defined(Z2_CS_PIN) + #define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS) + #endif + #if AXIS_HAS_UART(Z2) + #ifndef Z2_SERIAL_TX_PIN + #define Z2_SERIAL_TX_PIN _EPIN(Z2_E_INDEX, SERIAL_TX) + #endif + #ifndef Z2_SERIAL_RX_PIN + #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z2, X_MIN) + #define Z2_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z2, Y_MIN) + #define Z2_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z2, Z_MIN) + #define Z2_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z2, X_MAX) + #define Z2_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z2, Y_MAX) + #define Z2_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z2, Z_MAX) + #define Z2_USE_ENDSTOP _ZMAX_ + #else + #define _Z2_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z2_USE_ENDSTOP _Z2_USE_ENDSTOP(Z2_E_INDEX) + #endif + #undef Z2_DIAG_PIN + #endif + #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) +#else + #define Z3_E_INDEX Z2_E_INDEX +#endif + +#ifndef Z2_CS_PIN + #define Z2_CS_PIN -1 +#endif +#ifndef Z2_MS1_PIN + #define Z2_MS1_PIN -1 +#endif +#ifndef Z2_MS2_PIN + #define Z2_MS2_PIN -1 +#endif +#ifndef Z2_MS3_PIN + #define Z2_MS3_PIN -1 +#endif + +#if NUM_Z_STEPPER_DRIVERS >= 3 + #ifndef Z3_STEP_PIN + #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) + #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) + #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE) + #if Z3_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z3_STEP) + #error "No E stepper plug left for Z3!" + #endif + #endif + #if AXIS_HAS_SPI(Z3) + #ifndef Z3_CS_PIN + #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) + #endif + #endif + #ifndef Z3_MS1_PIN + #define Z3_MS1_PIN _EPIN(Z3_E_INDEX, MS1) + #endif + #ifndef Z3_MS2_PIN + #define Z3_MS2_PIN _EPIN(Z3_E_INDEX, MS2) + #endif + #ifndef Z3_MS3_PIN + #define Z3_MS3_PIN _EPIN(Z3_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(Z3) + #ifndef Z3_SERIAL_TX_PIN + #define Z3_SERIAL_TX_PIN _EPIN(Z3_E_INDEX, SERIAL_TX) + #endif + #ifndef Z3_SERIAL_RX_PIN + #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z3, X_MIN) + #define Z3_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z3, Y_MIN) + #define Z3_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z3, Z_MIN) + #define Z3_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z3, X_MAX) + #define Z3_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z3, Y_MAX) + #define Z3_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z3, Z_MAX) + #define Z3_USE_ENDSTOP _ZMAX_ + #else + #define _Z3_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z3_USE_ENDSTOP _Z3_USE_ENDSTOP(Z3_E_INDEX) + #endif + #undef Z3_DIAG_PIN + #endif + #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) +#endif + +#ifndef Z3_CS_PIN + #define Z3_CS_PIN -1 +#endif +#ifndef Z3_MS1_PIN + #define Z3_MS1_PIN -1 +#endif +#ifndef Z3_MS2_PIN + #define Z3_MS2_PIN -1 +#endif +#ifndef Z3_MS3_PIN + #define Z3_MS3_PIN -1 +#endif + +#if NUM_Z_STEPPER_DRIVERS >= 4 + #ifndef Z4_STEP_PIN + #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) + #define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR) + #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE) + #if Z4_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z4_STEP) + #error "No E stepper plug left for Z4!" + #endif + #endif + #if AXIS_HAS_SPI(Z4) + #ifndef Z4_CS_PIN + #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) + #endif + #endif + #ifndef Z4_MS1_PIN + #define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1) + #endif + #ifndef Z4_MS2_PIN + #define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2) + #endif + #ifndef Z4_MS3_PIN + #define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(Z4) + #ifndef Z4_SERIAL_TX_PIN + #define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX) + #endif + #ifndef Z4_SERIAL_RX_PIN + #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) + #if DIAG_REMAPPED(Z4, X_MIN) + #define Z4_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(Z4, Y_MIN) + #define Z4_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(Z4, Z_MIN) + #define Z4_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(Z4, X_MAX) + #define Z4_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(Z4, Y_MAX) + #define Z4_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(Z4, Z_MAX) + #define Z4_USE_ENDSTOP _ZMAX_ + #else + #define _Z4_USE_ENDSTOP(P) _E##P##_DIAG_ + #define Z4_USE_ENDSTOP _Z4_USE_ENDSTOP(Z4_E_INDEX) + #endif + #undef Z4_DIAG_PIN + #endif +#endif + +#ifndef Z4_CS_PIN + #define Z4_CS_PIN -1 +#endif +#ifndef Z4_MS1_PIN + #define Z4_MS1_PIN -1 +#endif +#ifndef Z4_MS2_PIN + #define Z4_MS2_PIN -1 +#endif +#ifndef Z4_MS3_PIN + #define Z4_MS3_PIN -1 +#endif + // // Disable unused endstop / probe pins // @@ -520,387 +906,9 @@ #undef Z4_MAX_PIN #endif -#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 - #define LCD_PINS_D4 -1 -#endif - -#if HAS_MARLINUI_HD44780 || TOUCH_UI_ULTIPANEL - #ifndef LCD_PINS_D5 - #define LCD_PINS_D5 -1 - #endif - #ifndef LCD_PINS_D6 - #define LCD_PINS_D6 -1 - #endif - #ifndef LCD_PINS_D7 - #define LCD_PINS_D7 -1 - #endif -#endif - -/** - * Auto-Assignment for Dual X, Dual Y, Multi-Z Steppers - * - * By default X2 is assigned to the next open E plug - * on the board, then in order, Y2, Z2, Z3. These can be - * overridden in Configuration.h or Configuration_adv.h. - */ - -#define __PEXI(p,q) PIN_EXISTS(E##p##_##q) -#define _PEXI(p,q) __PEXI(p,q) -#define __EPIN(p,q) E##p##_##q##_PIN -#define _EPIN(p,q) __EPIN(p,q) -#define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) - -// The X2 axis, if any, should be the next open extruder port -#define X2_E_INDEX E_STEPPERS - -#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) - #ifndef X2_STEP_PIN - #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) - #define X2_DIR_PIN _EPIN(X2_E_INDEX, DIR) - #define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE) - #if X2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(X2_STEP) - #error "No E stepper plug left for X2!" - #endif - #endif - #ifndef X2_MS1_PIN - #define X2_MS1_PIN _EPIN(X2_E_INDEX, MS1) - #endif - #ifndef X2_MS2_PIN - #define X2_MS2_PIN _EPIN(X2_E_INDEX, MS2) - #endif - #ifndef X2_MS3_PIN - #define X2_MS3_PIN _EPIN(X2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(X2) && !defined(X2_CS_PIN) - #define X2_CS_PIN _EPIN(X2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(X2) - #ifndef X2_SERIAL_TX_PIN - #define X2_SERIAL_TX_PIN _EPIN(X2_E_INDEX, SERIAL_TX) - #endif - #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN _EPIN(X2_E_INDEX, SERIAL_RX) - #endif - #endif - - // - // Auto-assign pins for stallGuard sensorless homing - // - #if defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) - #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) - #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... - #define X2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(X2, Y_MIN) - #define X2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(X2, Z_MIN) - #define X2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(X2, X_MAX) - #define X2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(X2, Y_MAX) - #define X2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(X2, Z_MAX) - #define X2_USE_ENDSTOP _ZMAX_ - #else // Otherwise use the driver DIAG_PIN directly - #define _X2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define X2_USE_ENDSTOP _X2_USE_ENDSTOP(X2_E_INDEX) - #endif - #undef X2_DIAG_PIN - #endif - - #define Y2_E_INDEX INCREMENT(X2_E_INDEX) -#else - #define Y2_E_INDEX X2_E_INDEX -#endif - -#ifndef X2_CS_PIN - #define X2_CS_PIN -1 -#endif -#ifndef X2_MS1_PIN - #define X2_MS1_PIN -1 -#endif -#ifndef X2_MS2_PIN - #define X2_MS2_PIN -1 -#endif -#ifndef X2_MS3_PIN - #define X2_MS3_PIN -1 -#endif - -// The Y2 axis, if any, should be the next open extruder port -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) - #ifndef Y2_STEP_PIN - #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) - #define Y2_DIR_PIN _EPIN(Y2_E_INDEX, DIR) - #define Y2_ENABLE_PIN _EPIN(Y2_E_INDEX, ENABLE) - #if Y2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Y2_STEP) - #error "No E stepper plug left for Y2!" - #endif - #endif - #ifndef Y2_MS1_PIN - #define Y2_MS1_PIN _EPIN(Y2_E_INDEX, MS1) - #endif - #ifndef Y2_MS2_PIN - #define Y2_MS2_PIN _EPIN(Y2_E_INDEX, MS2) - #endif - #ifndef Y2_MS3_PIN - #define Y2_MS3_PIN _EPIN(Y2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(Y2) && !defined(Y2_CS_PIN) - #define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(Y2) - #ifndef Y2_SERIAL_TX_PIN - #define Y2_SERIAL_TX_PIN _EPIN(Y2_E_INDEX, SERIAL_TX) - #endif - #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) - #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) - #if DIAG_REMAPPED(Y2, X_MIN) - #define Y2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Y2, Y_MIN) - #define Y2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Y2, Z_MIN) - #define Y2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Y2, X_MAX) - #define Y2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Y2, Y_MAX) - #define Y2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Y2, Z_MAX) - #define Y2_USE_ENDSTOP _ZMAX_ - #else - #define _Y2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Y2_USE_ENDSTOP _Y2_USE_ENDSTOP(Y2_E_INDEX) - #endif - #undef Y2_DIAG_PIN - #endif - #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) -#else - #define Z2_E_INDEX Y2_E_INDEX -#endif - -#ifndef Y2_CS_PIN - #define Y2_CS_PIN -1 -#endif -#ifndef Y2_MS1_PIN - #define Y2_MS1_PIN -1 -#endif -#ifndef Y2_MS2_PIN - #define Y2_MS2_PIN -1 -#endif -#ifndef Y2_MS3_PIN - #define Y2_MS3_PIN -1 -#endif - -// The Z2 axis, if any, should be the next open extruder port -#if NUM_Z_STEPPER_DRIVERS >= 2 - #ifndef Z2_STEP_PIN - #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) - #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) - #define Z2_ENABLE_PIN _EPIN(Z2_E_INDEX, ENABLE) - #if Z2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z2_STEP) - #error "No E stepper plug left for Z2!" - #endif - #endif - #ifndef Z2_MS1_PIN - #define Z2_MS1_PIN _EPIN(Z2_E_INDEX, MS1) - #endif - #ifndef Z2_MS2_PIN - #define Z2_MS2_PIN _EPIN(Z2_E_INDEX, MS2) - #endif - #ifndef Z2_MS3_PIN - #define Z2_MS3_PIN _EPIN(Z2_E_INDEX, MS3) - #endif - #if AXIS_HAS_SPI(Z2) && !defined(Z2_CS_PIN) - #define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS) - #endif - #if AXIS_HAS_UART(Z2) - #ifndef Z2_SERIAL_TX_PIN - #define Z2_SERIAL_TX_PIN _EPIN(Z2_E_INDEX, SERIAL_TX) - #endif - #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) - #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z2, X_MIN) - #define Z2_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z2, Y_MIN) - #define Z2_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z2, Z_MIN) - #define Z2_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z2, X_MAX) - #define Z2_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z2, Y_MAX) - #define Z2_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z2, Z_MAX) - #define Z2_USE_ENDSTOP _ZMAX_ - #else - #define _Z2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z2_USE_ENDSTOP _Z2_USE_ENDSTOP(Z2_E_INDEX) - #endif - #undef Z2_DIAG_PIN - #endif - #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) -#else - #define Z3_E_INDEX Z2_E_INDEX -#endif - -#ifndef Z2_CS_PIN - #define Z2_CS_PIN -1 -#endif -#ifndef Z2_MS1_PIN - #define Z2_MS1_PIN -1 -#endif -#ifndef Z2_MS2_PIN - #define Z2_MS2_PIN -1 -#endif -#ifndef Z2_MS3_PIN - #define Z2_MS3_PIN -1 -#endif - -#if NUM_Z_STEPPER_DRIVERS >= 3 - #ifndef Z3_STEP_PIN - #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) - #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) - #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE) - #if Z3_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z3_STEP) - #error "No E stepper plug left for Z3!" - #endif - #endif - #if AXIS_HAS_SPI(Z3) - #ifndef Z3_CS_PIN - #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) - #endif - #endif - #ifndef Z3_MS1_PIN - #define Z3_MS1_PIN _EPIN(Z3_E_INDEX, MS1) - #endif - #ifndef Z3_MS2_PIN - #define Z3_MS2_PIN _EPIN(Z3_E_INDEX, MS2) - #endif - #ifndef Z3_MS3_PIN - #define Z3_MS3_PIN _EPIN(Z3_E_INDEX, MS3) - #endif - #if AXIS_HAS_UART(Z3) - #ifndef Z3_SERIAL_TX_PIN - #define Z3_SERIAL_TX_PIN _EPIN(Z3_E_INDEX, SERIAL_TX) - #endif - #ifndef Z3_SERIAL_RX_PIN - #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) - #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z3, X_MIN) - #define Z3_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z3, Y_MIN) - #define Z3_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z3, Z_MIN) - #define Z3_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z3, X_MAX) - #define Z3_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z3, Y_MAX) - #define Z3_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z3, Z_MAX) - #define Z3_USE_ENDSTOP _ZMAX_ - #else - #define _Z3_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z3_USE_ENDSTOP _Z3_USE_ENDSTOP(Z3_E_INDEX) - #endif - #undef Z3_DIAG_PIN - #endif - #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) -#endif - -#ifndef Z3_CS_PIN - #define Z3_CS_PIN -1 -#endif -#ifndef Z3_MS1_PIN - #define Z3_MS1_PIN -1 -#endif -#ifndef Z3_MS2_PIN - #define Z3_MS2_PIN -1 -#endif -#ifndef Z3_MS3_PIN - #define Z3_MS3_PIN -1 -#endif - -#if NUM_Z_STEPPER_DRIVERS >= 4 - #ifndef Z4_STEP_PIN - #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) - #define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR) - #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE) - #if Z4_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z4_STEP) - #error "No E stepper plug left for Z4!" - #endif - #endif - #if AXIS_HAS_SPI(Z4) - #ifndef Z4_CS_PIN - #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) - #endif - #endif - #ifndef Z4_MS1_PIN - #define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1) - #endif - #ifndef Z4_MS2_PIN - #define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2) - #endif - #ifndef Z4_MS3_PIN - #define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3) - #endif - #if AXIS_HAS_UART(Z4) - #ifndef Z4_SERIAL_TX_PIN - #define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX) - #endif - #ifndef Z4_SERIAL_RX_PIN - #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) - #endif - #endif - #if defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) - #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) - #if DIAG_REMAPPED(Z4, X_MIN) - #define Z4_USE_ENDSTOP _XMIN_ - #elif DIAG_REMAPPED(Z4, Y_MIN) - #define Z4_USE_ENDSTOP _YMIN_ - #elif DIAG_REMAPPED(Z4, Z_MIN) - #define Z4_USE_ENDSTOP _ZMIN_ - #elif DIAG_REMAPPED(Z4, X_MAX) - #define Z4_USE_ENDSTOP _XMAX_ - #elif DIAG_REMAPPED(Z4, Y_MAX) - #define Z4_USE_ENDSTOP _YMAX_ - #elif DIAG_REMAPPED(Z4, Z_MAX) - #define Z4_USE_ENDSTOP _ZMAX_ - #else - #define _Z4_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z4_USE_ENDSTOP _Z4_USE_ENDSTOP(Z4_E_INDEX) - #endif - #undef Z4_DIAG_PIN - #endif -#endif - -#ifndef Z4_CS_PIN - #define Z4_CS_PIN -1 -#endif -#ifndef Z4_MS1_PIN - #define Z4_MS1_PIN -1 -#endif -#ifndef Z4_MS2_PIN - #define Z4_MS2_PIN -1 -#endif -#ifndef Z4_MS3_PIN - #define Z4_MS3_PIN -1 -#endif - +// +// Default DOGLCD SPI delays +// #if HAS_MARLINUI_U8GLIB #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 From d099cb3b5a301c3fd4b7e61ba0cdf81644cdef7c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Roman=20Morav=C4=8D=C3=ADk?= Date: Wed, 2 Jun 2021 04:10:15 +0200 Subject: [PATCH 0187/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Slovak=20lang?= =?UTF-8?q?uage=20(#22000)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_sk.h | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 2e851842e4..4b3ce5aa96 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -81,7 +81,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Ďalší bod"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Vyrovnanie hotové!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Výška rovnania"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastaviť ofsety"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastav. dom. ofsety"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Asist. vyrovnanie"); @@ -114,12 +117,15 @@ namespace Language_sk { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Výkon vretena"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Prepnúť laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Prepnúť ofuk"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test. impulz ms"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Vystreliť impulz"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Chyba chladenia"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Prepnúť vreteno"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Dopredný chod"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spätný chod"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnúť napájanie"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Vypnúť napájanie"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Vytlačiť (extr.)"); @@ -160,6 +166,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmerajte"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Odstráňte a zmerajte"); @@ -276,6 +283,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Chladen. lasera"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Prepnúť chladenie"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Bezpeč. prietok"); + PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Rýchlosť vent. ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); @@ -472,6 +483,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Ochladz. zlyhalo"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); @@ -487,6 +500,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Ochladz. sondy..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Ohrev komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Ochladz. komory..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Ochladz. lasera..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrácia"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovať X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovať Y"); @@ -506,6 +520,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineárne rovnanie"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mriežka dokončená"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Štatistika"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. o doske"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -683,4 +698,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Pravý dolný"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrácia dokončená"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); } From 0987c3a3a3001279b6cca930ccb764dfb719652a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 2 Jun 2021 02:53:34 +0000 Subject: [PATCH 0188/2168] [cron] Bump distribution date (2021-06-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 32fc8c23d6..e8a8586dcd 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 "2021-06-01" + #define STRING_DISTRIBUTION_DATE "2021-06-02" #endif /** From 62a595750dd0ba01c3acf03c1f6e495ed9f0f6cb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 1 Jun 2021 22:46:35 -0500 Subject: [PATCH 0189/2168] =?UTF-8?q?=F0=9F=94=A7=20Treat=20TPARA=20like?= =?UTF-8?q?=20SCARA=20in=20mfconfig?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/git/mfconfig | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index 592ecfa603..fb48d6b5a4 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -52,7 +52,7 @@ if [[ $ACTION == "manual" ]]; then git checkout $IMPORT || exit # Reset from the latest complete state - #git reset --hard master + #git reset --hard bugfix-2.0.x cp "$MARLINREPO/Marlin/"Configuration*.h "$CDEF/" #git add . && git commit -m "Changes from Marlin ($(date '+%Y-%m-%d %H:%M'))." @@ -99,8 +99,8 @@ if [[ $ACTION == "init" ]]; then # DEBUG: Commit the original config files for comparison ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Commit for comparison" >/dev/null - # Init Cartesian configurations to default - echo "- Initializing configs to default state..." + # Init Cartesian/SCARA/TPARA configurations to default + echo "- Initializing Cartesian/SCARA/TPARA configs to default state..." find "$CEXA" -name $BC ! -path */delta/* -print0 \ | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done @@ -108,7 +108,7 @@ if [[ $ACTION == "init" ]]; then | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done # DEBUG: Commit the reset for review - ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Cartesian/SCARA configs..." >/dev/null + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Cartesian/SCARA/TPARA configs..." >/dev/null # Create base Delta configurations cp "$CDEF"/* "$CEXA/delta/generic" @@ -121,23 +121,33 @@ if [[ $ACTION == "init" ]]; then # DEBUG: Commit Generic Delta changes for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Apply Generic Delta..." >/dev/null + # Reset all Delta configs to the generic version find "$CEXA/delta" -name $BC ! -path */generic/* -print0 \ | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$BC" "$F" ; done find "$CEXA/delta" -name $AC ! -path */generic/* -print0 \ | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$AC" "$F" ; done - # DEBUG: Commit the reset for review + # DEBUG: Commit the Delta reset for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Delta configs..." >/dev/null - # SCARA configurations + # Reset all SCARA configs to the default cartesian find "$CEXA/SCARA" -name $BC \ | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done find "$CEXA/SCARA" -name $AC \ | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done - # DEBUG: Commit the reset for review or... + # DEBUG: Commit the SCARA reset for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset SCARA..." >/dev/null + # Reset all TPARA configs to the default cartesian + find "$CEXA/TPARA" -name $BC \ + | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done + find "$CEXA/TPARA" -name $AC \ + | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done + + # DEBUG: Commit the TPARA reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset TPARA..." >/dev/null + # Update the %VERSION% in the README.md file SED=$(which gsed || which sed) VERS=$( echo $EXPORT | $SED 's/release-//' ) From 5ceccc95a88b1aa206a6677062d78cbb19a38c93 Mon Sep 17 00:00:00 2001 From: hannesweisbach Date: Wed, 2 Jun 2021 06:20:47 +0200 Subject: [PATCH 0190/2168] =?UTF-8?q?=E2=9C=A8=20TMC=20Driver=20distinct?= =?UTF-8?q?=20baudrates=20(#22008)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper/trinamic.cpp | 51 +++++++++++++++++++++++++- 1 file changed, 50 insertions(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 5acc860787..dab60e42a2 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -131,6 +131,55 @@ enum StealthIndex : uint8_t { #define TMC_BAUD_RATE TERN(HAS_TMC_SW_SERIAL, 57600, 115200) #endif +#ifndef TMC_X_BAUD_RATE + #define TMC_X_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_X2_BAUD_RATE + #define TMC_X2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y_BAUD_RATE + #define TMC_Y_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y2_BAUD_RATE + #define TMC_Y2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z_BAUD_RATE + #define TMC_Z_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z2_BAUD_RATE + #define TMC_Z2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z3_BAUD_RATE + #define TMC_Z3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z4_BAUD_RATE + #define TMC_Z4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E0_BAUD_RATE + #define TMC_E0_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E1_BAUD_RATE + #define TMC_E1_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E2_BAUD_RATE + #define TMC_E2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E3_BAUD_RATE + #define TMC_E3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E4_BAUD_RATE + #define TMC_E4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E5_BAUD_RATE + #define TMC_E5_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E6_BAUD_RATE + #define TMC_E6_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E7_BAUD_RATE + #define TMC_E7_BAUD_RATE TMC_BAUD_RATE +#endif + #if HAS_DRIVER(TMC2130) template void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { @@ -366,7 +415,7 @@ enum StealthIndex : uint8_t { } sp_helper; #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ - A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) + A##_HARDWARE_SERIAL.begin(TMC_##A##_BAUD_RATE); }while(0) #endif #if AXIS_HAS_UART(X) From c207111cc6aababfb1e617b7790d10af48233a25 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 1 Jun 2021 23:24:20 -0500 Subject: [PATCH 0191/2168] =?UTF-8?q?=F0=9F=94=A8=20Move=20FLY=5FMINI=20en?= =?UTF-8?q?v=20to=20stm32f1.ini?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 14 ++++++++++++++ ini/stm32f4.ini | 14 -------------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 6a234bdc97..722f80c462 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -381,6 +381,20 @@ board = genericSTM32F103RC extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +# +# FLY MINI (STM32F103RCT6) +# +[env:FLY_MINI] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +board_build.address = 0x08005000 +board_build.ldscript = fly_mini.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 + # # JGAurora A5S A1 (STM32F103ZET6) # diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 5d6d291182..087a446ede 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -68,20 +68,6 @@ build_flags = ${common_stm32.build_flags} extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -# -# FLY MINI (STM32F103RCT6) -# -[env:FLY_MINI] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -board_build.address = 0x08005000 -board_build.ldscript = fly_mini.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 - # # FYSETC S6 (STM32F446RET6 ARM Cortex-M4) # From 08155b4875fdb08f1888cacae6e1b68b48b9e51f Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 2 Jun 2021 18:42:15 +1200 Subject: [PATCH 0192/2168] =?UTF-8?q?=F0=9F=94=A8=20Creality=20v4=20with?= =?UTF-8?q?=20STM32=20HAL=20(#21999)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - New STM32 env for Creality V4 boards. - Separate Libmaple targets into their own `ini` file. - Temporarily remove unusable targets from `pins.h`. Co-authored-by: ellensp Co-authored-by: Scott Lahteine --- .github/workflows/test-builds.yml | 22 +- Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp | 82 ++++ Marlin/src/HAL/STM32/eeprom_if_iic.cpp | 54 +++ Marlin/src/libs/BL24CXX.cpp | 16 +- Marlin/src/pins/pins.h | 30 +- Marlin/src/pins/stm32f1/env_validate.h | 2 +- .../share/PlatformIO/scripts/mks_encrypt.py | 4 +- buildroot/tests/STM32F103RC_btt_USB | 2 +- ...tt_USB_stm32 => STM32F103RC_btt_USB_maple} | 4 +- ...F103RC_btt_stm32 => STM32F103RC_btt_maple} | 2 +- buildroot/tests/mks_robin | 13 +- buildroot/tests/mks_robin_maple | 22 + buildroot/tests/mks_robin_nano35 | 41 +- buildroot/tests/mks_robin_nano35_maple | 68 +++ buildroot/tests/mks_robin_nano35_stm32 | 67 --- buildroot/tests/mks_robin_stm32 | 13 - ini/stm32f1-maple.ini | 363 ++++++++++++++++ ini/stm32f1.ini | 391 ++---------------- platformio.ini | 1 + 19 files changed, 692 insertions(+), 505 deletions(-) create mode 100644 Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp create mode 100644 Marlin/src/HAL/STM32/eeprom_if_iic.cpp rename buildroot/tests/{STM32F103RC_btt_USB_stm32 => STM32F103RC_btt_USB_maple} (71%) rename buildroot/tests/{STM32F103RC_btt_stm32 => STM32F103RC_btt_maple} (84%) create mode 100755 buildroot/tests/mks_robin_maple create mode 100755 buildroot/tests/mks_robin_nano35_maple delete mode 100755 buildroot/tests/mks_robin_nano35_stm32 delete mode 100755 buildroot/tests/mks_robin_stm32 create mode 100644 ini/stm32f1-maple.ini diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 979f56cb6a..fd945b0f2a 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -56,29 +56,31 @@ jobs: # STM32F1 (Maple) Environments - - STM32F103RC_btt - - STM32F103RC_btt_USB - - STM32F103RE_btt - - STM32F103RE_btt_USB + #- STM32F103RC_btt_maple + - STM32F103RC_btt_USB_maple - STM32F103RC_fysetc - STM32F103RC_meeb - jgaurora_a5s_a1 - STM32F103VE_longer - - mks_robin + #- mks_robin_maple - mks_robin_lite - mks_robin_pro - - STM32F103RET6_creality - - mks_robin_nano35 + #- mks_robin_nano35_maple + #- STM32F103RET6_creality_maple # STM32 (ST) Environments - - STM32F103RC_btt_stm32 + - STM32F103RC_btt + #- STM32F103RC_btt_USB + - STM32F103RE_btt + - STM32F103RE_btt_USB + - STM32F103RET6_creality - STM32F407VE_black - STM32F401VE_STEVAL - BIGTREE_BTT002 - BIGTREE_SKR_PRO - BIGTREE_GTR_V1_0 - - mks_robin_stm32 + - mks_robin - ARMED - FYSETC_S6 - STM32F070CB_malyan @@ -88,7 +90,7 @@ jobs: - rumba32 - LERDGEX - LERDGEK - - mks_robin_nano35_stm32 + - mks_robin_nano35 - NUCLEO_F767ZI - REMRAM_V1 - BTT_SKR_SE_BX diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp new file mode 100644 index 0000000000..165b3c6bab --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp @@ -0,0 +1,82 @@ +/** + * 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 . + * + */ +#ifdef STM32F1 + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +// +// PersistentStore +// + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t * const p = (uint8_t * const)pos; + uint8_t c = eeprom_read_byte(p); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp new file mode 100644 index 0000000000..5c6cc802a6 --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp @@ -0,0 +1,54 @@ +/** + * 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 . + * + */ + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ + +#ifdef STM32F1 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../libs/BL24CXX.h" +#include "../shared/eeprom_if.h" + +void eeprom_init() { BL24CXX::init(); } + +// ------------------------ +// Public functions +// ------------------------ + +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // STM32F1 diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 8de320d576..adcd5ed894 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -27,7 +27,12 @@ */ #include "BL24CXX.h" -#include +#ifdef __STM32F1__ + #include +#else + #include "../HAL/shared/Delay.h" + #define delay_us(n) DELAY_US(n) +#endif #ifndef EEPROM_WRITE_DELAY #define EEPROM_WRITE_DELAY 10 @@ -37,8 +42,13 @@ #endif // IO direction setting -#define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) -#define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#ifdef __STM32F1__ + #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) + #define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#elif STM32F1 + #define SDA_IN() SET_INPUT(IIC_EEPROM_SDA) + #define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA) +#endif // IO ops #define IIC_SCL_0() WRITE(IIC_EEPROM_SCL, LOW) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3176b5e832..b4c79b3226 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -489,13 +489,13 @@ #elif MB(CHITU3D) #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103RE #elif MB(MKS_ROBIN) - #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_stm32 + #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple #elif MB(MKS_ROBIN_MINI) #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini #elif MB(MKS_ROBIN_NANO) - #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_stm32 + #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_NANO_V2) - #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_stm32 + #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_LITE) #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite #elif MB(MKS_ROBIN_LITE3) @@ -513,17 +513,17 @@ #elif MB(MKS_ROBIN_E3P) #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_2) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_MINI_E3_V2_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_MINI_MZ_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_E3_DIP) - #include "stm32f1/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 + #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K #elif MB(BTT_SKR_CR6) #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB #elif MB(JGAURORA_A5S_A1) @@ -543,17 +543,17 @@ #elif MB(CHITU3D_V6) #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 #elif MB(CREALITY_V4) - #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) - #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V427) - #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V431) - #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V452) - #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V453) - #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(TRIGORILLA_PRO) #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro #elif MB(FLY_MINI) diff --git a/Marlin/src/pins/stm32f1/env_validate.h b/Marlin/src/pins/stm32f1/env_validate.h index 62ccf7edcc..2e7b785172 100644 --- a/Marlin/src/pins/stm32f1/env_validate.h +++ b/Marlin/src/pins/stm32f1/env_validate.h @@ -21,6 +21,6 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) +#if NOT_TARGET(__STM32F1__, STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py index 0c622704e7..59322a6388 100644 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ b/buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -2,9 +2,9 @@ # buildroot/share/PlatformIO/scripts/mks_encrypt.py # # Apply encryption and save as 'build.firmware' for these environments: -# - env:mks_robin_stm32 +# - env:mks_robin # - env:flsun_hispeedv1 -# - env:mks_robin_nano35_stm32 +# - env:mks_robin_nano35 # Import("env") diff --git a/buildroot/tests/STM32F103RC_btt_USB b/buildroot/tests/STM32F103RC_btt_USB index fb0f2f5bd2..8381de0ea6 100755 --- a/buildroot/tests/STM32F103RC_btt_USB +++ b/buildroot/tests/STM32F103RC_btt_USB @@ -10,7 +10,7 @@ set -e # Build with the default configurations # restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 BAUDRATE_2 115200 +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" # clean up diff --git a/buildroot/tests/STM32F103RC_btt_USB_stm32 b/buildroot/tests/STM32F103RC_btt_USB_maple similarity index 71% rename from buildroot/tests/STM32F103RC_btt_USB_stm32 rename to buildroot/tests/STM32F103RC_btt_USB_maple index 8381de0ea6..eeb460911a 100755 --- a/buildroot/tests/STM32F103RC_btt_USB_stm32 +++ b/buildroot/tests/STM32F103RC_btt_USB_maple @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) +# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) with LibMaple STM32F1 HAL # # exit on first failure @@ -10,7 +10,7 @@ set -e # Build with the default configurations # restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 BAUDRATE_2 115200 exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" # clean up diff --git a/buildroot/tests/STM32F103RC_btt_stm32 b/buildroot/tests/STM32F103RC_btt_maple similarity index 84% rename from buildroot/tests/STM32F103RC_btt_stm32 rename to buildroot/tests/STM32F103RC_btt_maple index e76060aee8..e74e590213 100755 --- a/buildroot/tests/STM32F103RC_btt_stm32 +++ b/buildroot/tests/STM32F103RC_btt_maple @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) +# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) with LibMaple STM32F1 HAL # # exit on first failure diff --git a/buildroot/tests/mks_robin b/buildroot/tests/mks_robin index 652147f867..e250dceca2 100755 --- a/buildroot/tests/mks_robin +++ b/buildroot/tests/mks_robin @@ -1,22 +1,13 @@ #!/usr/bin/env bash # -# Build tests for MKS Robin -# (STM32F1 genericSTM32F103ZE) +# Build tests for MKS Robin (HAL/STM32) # # exit on first failure set -e use_example_configs Mks/Robin -exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" - -# -# MKS Robin LVGL FSMC -# -use_example_configs Mks/Robin -opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -opt_enable TFT_LVGL_UI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" +exec_test $1 $2 "MKS Robin base configuration" "$3" # cleanup restore_configs diff --git a/buildroot/tests/mks_robin_maple b/buildroot/tests/mks_robin_maple new file mode 100755 index 0000000000..fcb5118307 --- /dev/null +++ b/buildroot/tests/mks_robin_maple @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103ZE) +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin +exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" + +# +# MKS Robin LVGL FSMC +# +use_example_configs Mks/Robin +opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 index c54cd36655..0891744692 100755 --- a/buildroot/tests/mks_robin_nano35 +++ b/buildroot/tests/mks_robin_nano35 @@ -24,15 +24,24 @@ opt_disable TFT_INTERFACE_FSMC opt_enable TFT_INTERFACE_SPI exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" +# +# MKS Robin nano v1.2 LVGL FSMC +# +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + # # MKS Robin v2 nano LVGL SPI # (Robin v2 nano has no FSMC interface) # -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 -opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE -exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" # # MKS Robin v2 nano New Color UI 480x320 SPI @@ -42,27 +51,17 @@ use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -opt_enable BINARY_FILE_TRANSFER -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3" +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" # # MKS Robin v2 nano LVGL SPI + TMC # (Robin v2 nano has no FSMC interface) # -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 -opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" - -# -# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN -opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3" +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" # cleanup restore_configs diff --git a/buildroot/tests/mks_robin_nano35_maple b/buildroot/tests/mks_robin_nano35_maple new file mode 100755 index 0000000000..f1549a8103 --- /dev/null +++ b/buildroot/tests/mks_robin_nano35_maple @@ -0,0 +1,68 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin nano with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103VE) +# + +# exit on first failure +set -e + +# +# MKS Robin nano v1.2 Emulated DOGM FSMC +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" + +# +# MKS Robin v2 nano Emulated DOGM SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC +opt_enable TFT_INTERFACE_SPI +exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" + +# +# MKS Robin v2 nano LVGL SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 +opt_enable BINARY_FILE_TRANSFER +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3" + +# +# MKS Robin v2 nano LVGL SPI + TMC +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN +opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_nano35_stm32 b/buildroot/tests/mks_robin_nano35_stm32 deleted file mode 100755 index 0891744692..0000000000 --- a/buildroot/tests/mks_robin_nano35_stm32 +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin nano -# (STM32F1 genericSTM32F103VE) -# - -# exit on first failure -set -e - -# -# MKS Robin nano v1.2 Emulated DOGM FSMC -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" - -# -# MKS Robin v2 nano Emulated DOGM SPI -# (Robin v2 nano has no FSMC interface) -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC -opt_enable TFT_INTERFACE_SPI -exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" - -# -# MKS Robin nano v1.2 LVGL FSMC -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" - -# -# MKS Robin v2 nano LVGL SPI -# (Robin v2 nano has no FSMC interface) -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" - -# -# MKS Robin v2 nano New Color UI 480x320 SPI -# (Robin v2 nano has no FSMC interface) -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 -opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" - -# -# MKS Robin v2 nano LVGL SPI + TMC -# (Robin v2 nano has no FSMC interface) -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 -# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_stm32 b/buildroot/tests/mks_robin_stm32 deleted file mode 100755 index e250dceca2..0000000000 --- a/buildroot/tests/mks_robin_stm32 +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin (HAL/STM32) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -exec_test $1 $2 "MKS Robin base configuration" "$3" - -# cleanup -restore_configs diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini new file mode 100644 index 0000000000..cc9942fd75 --- /dev/null +++ b/ini/stm32f1-maple.ini @@ -0,0 +1,363 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +################################# +# +# STM32F1 Architecture with LibMaple STM32F1 HAL +# +# Naming Example: STM32F103RCT6 +# +# F : Foundation (sometimes High Performance F2/F4) +# 1 : Cortex M1 core +# 03 : Line/Features +# R : 64 or 66 pins (V:100, Z:144, I:176) +# C : 256KB Flash-memory (D:384KB, E:512KB, G:1024KB) +# T : LQFP package +# 6 : -40...85°C (7: ...105°C) +# +################################# + +# +# HAL/STM32F1 Common Environment values +# +[common_stm32f1] +platform = ststm32@~12.1 +board_build.core = maple +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py + ${common.build_flags} + -DARDUINO_ARCH_STM32 +build_unflags = -std=gnu11 -std=gnu++11 +src_filter = ${common.default_src_filter} + +lib_ignore = SPI, FreeRTOS701, FreeRTOS821 +lib_deps = ${common.lib_deps} + SoftwareSerialM +platform_packages = tool-stm32duino +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py + +# +# STM32F103RC +# +[common_STM32F103RC_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +monitor_speed = 115200 + +# +# MEEB_3DP (STM32F103RCT6 with 512K) +# +[env:STM32F103RC_meeb] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +board = marlin_MEEB_3DP +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 + -DSS_TIMER=4 + -DSTM32_FLASH_SIZE=512 + -DHSE_VALUE=12000000U + -DUSE_USB_COMPOSITE + -DVECT_TAB_OFFSET=0x2000 + -DGENERIC_BOOTLOADER +extra_scripts = ${common_stm32f1.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +lib_deps = ${common.lib_deps} + SoftwareSerialM + USBComposite for STM32F1@0.91 +custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use +debug_tool = stlink +upload_protocol = dfu + +# +# FYSETC STM32F103RC +# +[env:STM32F103RC_fysetc] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 +lib_ldf_mode = chain +debug_tool = stlink +upload_protocol = serial + +# +# BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) +# +# STM32F103RC_btt_maple ............. RCT6 with 256K +# STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) +# STM32F103RC_btt_512K_maple ........ RCT6 with 512K +# STM32F103RC_btt_512K_USB_maple .... RCT6 with 512K (USB mass storage) +# +# WARNING! If you have an SKR Mini v1.1 or an SKR Mini E3 1.0 / 1.2 / 2.0 / DIP +# and experience a printer freeze, re-flash Marlin using the regular (non-512K) +# build option. 256K chips may be re-branded 512K chips, but this means the +# upper 256K is sketchy, and failure is very likely. +# + +[env:STM32F103RC_btt_maple] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +board_build.address = 0x08007000 +board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 +monitor_speed = 115200 + +[env:STM32F103RC_btt_USB_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt_maple +build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} + USBComposite for STM32F1@0.91 + +[env:STM32F103RC_btt_512K_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt_maple +board_build.ldscript = STM32F103RC_SKR_MINI_512K.ld +board_upload.maximum_size = 524288 +build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DSTM32_FLASH_SIZE=512 + +[env:STM32F103RC_btt_512K_USB_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt_512K_maple +build_flags = ${env:STM32F103RC_btt_512K_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt_512K_maple.lib_deps} + USBComposite for STM32F1@0.91 + +# +# STM32F103RE with Unified STM32F1 HAL +# +[common_STM32F103RE] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RE +monitor_speed = 115200 + +# +# Creality (STM32F103RET6) +# +[env:STM32F103RET6_creality_maple] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RE +build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 +board_build.address = 0x08007000 +board_build.ldscript = creality.ld +extra_scripts = ${common_stm32f1.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py + buildroot/share/PlatformIO/scripts/custom_board.py +debug_tool = jlink +upload_protocol = jlink + +# +# STM32F103RE_btt ............. RET6 +# STM32F103RE_btt_USB ......... RET6 (USB mass storage) +# +[env:STM32F103RE_btt] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RE +board_build.address = 0x08007000 +board_build.ldscript = STM32F103RE_SKR_E3_DIP.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 +debug_tool = stlink +upload_protocol = stlink + +[env:STM32F103RE_btt_USB] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE_btt +build_flags = ${env:STM32F103RE_btt.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${common_stm32f1.lib_deps} + USBComposite for STM32F1@0.91 + +# +# Geeetech GTM32 (STM32F103VET6) +# +[env:STM32F103VE_GTM32] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +build_flags = ${common_stm32f1.build_flags} + -ffunction-sections -fdata-sections -nostdlib -MMD + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 + -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +upload_protocol = serial + +# +# Longer 3D board in Alfawise U20 (STM32F103VET6) +# +[env:STM32F103VE_longer] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +board_build.address = 0x08010000 +board_build.ldscript = STM32F103VE_longer.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + +# +# MKS Robin Mini (STM32F103VET6) +# +[env:mks_robin_mini] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_mini.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE + +# +# MKS Robin Nano (STM32F103VET6) +# +[env:mks_robin_nano35_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink + +# +# MKS Robin (STM32F103ZET6) +# +[env:mks_robin_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103ZE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin.py +build_flags = ${common_stm32f1.build_flags} + -DSS_TIMER=4 -DSTM32_XL_DENSITY + +# +# MKS Robin Pro (STM32F103ZET6) +# +[env:mks_robin_pro] +platform = ${common_stm32f1.platform} +extends = env:mks_robin_maple +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_pro.py + +# +# TRIGORILLA PRO (STM32F103ZET6) +# +[env:trigorilla_pro] +platform = ${common_stm32f1.platform} +extends = env:mks_robin_maple +extra_scripts = ${common_stm32f1.extra_scripts} + +# +# MKS Robin E3D (STM32F103RCT6) and +# MKS Robin E3 with TMC2209 +# +[env:mks_robin_e3] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_e3.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 + +# +# MKS Robin E3p (STM32F103VET6) +# - LVGL UI +# +[env:mks_robin_e3p] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink + +# +# MKS Robin Lite/Lite2 (STM32F103RCT6) +# +[env:mks_robin_lite] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_lite.py + +# +# MKS ROBIN LITE3 (STM32F103RCT6) +# +[env:mks_robin_lite3] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_lite3.py + +# +# JGAurora A5S A1 (STM32F103ZET6) +# +[env:jgaurora_a5s_a1] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103ZE +board_build.address = 0x0800A000 +board_build.ldscript = jgaurora_a5s_a1.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY + +# +# Malyan M200 (STM32F103CB) +# +[env:STM32F103CB_malyan] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = marlin_malyanM200 +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections + -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ +lib_ignore = ${common_stm32f1.lib_ignore} + SoftwareSerialM + +# +# Chitu boards like Tronxy X5s (STM32F103ZET6) +# +[env:chitu_f103] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = marlin_CHITU_F103 +extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/chitu_crypt.py +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + +# +# Some Chitu V5 boards have a problem with GPIO init. +# Use this target if G28 or G29 are always failing. +# +[env:chitu_v5_gpio_init] +platform = ${common_stm32f1.platform} +extends = env:chitu_f103 +build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 722f80c462..4c42922452 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -5,7 +5,7 @@ ################################# # -# STM32F1 Architecture +# STM32F1 Architecture with unified STM32 HAL # # Naming Example: STM32F103RCT6 # @@ -32,71 +32,6 @@ build_flags = ${common.build_flags} build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + + -# -# HAL/STM32F1 Common Environment values -# -[common_stm32f1] -platform = ststm32@~12.1 -board_build.core = maple -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} - -DARDUINO_ARCH_STM32 -build_unflags = -std=gnu11 -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_ignore = SPI, FreeRTOS701, FreeRTOS821 -lib_deps = ${common.lib_deps} - SoftwareSerialM -platform_packages = tool-stm32duino -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py - -# -# STM32F103RC -# -[env:STM32F103RC] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -monitor_speed = 115200 - -# -# MEEB_3DP (STM32F103RCT6 with 512K) -# -[env:STM32F103RC_meeb] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_MEEB_3DP -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 - -DSS_TIMER=4 - -DSTM32_FLASH_SIZE=512 - -DHSE_VALUE=12000000U - -DUSE_USB_COMPOSITE - -DVECT_TAB_OFFSET=0x2000 - -DGENERIC_BOOTLOADER -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py -lib_deps = ${common.lib_deps} - SoftwareSerialM - USBComposite for STM32F1@0.91 -custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use -debug_tool = stlink -upload_protocol = dfu - -# -# STM32F103RC_fysetc -# -[env:STM32F103RC_fysetc] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -lib_ldf_mode = chain -debug_tool = stlink -upload_protocol = serial - # # BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) # @@ -110,44 +45,7 @@ upload_protocol = serial # build option. 256K chips may be re-branded 512K chips, but this means the # upper 256K is sketchy, and failure is very likely. # - -[env:STM32F103RC_btt] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC -board_build.address = 0x08007000 -board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 -monitor_speed = 115200 - -[env:STM32F103RC_btt_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt -build_flags = ${env:STM32F103RC_btt.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt.lib_deps} - USBComposite for STM32F1@0.91 - -[env:STM32F103RC_btt_512K] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt -board_build.ldscript = STM32F103RC_SKR_MINI_512K.ld -board_upload.maximum_size=524288 -build_flags = ${env:STM32F103RC_btt.build_flags} -DSTM32_FLASH_SIZE=512 - -[env:STM32F103RC_btt_512K_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt_512K -build_flags = ${env:STM32F103RC_btt_512K.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt_512K.lib_deps} - USBComposite for STM32F1@0.91 - -# -# STM32 HAL version of STM32F103RC_btt envs -# - -[env:STM32F103RC_stm32] +[common_STM32F103RC] platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103RC @@ -159,21 +57,21 @@ extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py -[env:STM32F103RC_btt_stm32] +[env:STM32F103RC_btt] platform = ${common_stm32.platform} -extends = env:STM32F103RC_stm32 +extends = common_STM32F103RC build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 board_build.offset = 0x7000 board_build.encrypt = No board_build.firmware = firmware.bin board_upload.offset_address = 0x08007000 -[env:STM32F103RC_btt_USB_stm32] -extends = env:STM32F103RC_btt_stm32 +[env:STM32F103RC_btt_USB] +extends = env:STM32F103RC_btt platform = ${common_stm32.platform} platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC -build_flags = ${env:STM32F103RC_btt_stm32.build_flags} ${env:stm32_flash_drive.build_flags} +build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.build_flags} -DUSBCON -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 @@ -181,122 +79,23 @@ build_flags = ${env:STM32F103RC_btt_stm32.build_flags} ${env:stm32_flash_d -DUSE_USB_HS_IN_FS -DUSBD_USE_CDC_MSC -[env:STM32F103RC_btt_512K_stm32] +[env:STM32F103RC_btt_512K] platform = ${common_stm32.platform} -extends = env:STM32F103RC_btt_stm32 +extends = env:STM32F103RC_btt board_upload.maximum_size = 524288 -build_flags = ${env:STM32F103RC_btt_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 +build_flags = ${env:STM32F103RC_btt.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 -[env:STM32F103RC_btt_512K_USB_stm32] +[env:STM32F103RC_btt_512K_USB] platform = ${common_stm32.platform} -extends = env:STM32F103RC_btt_USB_stm32 +extends = env:STM32F103RC_btt_USB board_upload.maximum_size = 524288 -build_flags = ${env:STM32F103RC_btt_USB_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 +build_flags = ${env:STM32F103RC_btt_USB.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 # -# STM32F103RE -# -[env:STM32F103RE] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RE -monitor_speed = 115200 - -# -# STM32F103RE_btt ............. RET6 -# STM32F103RE_btt_USB ......... RET6 (USB mass storage) -# -[env:STM32F103RE_btt] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RE -board_build.address = 0x08007000 -board_build.ldscript = STM32F103RE_SKR_E3_DIP.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 -debug_tool = stlink -upload_protocol = stlink - -[env:STM32F103RE_btt_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RE_btt -build_flags = ${env:STM32F103RE_btt.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${common_stm32f1.lib_deps} - USBComposite for STM32F1@0.91 - -# -# Geeetech GTM32 (STM32F103VET6) -# -[env:STM32F103VE_GTM32] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -build_flags = ${common_stm32f1.build_flags} - -ffunction-sections -fdata-sections -nostdlib -MMD - -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v - -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 - -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 -upload_protocol = serial - -# -# Longer 3D board in Alfawise U20 (STM32F103VET6) -# -[env:STM32F103VE_longer] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -board_build.address = 0x08010000 -board_build.ldscript = STM32F103VE_longer.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 - -# -# MKS Robin Mini (STM32F103VET6) -# -[env:mks_robin_mini] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_mini.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE - -# -# MKS Robin Nano (STM32F103VET6) -# -[env:mks_robin_nano35] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_nano35.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink - -# -# MKS Robin (STM32F103ZET6) -# -[env:mks_robin] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103ZE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin.py -build_flags = ${common_stm32f1.build_flags} - -DSS_TIMER=4 -DSTM32_XL_DENSITY - # MKS Robin (STM32F103ZET6) # Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel # -[env:mks_robin_stm32] +[env:mks_robin] platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103ZE @@ -316,154 +115,30 @@ extra_scripts = ${common.extra_scripts} buildroot/share/PlatformIO/scripts/mks_encrypt.py lib_deps = -# -# MKS Robin Pro (STM32F103ZET6) -# -[env:mks_robin_pro] -platform = ${common_stm32f1.platform} -extends = env:mks_robin -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_pro.py - -# -# TRIGORILLA PRO (STM32F103ZET6) -# -[env:trigorilla_pro] -platform = ${common_stm32f1.platform} -extends = env:mks_robin -extra_scripts = ${common_stm32f1.extra_scripts} - -# -# MKS Robin E3D (STM32F103RCT6) and -# MKS Robin E3 with TMC2209 -# -[env:mks_robin_e3] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 - -# -# MKS Robin E3p (STM32F103VET6) -# - LVGL UI -# -[env:mks_robin_e3p] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3p.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink - -# -# MKS Robin Lite/Lite2 (STM32F103RCT6) -# -[env:mks_robin_lite] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite.py - -# -# MKS ROBIN LITE3 (STM32F103RCT6) -# -[env:mks_robin_lite3] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite3.py - -# -# FLY MINI (STM32F103RCT6) -# -[env:FLY_MINI] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -board_build.address = 0x08005000 -board_build.ldscript = fly_mini.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 - -# -# JGAurora A5S A1 (STM32F103ZET6) -# -[env:jgaurora_a5s_a1] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103ZE -board_build.address = 0x0800A000 -board_build.ldscript = jgaurora_a5s_a1.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY - -# -# Malyan M200 (STM32F103CB) -# -[env:STM32F103CB_malyan] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_malyanM200 -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections - -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ -lib_ignore = ${common_stm32f1.lib_ignore} - SoftwareSerialM - -# -# Chitu boards like Tronxy X5s (STM32F103ZET6) -# -[env:chitu_f103] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_CHITU_F103 -extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/chitu_crypt.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 - -# -# Some Chitu V5 boards have a problem with GPIO init. -# Use this target if G28 or G29 are always failing. -# -[env:chitu_v5_gpio_init] -platform = ${common_stm32f1.platform} -extends = env:chitu_f103 -build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX - # # Creality (STM32F103RET6) # [env:STM32F103RET6_creality] -platform = ${env:STM32F103RE.platform} -extends = env:STM32F103RE -build_flags = ${env:STM32F103RE.build_flags} -DTEMP_TIMER_CHAN=4 -board_build.address = 0x08007000 -board_build.ldscript = creality.ld -extra_scripts = ${env:STM32F103RE.extra_scripts} +platform = ${common_stm32.platform} +extends = common_stm32 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +board = genericSTM32F103RE +monitor_speed = 115200 +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 +board_build.ldscript = ldscript.ld +board_upload.offset_address = 0x08007000 +build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py pre:buildroot/share/PlatformIO/scripts/random-bin.py - buildroot/share/PlatformIO/scripts/custom_board.py -debug_tool = jlink -upload_protocol = jlink + buildroot/share/PlatformIO/scripts/stm32_bootloader.py +debug_tool = jlink +upload_protocol = jlink # -# FLSUN QQS Pro (STM32F103VET6) using hal STM32 +# FLSUN QQS Pro (STM32F103VET6) # board Hispeedv1 # [env:flsun_hispeedv1] @@ -485,9 +160,9 @@ extra_scripts = ${common.extra_scripts} buildroot/share/PlatformIO/scripts/mks_encrypt.py # -# MKS Robin Nano V1.2 and V2 using hal STM32 +# MKS Robin Nano V1.2 and V2 # -[env:mks_robin_nano35_stm32] +[env:mks_robin_nano35] platform = ${common_stm32.platform} extends = common_stm32 build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 diff --git a/platformio.ini b/platformio.ini index b552eda81d..f55f5f5a93 100644 --- a/platformio.ini +++ b/platformio.ini @@ -24,6 +24,7 @@ extra_configs = ini/native.ini ini/samd51.ini ini/stm32f0.ini + ini/stm32f1-maple.ini ini/stm32f1.ini ini/stm32f4.ini ini/stm32f7.ini From dc202b3cb3c2f91e2f7dcf582da46d2182cd2782 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 2 Jun 2021 15:34:03 -0500 Subject: [PATCH 0193/2168] =?UTF-8?q?=F0=9F=8E=A8=20Clean=20up=20stops,=20?= =?UTF-8?q?sdss=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 4 +- Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 6 +-- Marlin/src/pins/ramps/pins_3DRAG.h | 11 +++-- Marlin/src/pins/ramps/pins_COPYMASTER_3D.h | 8 ++-- Marlin/src/pins/ramps/pins_K8600.h | 7 +--- Marlin/src/pins/ramps/pins_RAMPS.h | 4 +- Marlin/src/pins/sam/pins_ADSK.h | 6 +-- Marlin/src/pins/sam/pins_DUE3DOM.h | 3 -- Marlin/src/pins/sam/pins_DUE3DOM_MINI.h | 27 +++++-------- Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h | 6 +-- Marlin/src/pins/samd/pins_RAMPS_144.h | 40 +++++++++---------- Marlin/src/pins/stm32f1/pins_BEAST.h | 26 ++++-------- Marlin/src/pins/stm32f1/pins_CHITU3D.h | 31 ++++---------- Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 8 ++-- Marlin/src/pins/stm32f1/pins_MORPHEUS.h | 6 +-- Marlin/src/pins/stm32f1/pins_STM3R_MINI.h | 2 +- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 6 ++- Marlin/src/pins/teensy2/pins_PRINTRBOARD.h | 8 ++-- 18 files changed, 84 insertions(+), 125 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 0760eee0ab..5131069f6b 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -37,8 +37,8 @@ // // Limit Switches // -#define X_MIN_PIN P1_24 -#define Y_MIN_PIN P1_26 +#define X_STOP_PIN P1_24 +#define Y_STOP_PIN P1_26 #define Z_MIN_PIN P1_28 #define Z_MAX_PIN P1_29 diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 78cf7a84fc..2972ac7560 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -40,10 +40,8 @@ // #define X_MIN_PIN P1_28 #define X_MAX_PIN P1_25 -#define Y_MIN_PIN P2_11 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN P1_27 -#define Z_MAX_PIN -1 +#define Y_STOP_PIN P2_11 +#define Z_STOP_PIN P1_27 #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN P1_22 #endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 08354ce2ff..e78f7683f6 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -44,6 +44,11 @@ #define RAMPS_D9_PIN 8 #define MOSFET_D_PIN 12 +// +// Misc. Functions +// +#define SDSS 25 + #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header #endif @@ -66,12 +71,6 @@ // #define HEATER_2_PIN 6 -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 - #undef SD_DETECT_PIN #define SD_DETECT_PIN 53 diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h index b9eee6bd53..020941027a 100644 --- a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -23,10 +23,10 @@ #define BOARD_INFO_NAME "Copymaster 3D RAMPS" -#define Z_STEP_PIN 47 -#define Y_MAX_PIN 14 -#define FIL_RUNOUT_PIN 15 -#define SD_DETECT_PIN 66 +#define Z_STEP_PIN 47 +#define Y_MAX_PIN 14 +#define FIL_RUNOUT_PIN 15 +#define SD_DETECT_PIN 66 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 1a396b20f4..c2d91ad7ee 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -47,6 +47,7 @@ // // Misc. Functions // +#define SDSS 25 #define CASE_LIGHT_PIN 7 // @@ -87,12 +88,6 @@ // #undef HEATER_BED_PIN -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 // 53 - // // LCD / Controller // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index f30a235626..c2d4dbeb3f 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -241,7 +241,9 @@ // // Misc. Functions // -#define SDSS EXP2_07_PIN +#ifndef SDSS + #define SDSS EXP2_07_PIN +#endif #define LED_PIN 13 #ifndef FILWIDTH_PIN diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 9026ca7771..6fe0520f81 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -86,9 +86,9 @@ A stepper for E0 extruder // // Limit Switches // -#define X_MIN_PIN 9 -#define Y_MIN_PIN 10 -#define Z_MIN_PIN 11 +#define X_STOP_PIN 9 +#define Y_STOP_PIN 10 +#define Z_STOP_PIN 11 #define Z_MIN_PROBE_PIN 62 // Analog pin 8, Digital pin 62 diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index 4ebece58e4..de3cb33e8d 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -128,7 +128,6 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -141,8 +140,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index dd8f263676..c52199a54d 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -40,12 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 38 -#define X_MAX_PIN -1 -#define Y_MIN_PIN 34 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN -1 +#define X_STOP_PIN 38 +#define Y_STOP_PIN 34 +#define Z_STOP_PIN 30 // // Steppers @@ -120,7 +117,10 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -133,8 +133,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED @@ -143,7 +141,7 @@ #define BTN_EN2 52 #define BTN_ENC 48 #define BEEPER_PIN 41 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) @@ -158,20 +156,17 @@ #define BEEPER_PIN -1 - #elif ENABLED(MINIPANEL) + #elif ENABLED(MINIPANEL) + #define BTN_EN1 52 #define BTN_EN2 50 #define BTN_ENC 48 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #define BEEPER_PIN 41 #define DOGLCD_A0 46 #define DOGLCD_CS 45 - #endif // SPARK_FULL_GRAPHICS - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index 874950f34b..aa01a9227f 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -40,9 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 22 // PB26 -#define Y_MAX_PIN 18 // PA11 -#define Z_MIN_PIN 19 // PA10 +#define X_STOP_PIN 22 // PB26 +#define Y_STOP_PIN 18 // PA11 +#define Z_STOP_PIN 19 // PA10 // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 8311ac9012..fbd9d7c864 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -130,7 +130,6 @@ // // Misc. Functions // -#define SDSS 53 #define LED_PIN 13 #ifndef FILWIDTH_PIN @@ -252,6 +251,21 @@ #endif #endif +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SDSS 83 + #undef SD_DETECT_PIN + #define SD_DETECT_PIN 95 +#else + #define SDSS 53 +#endif + ////////////////////////// // LCDs and Controllers // ////////////////////////// @@ -356,6 +370,9 @@ #else #define BTN_EN1 31 #define BTN_EN2 33 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif #define BTN_ENC 35 @@ -365,8 +382,7 @@ #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - // TO TEST - //#define LCD_BACKLIGHT_PIN 39 + //#define LCD_BACKLIGHT_PIN 39 // TO TEST #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -563,22 +579,4 @@ #endif #endif // IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - #endif // HAS_WIRED_LCD - -// -// SD Support -// -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#if SD_CONNECTION_IS(ONBOARD) - #undef SDSS - #define SDSS 83 - #undef SD_DETECT_PIN - #define SD_DETECT_PIN 95 -#endif diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index 05f77f1029..2ace47822e 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -36,34 +36,27 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +// +// Limit Switches +// +#define X_STOP_PIN PD5 +#define Y_STOP_PIN PD6 +#define Z_STOP_PIN PD7 + // // Steppers // #define X_STEP_PIN PE0 #define X_DIR_PIN PE1 #define X_ENABLE_PIN PC0 -#define X_MIN_PIN PD5 -#define X_MAX_PIN -1 #define Y_STEP_PIN PE2 #define Y_DIR_PIN PE3 #define Y_ENABLE_PIN PC1 -#define Y_MIN_PIN PD6 -#define Y_MAX_PIN #define Z_STEP_PIN PE4 #define Z_DIR_PIN PE5 #define Z_ENABLE_PIN PC2 -#define Z_MIN_PIN PD7 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 #define E0_STEP_PIN PE6 #define E0_DIR_PIN PE7 @@ -87,9 +80,6 @@ #define SDSS PA15 #define LED_PIN PB2 -#define PS_ON_PIN -1 -#define KILL_PIN -1 - // // Heaters / Fans // @@ -98,8 +88,6 @@ #define HEATER_2_PIN PD14 #define HEATER_BED_PIN PB9 // BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN #define FAN_PIN PB10 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index dd6edf9024..c2025ba8c0 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -38,47 +38,32 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +// +// Limit Switches +// +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#define Z_STOP_PIN PA14 + // // Steppers // #define X_STEP_PIN PE5 #define X_DIR_PIN PE6 #define X_ENABLE_PIN PC13 -#define X_MIN_PIN PG10 -#define X_MAX_PIN -1 #define Y_STEP_PIN PE2 #define Y_DIR_PIN PE3 #define Y_ENABLE_PIN PE4 -#define Y_MIN_PIN PA12 -#define Y_MAX_PIN #define Z_STEP_PIN PB9 #define Z_DIR_PIN PE0 #define Z_ENABLE_PIN PE1 -#define Z_MIN_PIN PA14 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 #define E0_STEP_PIN PB4 #define E0_DIR_PIN PB5 #define E0_ENABLE_PIN PB8 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 - -#define E2_STEP_PIN -1 -#define E2_DIR_PIN -1 -#define E2_ENABLE_PIN -1 - // // Misc. Functions // @@ -114,8 +99,6 @@ // #define TEMP_BED_PIN PA0 // Analog Input #define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_2_PIN -1 // Analog Input // // LCD Pins diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index e33e029deb..32d1937653 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -41,7 +41,7 @@ #define FLASH_EEPROM_EMULATION #endif -#define SDSS SD_SS_PIN +#define SDSS SD_SS_PIN // Also in HAL/STM32F1/spi_pins.h // Based on PWM timer usage, we have to use these timers and soft PWM for the fans // On STM32F103: @@ -53,9 +53,9 @@ // // Limit Switches // -#define X_MIN_PIN PB4 -#define Y_MIN_PIN PA15 -#define Z_MIN_PIN PB5 +#define X_STOP_PIN PB4 +#define Y_STOP_PIN PA15 +#define Z_STOP_PIN PB5 // // Steppers diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index 05e02c9e4d..87919c12f4 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -39,9 +39,9 @@ // // Limit Switches // -#define X_MIN_PIN PB14 -#define Y_MIN_PIN PB13 -#define Z_MIN_PIN PB12 +#define X_STOP_PIN PB14 +#define Y_STOP_PIN PB13 +#define Z_STOP_PIN PB12 // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index d25ca1bd2e..7171de919d 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 10 Dec 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index dc02fd02ea..5f8ffe975b 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -173,7 +173,6 @@ // // Misc functions // -#define SDSS 16 // PA4 SPI_CS #define LED_PIN -1 // 9 // PE1 green LED Heart beat #define PS_ON_PIN -1 #define KILL_PIN -1 @@ -245,7 +244,6 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD - #undef SDSS #define SDSS SDIO_D3_PIN #define SD_SCK_PIN SDIO_CK_PIN #define SD_MISO_PIN SDIO_D0_PIN @@ -253,6 +251,10 @@ #endif #endif +#ifndef SDSS + #define SDSS 16 // PA4 SPI_CS +#endif + // OTG // 30 // PA11 OTG_DM // 31 // PA12 OTG_DP diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 7b3685d08e..cb038fe737 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -116,7 +116,6 @@ // // Misc. Functions // -#define SDSS 26 // B6 SDCS #define FILWIDTH_PIN 2 // Analog Input // @@ -142,7 +141,6 @@ #define BTN_EN2 3 // D3 RX1 JP2-7 #define BTN_ENC 45 // F7 TDI JP2-12 - #undef SDSS #define SDSS 43 // F5 TMS JP2-8 #define STAT_LED_RED_PIN 12 // C2 JP11-14 @@ -153,7 +151,7 @@ #define BTN_EN1 3 // D3 RX1 JP2-7 #define BTN_EN2 2 // D2 TX1 JP2-5 #define BTN_ENC 41 // F3 JP2-4 - #undef SDSS + #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 #else @@ -165,3 +163,7 @@ #endif #endif // IS_ULTRA_LCD && IS_NEWPANEL + +#ifndef SDSS + #define SDSS 26 // B6 SDCS +#endif From b99411b62b6c21aee64f5d33ef5cbee4b701dc68 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 2 Jun 2021 15:34:31 -0500 Subject: [PATCH 0194/2168] =?UTF-8?q?=F0=9F=8E=A8=20Reorganize=20BTT=5FE3?= =?UTF-8?q?=5FRRF=5FIDEX=5FBOARD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 120 +++++++++++++--------- 1 file changed, 69 insertions(+), 51 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 621b136e17..a806611c18 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -29,58 +29,9 @@ #define BOARD_INFO_NAME "BTT E3 RRF" #endif -#define FPC2_PIN PB11 -#define FPC3_PIN PB10 -#define FPC4_PIN PE12 -#define FPC5_PIN PE13 -#define FPC6_PIN PE14 -#define FPC7_PIN PE15 -#define FPC8_PIN PA3 -#define FPC9_PIN PA2 -#define FPC10_PIN PA8 -#define FPC11_PIN PC15 -#define FPC12_PIN PC14 -#define FPC13_PIN PC13 -#define FPC14_PIN PE6 -#define FPC15_PIN PE5 -#define FPC16_PIN PE4 -#define FPC17_PIN PE3 - +// Add-on board for IDEX conversion //#define BTT_E3_RRF_IDEX_BOARD -#ifdef BTT_E3_RRF_IDEX_BOARD - - #define X2_ENABLE_PIN FPC13_PIN // X2EN - #define X2_STEP_PIN FPC11_PIN // X2STP - #define X2_DIR_PIN FPC10_PIN // X2DIR - #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART - #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART - #if X_HOME_TO_MIN - #define X_MAX_PIN FPC2_PIN // X2-STOP - #else - #define X_MIN_PIN FPC2_PIN // X2-STOP - #endif - - #define E1_ENABLE_PIN FPC7_PIN // E1EN - #define E1_STEP_PIN FPC5_PIN // E1STP - #define E1_DIR_PIN FPC4_PIN // E1DIR - #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART - #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART - - #ifndef FIL1_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN FPC3_PIN // E1-STOP - #endif - - #define HEATER_1_PIN FPC16_PIN // "HE1" - - #define PT100_PIN FPC8_PIN // Analog Input "PT100"(INA826) - #define TEMP_1_PIN FPC9_PIN // Analog Input "TH1" - - #define FAN1_PIN FPC15_PIN // "FAN0" in IDEX board - #define FAN2_PIN FPC14_PIN // "FAN1" in IDEX board - -#endif - // Onboard I2C EEPROM #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4KB @@ -97,6 +48,14 @@ #define Y_STOP_PIN PC1 // Y-STOP #define Z_STOP_PIN PC2 // Z-STOP +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #if X2_USE_ENDSTOP == _XMAX_ + #define X_MAX_PIN FPC2_PIN // X2-STOP + #elif X2_USE_ENDSTOP == _XMIN_ + #define X_MIN_PIN FPC2_PIN // X2-STOP + #endif +#endif + // // Z Probe must be this pin // @@ -109,6 +68,10 @@ #define FIL_RUNOUT_PIN PC3 // E0-STOP #endif +#if !defined(FIL1_RUNOUT2_PIN) && ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FIL_RUNOUT2_PIN FPC3_PIN // E1-STOP +#endif + // // Power-loss Detection // @@ -135,6 +98,16 @@ #define E0_STEP_PIN PD12 #define E0_DIR_PIN PD13 +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define E1_ENABLE_PIN FPC7_PIN // E1EN + #define E1_STEP_PIN FPC5_PIN // E1STP + #define E1_DIR_PIN FPC4_PIN // E1DIR + + #define X2_ENABLE_PIN FPC13_PIN // X2EN + #define X2_STEP_PIN FPC11_PIN // X2STP + #define X2_DIR_PIN FPC10_PIN // X2DIR +#endif + /** * TMC2208/TMC2209 stepper drivers */ @@ -154,6 +127,14 @@ #define E0_SERIAL_TX_PIN PD11 #define E0_SERIAL_RX_PIN PD11 + #if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART + #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART + + #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART + #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART + #endif + // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif @@ -164,19 +145,37 @@ #define TEMP_BED_PIN PA1 // Analog Input "TB" #define TEMP_0_PIN PA0 // Analog Input "TH0" +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define TEMP_1_PIN FPC9_PIN // Analog Input "TH1" + #define PT100_PIN FPC8_PIN // Analog Input "PT100" (INA826) +#endif + // // Heaters / Fans // #define HEATER_BED_PIN PB4 // "HB" #define HEATER_0_PIN PB3 // "HE0" +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define HEATER_1_PIN FPC16_PIN // "HE1" +#endif + #define FAN_PIN PB5 // "FAN0" -//#define FAN1_PIN PB6 // "FAN1" #ifndef CONTROLLER_FAN_PIN #define CONTROLLER_FAN_PIN PB6 // "FAN1" #endif +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FAN1_PIN FPC15_PIN // "FAN0" in IDEX board + #define FAN2_PIN FPC14_PIN // "FAN1" in IDEX board +#else + //#define FAN1_PIN PB6 // "FAN1" +#endif + +// +// Misc. Functions +// #ifndef NEOPIXEL_PIN #define NEOPIXEL_PIN PB7 // LED driving pin #endif @@ -373,3 +372,22 @@ #define ESP_WIFI_MODULE_RESET_PIN PA4 #define ESP_WIFI_MODULE_ENABLE_PIN PA5 #define ESP_WIFI_MODULE_GPIO0_PIN PA6 + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FPC2_PIN PB11 + #define FPC3_PIN PB10 + #define FPC4_PIN PE12 + #define FPC5_PIN PE13 + #define FPC6_PIN PE14 + #define FPC7_PIN PE15 + #define FPC8_PIN PA3 + #define FPC9_PIN PA2 + #define FPC10_PIN PA8 + #define FPC11_PIN PC15 + #define FPC12_PIN PC14 + #define FPC13_PIN PC13 + #define FPC14_PIN PE6 + #define FPC15_PIN PE5 + #define FPC16_PIN PE4 + #define FPC17_PIN PE3 +#endif From 8f59d44e4d235de1eed2725bceabb87934d7ffad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 2 Jun 2021 17:09:47 -0500 Subject: [PATCH 0195/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20G61=20comment?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/pause/G61.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 14a2e64969..00a6478f3d 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -37,8 +37,7 @@ * * F - Feedrate (optional) for the move back. * S - Slot # (0-based) to restore from (default 0). - * X Y Z - Axes to restore. At least one is required. - * E - Restore extruder position + * X Y Z E - Axes to restore. At least one is required. * * If XYZE are not given, default restore uses the smart blocking move. */ From 25053572ec906be78b383165a101c37dc1284d20 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 2 Jun 2021 19:38:34 -0500 Subject: [PATCH 0196/2168] =?UTF-8?q?=F0=9F=93=8C=20Use=20U8glib-HAL@~0.4.?= =?UTF-8?q?5?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index 89df3b99fe..f8f995c69f 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -35,7 +35,7 @@ USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 HAS_WIRED_LCD = src_filter=+ HAS_MARLINUI_HD44780 = src_filter=+ -HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.4 +HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.5 src_filter=+ HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + HAS_FSMC_TFT = src_filter=+ + From a4e955d606ba2847287e8a76594f776212d10f79 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 3 Jun 2021 02:28:46 +0000 Subject: [PATCH 0197/2168] [cron] Bump distribution date (2021-06-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e8a8586dcd..a32fe681f3 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 "2021-06-02" + #define STRING_DISTRIBUTION_DATE "2021-06-03" #endif /** From 67c1075e47fa9b68bf7a89164b8e5b385c5e0be5 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 3 Jun 2021 19:40:16 +1200 Subject: [PATCH 0198/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20env:STM32F103RE?= =?UTF-8?q?=20maple/unified=20split-up=20(#22019)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #21999 --- Marlin/src/pins/pins.h | 24 ++++++++++++------------ ini/stm32f1-maple.ini | 8 ++++---- ini/stm32f1.ini | 27 +++++++++++++++++++++++++++ 3 files changed, 43 insertions(+), 16 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b4c79b3226..49d91e493a 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -469,25 +469,25 @@ // #elif MB(STM32F103RE) - #include "stm32f1/pins_STM32F1R.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM32F1R.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(MALYAN_M200) - #include "stm32f1/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan + #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan #elif MB(STM3R_MINI) - #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM3R_MINI.h" // STM32F103RE? env:STM32F103RE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) - #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VD) - #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI) - #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_REV_B) - #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(MORPHEUS) - #include "stm32f1/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MORPHEUS.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(CHITU3D) - #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_CHITU3D.h" // STM32F103ZE env:STM32F103ZE env:STM32F103RE_maple #elif MB(MKS_ROBIN) #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple #elif MB(MKS_ROBIN_MINI) @@ -561,9 +561,9 @@ #elif MB(FLSUN_HISPEED) #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) - #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103VE env:STM32F103RE_maple #elif MB(MINGDA_MPX_ARM_MINI) - #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini // // ARM Cortex-M4F diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index cc9942fd75..e58064424d 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -131,9 +131,9 @@ lib_deps = ${env:STM32F103RC_btt_512K_maple.lib_deps} USBComposite for STM32F1@0.91 # -# STM32F103RE with Unified STM32F1 HAL +# Generic STM32F103RE environment # -[common_STM32F103RE] +[env:STM32F103RE_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RE @@ -144,7 +144,7 @@ monitor_speed = 115200 # [env:STM32F103RET6_creality_maple] platform = ${common_stm32f1.platform} -extends = common_STM32F103RE +extends = env:STM32F103RE_maple build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = creality.ld @@ -160,7 +160,7 @@ upload_protocol = jlink # [env:STM32F103RE_btt] platform = ${common_stm32f1.platform} -extends = common_STM32F103RE +extends = env:STM32F103RE_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RE_SKR_E3_DIP.ld extra_scripts = ${common_stm32f1.extra_scripts} diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 4c42922452..161e59b2e3 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -57,6 +57,33 @@ extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py +# +# STM32F103RE +# +[env:STM32F103RE] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103RE +monitor_speed = 115200 + +# +# STM32F103VE +# +[env:STM32F103VE] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +monitor_speed = 115200 + +# +# STM32F103ZE +# +[env:STM32F103ZE] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +monitor_speed = 115200 + [env:STM32F103RC_btt] platform = ${common_stm32.platform} extends = common_STM32F103RC From 62dc3e7a22503702ebc4a168950510c3e125a2af Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Jun 2021 02:55:30 -0500 Subject: [PATCH 0199/2168] =?UTF-8?q?=F0=9F=94=A8=20Consolidate=20BTT=20li?= =?UTF-8?q?nker=20scripts?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Originally from #22022 --- .../PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld | 14 -------------- ...R_MINI_512K.ld => STM32F103RE_SKR_MINI_512K.ld} | 0 ini/stm32f1-maple.ini | 4 +++- 3 files changed, 3 insertions(+), 15 deletions(-) delete mode 100644 buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld rename buildroot/share/PlatformIO/ldscripts/{STM32F103RC_SKR_MINI_512K.ld => STM32F103RE_SKR_MINI_512K.ld} (100%) diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld deleted file mode 100644 index 248b7781cf..0000000000 --- a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld +++ /dev/null @@ -1,14 +0,0 @@ -MEMORY -{ - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 - rom (rx) : ORIGIN = 0x08007000, LENGTH = 512K - 28K - 4K -} - -/* Provide memory region aliases for common.inc */ -REGION_ALIAS("REGION_TEXT", rom); -REGION_ALIAS("REGION_DATA", ram); -REGION_ALIAS("REGION_BSS", ram); -REGION_ALIAS("REGION_RODATA", rom); - -/* Let common.inc handle the real work. */ -INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_512K.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld similarity index 100% rename from buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_512K.ld rename to buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index e58064424d..7a43e2d0cb 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -154,6 +154,8 @@ extra_scripts = ${common_stm32f1.extra_scripts} debug_tool = jlink upload_protocol = jlink +# +# BigTree SKR Mini E3 DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt ............. RET6 # STM32F103RE_btt_USB ......... RET6 (USB mass storage) @@ -162,7 +164,7 @@ upload_protocol = jlink platform = ${common_stm32f1.platform} extends = env:STM32F103RE_maple board_build.address = 0x08007000 -board_build.ldscript = STM32F103RE_SKR_E3_DIP.ld +board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/custom_board.py build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 From 4e9ccffc10fb4e7e1be22331deb2307e6d8fbf36 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 3 Jun 2021 20:10:04 +1200 Subject: [PATCH 0200/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Creality=20v4=20?= =?UTF-8?q?servo=20timer=20(#22021)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #21999 --- ini/stm32f1.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 161e59b2e3..7bf8ea3617 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -148,7 +148,7 @@ lib_deps = [env:STM32F103RET6_creality] platform = ${common_stm32.platform} extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 board = genericSTM32F103RE monitor_speed = 115200 board_build.core = stm32 From 9d1d35f1ed07a8884b928e9ee18f06e5f84f28de Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Jun 2021 03:23:10 -0500 Subject: [PATCH 0201/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Remove=20whitesp?= =?UTF-8?q?ace?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c | 8 ++++---- .../share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c index 333bef3db2..2ad0bb864c 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c @@ -88,7 +88,7 @@ const PinMap PinMap_ADC[] = { // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - + }; #endif @@ -214,7 +214,7 @@ const PinMap PinMap_PWM[] = { //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - + //176 pins mcu, 140 gpio //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 @@ -393,12 +393,12 @@ const PinMap PinMap_USB_OTG_FS[] = { #endif #ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { +const PinMap PinMap_USB_OTG_HS[] = { //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP - + /*#error "USB in HS mode isn't supported by the board" {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld index 80bb1d2bb7..f8eb971a6c 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld @@ -102,7 +102,7 @@ SECTIONS . = ALIGN(4); } >FLASH - .ARM.extab : { + .ARM.extab : { . = ALIGN(4); *(.ARM.extab* .gnu.linkonce.armextab.*) . = ALIGN(4); @@ -146,7 +146,7 @@ SECTIONS _sidata = LOADADDR(.data); /* Initialized data sections into "RAM" Ram type memory */ - .data : + .data : { . = ALIGN(4); _sdata = .; /* create a global symbol at data start */ @@ -157,7 +157,7 @@ SECTIONS _edata = .; /* define a global symbol at data end */ } >RAM AT> FLASH - + /* Uninitialized data section into "RAM" Ram type memory */ . = ALIGN(4); .bss : @@ -185,7 +185,7 @@ SECTIONS . = ALIGN(8); } >RAM - + /* Remove information from the compiler libraries */ /DISCARD/ : From 0398a0b780afe73115374900814f4c87b43a3889 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Thu, 3 Jun 2021 18:52:25 -0300 Subject: [PATCH 0202/2168] =?UTF-8?q?=F0=9F=91=BD=EF=B8=8F=20Fix=20usb-hos?= =?UTF-8?q?t-msc-cdc-msc=20issue=20(#22025)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/inc/Conditionals_adv.h | 2 +- buildroot/share/PlatformIO/scripts/generic_create_variant.py | 2 +- ini/stm32f1.ini | 2 +- ini/stm32f4.ini | 4 ++-- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index 9c9a7014c7..d71a5c61b9 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -21,7 +21,7 @@ */ #pragma once -#if defined(USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) +#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 3290dcea19..75c62ef70e 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -28,7 +28,7 @@ if len(platform_packages) == 0: else: platform_name = PackageSpec(platform_packages[0]).name -if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "tool-stm32duino" ]: +if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "tool-stm32duino" ]: platform_name = "framework-arduinoststm32" FRAMEWORK_DIR = platform.get_package_dir(platform_name) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 7bf8ea3617..a0dd38fcd4 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -96,7 +96,7 @@ board_upload.offset_address = 0x08007000 [env:STM32F103RC_btt_USB] extends = env:STM32F103RC_btt platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.build_flags} -DUSBCON diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 087a446ede..d730387cb9 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -146,7 +146,7 @@ debug_init_break = # USB Flash Drive mix-ins for STM32 # [stm_flash_drive] -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 @@ -424,7 +424,7 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} [env:mks_robin_nano_v3_usb_flash_drive_msc] platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3 -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} -DUSBCON From 30c9b9bbba9bed340e877aee10237fc96f678be4 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 3 Jun 2021 17:51:22 -0700 Subject: [PATCH 0203/2168] =?UTF-8?q?=F0=9F=94=A8=20Consolidate=20BTT=20li?= =?UTF-8?q?nker=20scripts=20followup=20(#22038)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1-maple.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 7a43e2d0cb..b7869fd949 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -119,7 +119,7 @@ lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} [env:STM32F103RC_btt_512K_maple] platform = ${common_stm32f1.platform} extends = env:STM32F103RC_btt_maple -board_build.ldscript = STM32F103RC_SKR_MINI_512K.ld +board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld board_upload.maximum_size = 524288 build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DSTM32_FLASH_SIZE=512 From 29ab4f59823ac8b9d5ce41333e2bdf550608dede Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 4 Jun 2021 01:56:49 +0000 Subject: [PATCH 0204/2168] [cron] Bump distribution date (2021-06-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a32fe681f3..4c70835964 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 "2021-06-03" + #define STRING_DISTRIBUTION_DATE "2021-06-04" #endif /** From 6131d2c5a6285da849fbb8d3e592f89518b02b24 Mon Sep 17 00:00:00 2001 From: ldursw <37294448+ldursw@users.noreply.github.com> Date: Fri, 4 Jun 2021 00:38:10 -0300 Subject: [PATCH 0205/2168] =?UTF-8?q?=F0=9F=94=A8=20MKS=20Robin=20E3=20for?= =?UTF-8?q?=20HAL/STM32=20(#21927)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 11 ++++++- .../PlatformIO/scripts/stm32_serialbuffer.py | 23 ++++++++++++++ ini/stm32f1-maple.ini | 2 +- ini/stm32f1.ini | 30 +++++++++++++++---- 5 files changed, 60 insertions(+), 8 deletions(-) create mode 100644 buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 49d91e493a..fa6c5208f9 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -503,7 +503,7 @@ #elif MB(MKS_ROBIN_PRO) #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro #elif MB(MKS_ROBIN_E3) - #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 + #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple #elif MB(MKS_ROBIN_E3_V1_1) #include "stm32f1/pins_MKS_ROBIN_E3_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3D) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index da7bdc79e5..6369fcd31b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -176,8 +176,17 @@ // // SD Card // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 +#define ONBOARD_SPI_DEVICE 2 +#define SDSS SD_SS_PIN +#define SDCARD_CONNECTION ONBOARD #define SD_DETECT_PIN PC10 +#define ONBOARD_SD_CS_PIN SD_SS_PIN +#define NO_SD_HOST_DRIVE + +// TODO: This is the only way to set SPI for SD on STM32 (for now) +#define ENABLE_SPI2 +#define CUSTOM_SPI_PINS #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py new file mode 100644 index 0000000000..2be5a202ef --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -0,0 +1,23 @@ +# +# stm32_serialbuffer.py +# +Import("env") + +# Marlin has `RX_BUFFER_SIZE` and `TX_BUFFER_SIZE` to configure the +# buffer size for receiving and transmitting data respectively. +# Stm32duino uses another set of defines for the same purpose, +# so we get the values from the Marlin configuration and set +# them in `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE`. +# It is not possible to change the values at runtime, they must +# be set with build flags. +# +# The script will set the value as the default one (64 bytes) +# or the user-configured one, whichever is higher. +mf = env["MARLIN_FEATURES"] +rxBuf = str(max(64, int(mf["RX_BUFFER_SIZE"]) if "RX_BUFFER_SIZE" in mf else 0)) +txBuf = str(max(64, int(mf["TX_BUFFER_SIZE"]) if "TX_BUFFER_SIZE" in mf else 0)) + +build_flags = env.get('BUILD_FLAGS') +build_flags.append("-DSERIAL_RX_BUFFER_SIZE=" + rxBuf) +build_flags.append("-DSERIAL_TX_BUFFER_SIZE=" + txBuf) +env.Replace(BUILD_FLAGS=build_flags) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index b7869fd949..ec72e89831 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -268,7 +268,7 @@ extra_scripts = ${common_stm32f1.extra_scripts} # MKS Robin E3D (STM32F103RCT6) and # MKS Robin E3 with TMC2209 # -[env:mks_robin_e3] +[env:mks_robin_e3_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index a0dd38fcd4..bbd2038479 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -31,6 +31,8 @@ build_flags = ${common.build_flags} -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + + +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py # # BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) @@ -53,7 +55,7 @@ monitor_speed = 115200 board_build.core = stm32 board_build.variant = MARLIN_F103Rx board_build.ldscript = ldscript.ld -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -136,12 +138,30 @@ build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py lib_deps = +# +# MKS Robin E3/E3D (STM32F103RCT6) with TMC2209 +# +[env:mks_robin_e3] +platform = ${common_stm32.platform} +extends = common_STM32F103RC +build_flags = ${common_stm32.build_flags} + -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 +build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC +monitor_speed = 115200 +board_build.offset = 0x5000 +board_build.encrypt = Yes +board_build.firmware = Robin_e3.bin +board_upload.offset_address = 0x08005000 +debug_tool = stlink +extra_scripts = ${env:STM32F103RC.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_encrypt.py + # # Creality (STM32F103RET6) # @@ -181,7 +201,7 @@ board_build.firmware = Robin_mini.bin board_build.encrypt = Yes board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -204,7 +224,7 @@ board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC debug_tool = jlink upload_protocol = jlink -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -222,6 +242,6 @@ board_build.ldscript = ldscript.ld board_build.offset = 0x10000 build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py From eea9b6d8ae38af3ca9d5b2f6fb355fc8fce405fb Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sat, 5 Jun 2021 03:02:37 +0200 Subject: [PATCH 0206/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MMU=20compile=20?= =?UTF-8?q?with=20>5=20EXTRUDERS=20(#22036)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 7 ++----- Marlin/src/feature/mmu/mmu.cpp | 9 ++++++++- Marlin/src/feature/mmu/mmu.h | 1 + Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 15 +++++++++------ Marlin/src/module/planner.cpp | 10 ++++++---- Marlin/src/module/planner.h | 4 ++-- Marlin/src/module/stepper/indirection.h | 2 +- Marlin/src/pins/pins.h | 5 ----- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 6 +++--- 10 files changed, 33 insertions(+), 28 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 4fca64ba6b..75e20364f5 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -317,7 +317,7 @@ void disable_e_steppers() { void disable_e_stepper(const uint8_t e) { #define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break; switch (e) { - REPEAT(EXTRUDERS, _CASE_DIS_E) + REPEAT(E_STEPPERS, _CASE_DIS_E) } } @@ -1423,10 +1423,7 @@ void setup() { #endif #if HAS_PRUSA_MMU1 - SETUP_LOG("Prusa MMU1"); - SET_OUTPUT(E_MUX0_PIN); - SET_OUTPUT(E_MUX1_PIN); - SET_OUTPUT(E_MUX2_PIN); + SETUP_RUN(mmu_init()); #endif #if HAS_FANMUX diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp index 9a448296bb..7189723138 100644 --- a/Marlin/src/feature/mmu/mmu.cpp +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -24,7 +24,14 @@ #if HAS_PRUSA_MMU1 -#include "../module/stepper.h" +#include "../MarlinCore.h" +#include "../module/planner.h" + +void mmu_init() { + SET_OUTPUT(E_MUX0_PIN); + SET_OUTPUT(E_MUX1_PIN); + SET_OUTPUT(E_MUX2_PIN); +} void select_multiplexed_stepper(const uint8_t e) { planner.synchronize(); diff --git a/Marlin/src/feature/mmu/mmu.h b/Marlin/src/feature/mmu/mmu.h index 10805c8e26..23742d00c6 100644 --- a/Marlin/src/feature/mmu/mmu.h +++ b/Marlin/src/feature/mmu/mmu.h @@ -21,4 +21,5 @@ */ #pragma once +void mmu_init(); void select_multiplexed_stepper(const uint8_t e); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9b4f832a05..8e4241bf64 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -517,7 +517,7 @@ #define HAS_PRUSA_MMU2 1 #define HAS_PRUSA_MMU2S 1 #endif - #if MMU_MODEL == EXTENDABLE_EMU_MMU2 || MMU_MODEL == EXTENDABLE_EMU_MMU2S + #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 #define HAS_EXTENDABLE_MMU 1 #endif #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index eabe7adbfb..936f83915f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -954,9 +954,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Multi-Material-Unit 2 / EXTENDABLE_EMU_MMU2 requirements */ #if HAS_PRUSA_MMU2 - #if EXTRUDERS != 5 + #if !HAS_EXTENDABLE_MMU && EXTRUDERS != 5 #undef SINGLENOZZLE #error "PRUSA_MMU2(S) requires exactly 5 EXTRUDERS. Please update your Configuration." + #elif HAS_EXTENDABLE_MMU && EXTRUDERS > 15 + #error "EXTRUDERS is too large for MMU(S) emulation mode. The maximum value is 15." #elif DISABLED(NOZZLE_PARK_FEATURE) #error "PRUSA_MMU2(S) requires NOZZLE_PARK_FEATURE. Enable it to continue." #elif HAS_PRUSA_MMU2S && DISABLED(FILAMENT_RUNOUT_SENSOR) @@ -969,18 +971,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2(S) / HAS_EXTENDABLE_MMU(S)."); #endif #endif -#if HAS_EXTENDABLE_MMU && EXTRUDERS > 15 - #error "Too many extruders for MMU(S) emulation mode. (15 maximum)." -#endif /** * Options only for EXTRUDERS > 1 */ #if HAS_MULTI_EXTRUDER - #if EXTRUDERS > 8 - #error "Marlin supports a maximum of 8 EXTRUDERS." + #if HAS_EXTENDABLE_MMU + #define MAX_EXTRUDERS 15 + #else + #define MAX_EXTRUDERS 8 #endif + static_assert(EXTRUDERS <= MAX_EXTRUDERS, "Marlin supports a maximum of " STRINGIFY(MAX_EXTRUDERS) " EXTRUDERS."); + #undef MAX_EXTRUDERS #if ENABLED(HEATERS_PARALLEL) #error "EXTRUDERS must be 1 with HEATERS_PARALLEL." diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c06e4be79b..1ea333e926 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -213,7 +213,7 @@ xyze_float_t Planner::previous_speed; float Planner::previous_nominal_speed_sqr; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - last_move_t Planner::g_uc_extruder_last_move[EXTRUDERS] = { 0 }; + last_move_t Planner::g_uc_extruder_last_move[E_STEPPERS] = { 0 }; #endif #ifdef XY_FREQUENCY_LIMIT @@ -2122,11 +2122,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder - LOOP_L_N(i, EXTRUDERS) + LOOP_L_N(i, E_STEPPERS) if (g_uc_extruder_last_move[i]) g_uc_extruder_last_move[i]--; + #define E_STEPPER_INDEX(E) TERN(SWITCHING_EXTRUDER, (E) / 2, E) + #define ENABLE_ONE_E(N) do{ \ - if (extruder == N) { \ + if (E_STEPPER_INDEX(extruder) == N) { \ ENABLE_AXIS_E##N(); \ g_uc_extruder_last_move[N] = (BLOCK_BUFFER_SIZE) * 2; \ if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ @@ -2145,7 +2147,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif - REPEAT(EXTRUDERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) + REPEAT(E_STEPPERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) } #endif // EXTRUDERS diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index edeac9b7f9..02b7179c5a 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -450,8 +450,8 @@ class Planner { #endif #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - // Counters to manage disabling inactive extruders - static last_move_t g_uc_extruder_last_move[EXTRUDERS]; + // Counters to manage disabling inactive extruder steppers + static last_move_t g_uc_extruder_last_move[E_STEPPERS]; #endif #if HAS_WIRED_LCD diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index e72d793ca6..6f9fd24ce8 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -418,7 +418,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define REV_E_DIR(E) do{ E0_DIR_WRITE(E ? !INVERT_E0_DIR : INVERT_E0_DIR); }while(0) #endif -#elif HAS_PRUSA_MMU2 +#elif HAS_PRUSA_MMU2 // One multiplexed stepper driver #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index fa6c5208f9..a1f45f5774 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -35,11 +35,6 @@ * These numbers are the same in any pin mapping. */ -#if HAS_EXTENDABLE_MMU - #define MAX_EXTRUDERS 15 -#else - #define MAX_EXTRUDERS 8 -#endif #define MAX_E_STEPPERS 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) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 70ac9a13c3..8f19b1915d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -23,10 +23,10 @@ #include "env_validate.h" -#if HOTENDS > 8 || E_STEPPERS > 8 - #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." -#elif HOTENDS > MAX_E_STEPPERS || E_STEPPERS > MAX_E_STEPPERS +#if E_STEPPERS > MAX_E_STEPPERS #error "Marlin extruder/hotends limit! Increase MAX_E_STEPPERS to continue." +#elif HOTENDS > 8 || E_STEPPERS > 8 + #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." #endif #define BOARD_INFO_NAME "BTT GTR V1.0" From a6125b859d46ea3f9321ddd133c389aacdde7872 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 5 Jun 2021 01:38:30 +0000 Subject: [PATCH 0207/2168] [cron] Bump distribution date (2021-06-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4c70835964..cba2db71c4 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 "2021-06-04" + #define STRING_DISTRIBUTION_DATE "2021-06-05" #endif /** From c2c771a1ccbe2b61ef36e040613bd6176675d974 Mon Sep 17 00:00:00 2001 From: Taylor Talkington Date: Sat, 5 Jun 2021 00:01:06 -0400 Subject: [PATCH 0208/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M140=20print=20j?= =?UTF-8?q?ob=20timer=20autostart=20(#22046)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 17 +++++++++++++---- Marlin/src/gcode/temp/M140_M190.cpp | 5 +++-- 2 files changed, 16 insertions(+), 6 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 366267aa7e..f724d8f34c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1824,11 +1824,20 @@ /** * Print Job Timer * - * Automatically start and stop the print job timer on M104/M109/M190. + * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191. + * The print job timer will only be stopped if the bed/chamber target temp is + * below BED_MINTEMP/CHAMBER_MINTEMP. * - * M104 (hotend, no wait) - high temp = none, low temp = stop timer - * M109 (hotend, wait) - high temp = start timer, low temp = stop timer - * M190 (bed, wait) - high temp = start timer, low temp = none + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M140 (bed, no wait) - high temp = none, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * M141 (chamber, no wait) - high temp = none, low temp = stop timer + * M191 (chamber, wait) - high temp = start timer, low temp = none + * + * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2. + * For M140/M190, high temp is anything over BED_MINTEMP. + * For M141/M191, high temp is anything over CHAMBER_MINTEMP. * * The timer can also be controlled with the following commands: * diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index ddab003973..857e11dde5 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -83,10 +83,11 @@ void GcodeSuite::M140_M190(const bool isM190) { thermalManager.setTargetBed(temp); - TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(true, false)); - ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); + // with PRINTJOB_TIMER_AUTOSTART, M190 can start the timer, and M140 can stop it + TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(isM190, !isM190)); + if (isM190) thermalManager.wait_for_bed(no_wait_for_cooling); } From 9d3bc551bc03d1408d47da750825729225374cb1 Mon Sep 17 00:00:00 2001 From: hannesweisbach Date: Sat, 5 Jun 2021 06:38:43 +0200 Subject: [PATCH 0209/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Probe=20Temp=20C?= =?UTF-8?q?alibration=20compile=20(#22032)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/probe_temp_comp.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 2eeb7f47ec..2e5ae85a43 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -64,7 +64,7 @@ typedef struct { #ifndef BTC_SAMPLE_COUNT #define BTC_SAMPLE_COUNT 10U #endif -#ifndef BTC_SAMPLE_STEP +#ifndef BTC_SAMPLE_RES #define BTC_SAMPLE_RES 5 #endif #ifndef BTC_SAMPLE_START From 53a82511ff04df00c6ad47e198da7e8ab9169b07 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 4 Jun 2021 23:44:16 -0500 Subject: [PATCH 0210/2168] =?UTF-8?q?=E2=9C=A8=20Update=20G34=20for=204x?= =?UTF-8?q?=20Z=20steppers=20(#22039)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G34_M422.cpp | 89 ++++++++++++++----------- 1 file changed, 50 insertions(+), 39 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 1614dd6fbd..1803933d16 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -48,6 +48,13 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +#if NUM_Z_STEPPER_DRIVERS >= 3 + #define TRIPLE_Z 1 + #if NUM_Z_STEPPER_DRIVERS >= 4 + #define QUAD_Z 1 + #endif +#endif + /** * G34: Z-Stepper automatic alignment * @@ -82,9 +89,9 @@ void GcodeSuite::G34() { switch (parser.intval('Z')) { case 1: stepper.set_z1_lock(state); break; case 2: stepper.set_z2_lock(state); break; - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if TRIPLE_Z case 3: stepper.set_z3_lock(state); break; - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if QUAD_Z case 4: stepper.set_z4_lock(state); break; #endif #endif @@ -99,13 +106,6 @@ void GcodeSuite::G34() { #if ENABLED(Z_STEPPER_AUTO_ALIGN) do { // break out on error - #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 - const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); if (!WITHIN(z_auto_align_iterations, 1, 30)) { SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); @@ -157,16 +157,14 @@ void GcodeSuite::G34() { 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 - _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 - magnitude2(0, 1) + float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT(_MAX(0, magnitude2(0, 1) + #if TRIPLE_Z + , magnitude2(2, 1), magnitude2(2, 0) + #if QUAD_Z + , magnitude2(3, 2), magnitude2(3, 1), magnitude2(3, 0) + #endif #endif - ); + )); // Home before the alignment procedure if (!all_axes_trusted()) home_all_axes(); @@ -178,7 +176,7 @@ void GcodeSuite::G34() { // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. #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); + float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f); #else float last_z_align_level_indicator = 10000.0f; #endif @@ -280,39 +278,52 @@ void GcodeSuite::G34() { z_measured_min = _MIN(z_measured_min, z_measured[i]); } - SERIAL_ECHOLNPAIR("CALCULATED STEPPER POSITIONS: Z1=", z_measured[0], " Z2=", z_measured[1], " Z3=", z_measured[2]); + SERIAL_ECHOLNPAIR( + LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS), + "Calculated Z1=", z_measured[0], + " Z2=", z_measured[1], + " Z3=", z_measured[2], + " Z4=", z_measured[3] + ) + ); #endif SERIAL_ECHOLNPAIR("\n" - "DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1]) - #if NUM_Z_STEPPER_DRIVERS == 3 - , " Z2-Z3=", ABS(z_measured[1] - z_measured[2]) + "Z2-Z1=", ABS(z_measured[1] - z_measured[0]) + #if TRIPLE_Z + , " Z3-Z2=", ABS(z_measured[2] - z_measured[1]) , " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) + #if QUAD_Z + , " Z4-Z3=", ABS(z_measured[3] - z_measured[2]) + , " Z4-Z2=", ABS(z_measured[3] - z_measured[1]) + , " Z4-Z1=", ABS(z_measured[3] - z_measured[0]) + #endif #endif ); + #if HAS_STATUS_MESSAGE char fstr1[10]; - #if NUM_Z_STEPPER_DRIVERS == 2 - char msg[6 + (6 + 5) * 1 + 1]; - #else - char msg[6 + (6 + 5) * 3 + 1], fstr2[10], fstr3[10]; - #endif - sprintf_P(msg, - PSTR("Diffs Z1-Z2=%s" - #if NUM_Z_STEPPER_DRIVERS == 3 - " Z2-Z3=%s" - " Z3-Z1=%s" + char msg[6 + (6 + 5) * NUM_Z_STEPPER_DRIVERS + 1] + #if TRIPLE_Z + , fstr2[10], fstr3[10] + #if QUAD_Z + , fstr4[10], fstr5[10], fstr6[10] #endif - ), dtostrf(ABS(z_measured[0] - z_measured[1]), 1, 3, fstr1) - #if NUM_Z_STEPPER_DRIVERS == 3 - , dtostrf(ABS(z_measured[1] - z_measured[2]), 1, 3, fstr2) - , dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3) #endif + ; + sprintf_P(msg, + PSTR("1:2=%s" TERN_(TRIPLE_Z, " 3-2=%s 3-1=%s") TERN_(QUAD_Z, " 4-3=%s 4-2=%s 4-1=%s")), + dtostrf(ABS(z_measured[1] - z_measured[0]), 1, 3, fstr1) + OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2)) + OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) ); ui.set_status(msg); #endif - auto decreasing_accuracy = [](const_float_t v1, const_float_t v2){ + auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) { if (v1 < v2 * 0.7f) { SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY); @@ -437,7 +448,7 @@ void GcodeSuite::G34() { #endif }while(0); - #endif + #endif // Z_STEPPER_AUTO_ALIGN } #endif // Z_MULTI_ENDSTOPS || Z_STEPPER_AUTO_ALIGN From c73d47327b80968181450fa222b73f0e7f45fd2a Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sat, 5 Jun 2021 01:49:00 -0300 Subject: [PATCH 0211/2168] =?UTF-8?q?=F0=9F=93=A6=EF=B8=8F=20STM32F103RE?= =?UTF-8?q?=5Fbtt(=5FUSB)=20with=20HAL/STM32=20(#22040)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 4 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 4 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 4 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 4 +- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 6 +-- ini/stm32f1-maple.ini | 12 +++--- ini/stm32f1.ini | 37 +++++++++++++++++++ 7 files changed, 51 insertions(+), 20 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a1f45f5774..4aec569ac5 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -518,9 +518,9 @@ #elif MB(BTT_SKR_MINI_MZ_V1_0) #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple #elif MB(BTT_SKR_E3_DIP) - #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K + #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple env:STM32F103RC_btt env:STM32F103RC_btt_512K #elif MB(BTT_SKR_CR6) - #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB + #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(JGAURORA_A5S_A1) #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 #elif MB(FYSETC_AIO_II) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 50a533cde2..35224ebdd0 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BTT SKR E3 DIP V1.x" diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 58adc5853a..bb356485cb 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" // Release PB3/PB4 (E0 STP/DIR) from JTAG pins #define DISABLE_JTAG diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 8668e1defd..6b3d2832d0 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BTT SKR Mini V1.1" diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 43dfdece44..dc8b8c50f1 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -21,9 +21,9 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 #error "CCROBOT-ONLINE MEEB_3DP only supports one hotend / E-stepper. Comment out this line to continue." #endif diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index ec72e89831..4daf04263a 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -157,10 +157,10 @@ upload_protocol = jlink # # BigTree SKR Mini E3 DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # -# STM32F103RE_btt ............. RET6 -# STM32F103RE_btt_USB ......... RET6 (USB mass storage) +# STM32F103RE_btt_maple ............. RET6 +# STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) # -[env:STM32F103RE_btt] +[env:STM32F103RE_btt_maple] platform = ${common_stm32f1.platform} extends = env:STM32F103RE_maple board_build.address = 0x08007000 @@ -171,10 +171,10 @@ build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 debug_tool = stlink upload_protocol = stlink -[env:STM32F103RE_btt_USB] +[env:STM32F103RE_btt_USB_maple] platform = ${common_stm32f1.platform} -extends = env:STM32F103RE_btt -build_flags = ${env:STM32F103RE_btt.build_flags} -DUSE_USB_COMPOSITE +extends = env:STM32F103RE_btt_maple +build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${common_stm32f1.lib_deps} USBComposite for STM32F1@0.91 diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index bbd2038479..2e197ccb4d 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -184,6 +184,43 @@ extra_scripts = ${common.extra_scripts} debug_tool = jlink upload_protocol = jlink +# +# BigTree SKR Mini E3 DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) +# +# STM32F103RE_btt ............. RET6 +# STM32F103RE_btt_USB ......... RET6 (USB mass storage) +# +[env:STM32F103RE_btt] +platform = ${common_stm32.platform} +extends = common_stm32 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +board = genericSTM32F103RE +monitor_speed = 115200 +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 +board_build.ldscript = ldscript.ld +board_upload.offset_address = 0x08007000 +build_unflags = ${common_stm32.build_unflags} +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py +debug_tool = jlink +upload_protocol = jlink + +[env:STM32F103RE_btt_USB] +extends = env:STM32F103RE_btt +platform = ${common_stm32.platform} +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip +build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC +build_flags = ${env:STM32F103RE_btt.build_flags} ${env:stm32_flash_drive.build_flags} + -DUSBCON + -DUSE_USBHOST_HS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSE_USB_HS_IN_FS + -DUSBD_USE_CDC_MSC + # # FLSUN QQS Pro (STM32F103VET6) # board Hispeedv1 From da8576f642e97b74a6be6eec18fb4ffe3b8dd477 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sat, 5 Jun 2021 16:51:17 +1200 Subject: [PATCH 0212/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STM3R=20/=20BEAS?= =?UTF-8?q?T=20envs=20(#22028)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 4aec569ac5..960c35aefe 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -468,7 +468,7 @@ #elif MB(MALYAN_M200) #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan #elif MB(STM3R_MINI) - #include "stm32f1/pins_STM3R_MINI.h" // STM32F103RE? env:STM32F103RE env:STM32F103RE_maple + #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VD) @@ -556,7 +556,7 @@ #elif MB(FLSUN_HISPEED) #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) - #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_BEAST.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(MINGDA_MPX_ARM_MINI) #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini From d18c8340291b2dfa2c685ffa01bd07f76de1bc18 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Fri, 4 Jun 2021 21:56:18 -0700 Subject: [PATCH 0213/2168] =?UTF-8?q?=E2=9C=A8=20BigTreeTech=20Octopus=20V?= =?UTF-8?q?1.1=20(#22042)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 29 +- Marlin/src/pins/pins.h | 4 +- .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h | 508 +---------------- .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h | 26 + .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 526 ++++++++++++++++++ .../boards/marlin_BigTree_Octopus_v1.json | 2 +- .../PeripheralPins.c | 0 .../PinNamesVar.h | 0 .../hal_conf_extra.h | 0 .../ldscript.ld | 0 .../variant.cpp | 0 .../variant.h | 0 ini/stm32f4.ini | 10 +- 13 files changed, 578 insertions(+), 527 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h create mode 100644 Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/PeripheralPins.c (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/PinNamesVar.h (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/hal_conf_extra.h (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/ldscript.ld (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/variant.cpp (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_BIGTREE_OCTOPUS_V1_0 => MARLIN_BIGTREE_OCTOPUS_V1}/variant.h (100%) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 1f73f04d16..651df5aedf 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -372,20 +372,21 @@ #define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) #define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6) -#define BOARD_LERDGE_K 4215 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4216 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4217 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4218 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4219 // FYSETC S6 (STM32F446VET6) -#define BOARD_FYSETC_S6_V2_0 4220 // FYSETC S6 v2.0 (STM32F446VET6) -#define BOARD_FYSETC_SPIDER 4221 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4222 // FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4223 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4224 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4225 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_ANET_ET4 4226 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4227 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4228 // FYSETC Cheetah V2.0 +#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZET6) +#define BOARD_LERDGE_K 4216 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4217 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4218 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4219 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4223 // FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_ANET_ET4 4227 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4228 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4229 // FYSETC Cheetah V2.0 // diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 960c35aefe..b0463d4498 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -598,7 +598,9 @@ #elif MB(BTT_SKR_V2_0_REV_B) #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 #elif MB(BTT_OCTOPUS_V1_0) - #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1_0 env:BIGTREE_OCTOPUS_V1_0_USB + #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB +#elif MB(BTT_OCTOPUS_V1_1) + #include "stm32f4/pins_BTT_OCTOPUS_V1_1.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(LERDGE_K) #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive #elif MB(LERDGE_S) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 34fe1a824b..e51e0a24bb 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -21,510 +21,6 @@ */ #pragma once -#include "env_validate.h" +#define BOARD_INFO_NAME "BTT OCTOPUS V1.0" -#ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "BTT OCTOPUS V1.0" -#endif - -// Onboard I2C EEPROM -#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) -#define I2C_SCL_PIN PB8 -#define I2C_SDA_PIN PB9 - -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT - -// Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 - -// -// Servos -#define SERVO0_PIN PB6 - -// -// Misc. Functions -// -#define LED_PIN PA13 - -// -// Trinamic Stallguard pins -// -#define X_DIAG_PIN PG6 // X-STOP -#define Y_DIAG_PIN PG9 // Y-STOP -#define Z_DIAG_PIN PG10 // Z-STOP -#define Z2_DIAG_PIN PG11 // Z2-STOP -#define E0_DIAG_PIN PG12 // E0DET -#define E1_DIAG_PIN PG13 // E1DET -#define E2_DIAG_PIN PG14 // E2DET -#define E3_DIAG_PIN PG15 // E3DET - -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB7 -#endif - -// -// Limit Switches -// -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #else - #define X_MIN_PIN E0_DIAG_PIN // E0DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #else - #define Y_MIN_PIN E1_DIAG_PIN // E1DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #else - #define Z_MIN_PIN E2_DIAG_PIN // PWRDET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP -#endif - -// -// Filament Runout Sensor -// -#define FIL_RUNOUT_PIN PG12 // E0DET -#define FIL_RUNOUT2_PIN PG13 // E1DET -#define FIL_RUNOUT3_PIN PG14 // E2DET -#define FIL_RUNOUT4_PIN PG15 // E3DET - -// -// Power Supply Control -// -#ifndef PS_ON_PIN - #define PS_ON_PIN PE11 // PS-ON -#endif - -// -// Power Loss Detection -// -#ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PC0 // PWRDET -#endif - -// -// NeoPixel LED -// -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PB0 -#endif - -// -// Steppers -// -#define X_STEP_PIN PF13 // MOTOR 0 -#define X_DIR_PIN PF12 -#define X_ENABLE_PIN PF14 -#ifndef X_CS_PIN - #define X_CS_PIN PC4 -#endif - -#define Y_STEP_PIN PG0 // MOTOR 1 -#define Y_DIR_PIN PG1 -#define Y_ENABLE_PIN PF15 -#ifndef Y_CS_PIN - #define Y_CS_PIN PD11 -#endif - -#define Z_STEP_PIN PF11 // MOTOR 2 -#define Z_DIR_PIN PG3 -#define Z_ENABLE_PIN PG5 -#ifndef Z_CS_PIN - #define Z_CS_PIN PC6 -#endif - -#define Z2_STEP_PIN PG4 // MOTOR 3 -#define Z2_DIR_PIN PC1 -#define Z2_ENABLE_PIN PA0 -#ifndef Z2_CS_PIN - #define Z2_CS_PIN PC7 -#endif - -#define E0_STEP_PIN PF9 // MOTOR 4 -#define E0_DIR_PIN PF10 -#define E0_ENABLE_PIN PG2 -#ifndef E0_CS_PIN - #define E0_CS_PIN PF2 -#endif - -#define E1_STEP_PIN PC13 // MOTOR 5 -#define E1_DIR_PIN PF0 -#define E1_ENABLE_PIN PF1 -#ifndef E1_CS_PIN - #define E1_CS_PIN PE4 -#endif - -#define E2_STEP_PIN PE2 // MOTOR 6 -#define E2_DIR_PIN PE3 -#define E2_ENABLE_PIN PD4 -#ifndef E2_CS_PIN - - #define E2_CS_PIN PE1 -#endif - -#define E3_STEP_PIN PE6 // MOTOR 7 -#define E3_DIR_PIN PA14 -#define E3_ENABLE_PIN PE0 -#ifndef E3_CS_PIN - #define E3_CS_PIN PD3 -#endif - -// -// Temperature Sensors -// -#define TEMP_BED_PIN PF3 // TB -#if TEMP_SENSOR_0 == 20 - #define TEMP_0_PIN PF8 // PT100 Connector -#else - #define TEMP_0_PIN PF4 // TH0 -#endif -#define TEMP_1_PIN PF5 // TH1 -#define TEMP_2_PIN PF6 // TH2 -#define TEMP_3_PIN PF7 // TH3 - -// -// Heaters / Fans -// -#define HEATER_BED_PIN PA1 // Hotbed -#define HEATER_0_PIN PA2 // Heater0 -#define HEATER_1_PIN PA3 // Heater1 -#define HEATER_2_PIN PB10 // Heater2 -#define HEATER_3_PIN PB11 // Heater3 - -#define FAN_PIN PA8 // Fan0 -#define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PD12 // Fan2 -#define FAN3_PIN PD13 // Fan3 -#define FAN4_PIN PD14 // Fan4 -#define FAN5_PIN PD15 // Fan5 - -// -// SD Support -// -#ifndef SDCARD_CONNECTION - #if HAS_WIRED_LCD - #define SDCARD_CONNECTION LCD - #else - #define SDCARD_CONNECTION ONBOARD - #endif -#endif - -// -// Software SPI pins for TMC2130 stepper drivers -// -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif -#endif - -#if HAS_TMC_UART - /** - * TMC2208/TMC2209 stepper drivers - * - * Hardware serial communication ports. - * If undefined software serial is used according to the pins below - */ - //#define X_HARDWARE_SERIAL Serial1 - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 - - // - // Software serial - // - #define X_SERIAL_TX_PIN PC4 - #define X_SERIAL_RX_PIN PC4 - - #define Y_SERIAL_TX_PIN PD11 - #define Y_SERIAL_RX_PIN PD11 - - #define Z_SERIAL_TX_PIN PC6 - #define Z_SERIAL_RX_PIN PC6 - - #define Z2_SERIAL_TX_PIN PC7 - #define Z2_SERIAL_RX_PIN PC7 - - #define E0_SERIAL_TX_PIN PF2 - #define E0_SERIAL_RX_PIN PF2 - - #define E1_SERIAL_TX_PIN PE4 - #define E1_SERIAL_RX_PIN PE4 - - #define E2_SERIAL_TX_PIN PE1 - #define E2_SERIAL_RX_PIN PE1 - - #define E3_SERIAL_TX_PIN PD3 - #define E3_SERIAL_RX_PIN PD3 - - // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif - -/** - * ______ ______ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) - * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) - * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) - * ------ ----- - * EXP2 EXP1 - */ - -#define EXP1_03_PIN PE15 -#define EXP1_04_PIN PE14 -#define EXP1_05_PIN PE13 -#define EXP1_06_PIN PE12 -#define EXP1_07_PIN PE10 -#define EXP1_08_PIN PE9 -#define EXP1_09_PIN PE7 -#define EXP1_10_PIN PE8 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC15 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB2 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PB1 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 - -// -// Onboard SD card -// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 -// -#if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #ifndef SD_DETECT_STATE - #define SD_DETECT_STATE HIGH - #elif SD_DETECT_STATE == LOW - #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." - #endif - #define SD_DETECT_PIN PC14 -#elif SD_CONNECTION_IS(LCD) - - #define CUSTOM_SPI_PINS - #define SDSS PA4 - #define SD_SS_PIN SDSS - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PC15 - -#elif SD_CONNECTION_IS(CUSTOM_CABLE) - #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" -#endif - -#if ENABLED(BTT_MOTOR_EXPANSION) - /** - * ______ ______ - * NC | 1 2 | GND NC | 1 2 | GND - * NC | 3 4 | M1EN M2EN | 3 4 | M3EN - * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG - * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG - * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG - * ------ ------ - * EXP2 EXP1 - */ - - // M1 on Driver Expansion Module - #define E4_STEP_PIN EXP2_05_PIN - #define E4_DIR_PIN EXP2_06_PIN - #define E4_ENABLE_PIN EXP2_04_PIN - #define E4_DIAG_PIN EXP1_06_PIN - #define E4_CS_PIN EXP1_05_PIN - #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_05_PIN - #define E4_SERIAL_RX_PIN EXP1_05_PIN - #endif - - // M2 on Driver Expansion Module - #define E5_STEP_PIN EXP2_08_PIN - #define E5_DIR_PIN EXP2_07_PIN - #define E5_ENABLE_PIN EXP1_03_PIN - #define E5_DIAG_PIN EXP1_08_PIN - #define E5_CS_PIN EXP1_07_PIN - #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_07_PIN - #define E5_SERIAL_RX_PIN EXP1_07_PIN - #endif - - // M3 on Driver Expansion Module - #define E6_STEP_PIN EXP2_10_PIN - #define E6_DIR_PIN EXP2_09_PIN - #define E6_ENABLE_PIN EXP1_04_PIN - #define E6_DIAG_PIN EXP1_10_PIN - #define E6_CS_PIN EXP1_09_PIN - #if HAS_TMC_UART - #define E6_SERIAL_TX_PIN EXP1_09_PIN - #define E6_SERIAL_RX_PIN EXP1_09_PIN - #endif - -#endif // BTT_MOTOR_EXPANSION - -// -// LCDs and Controllers -// -#if IS_TFTGLCD_PANEL - - #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN - #endif - -#elif HAS_WIRED_LCD - - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN - - #if ENABLED(CR10_STOCKDISPLAY) - - #define LCD_PINS_RS EXP1_04_PIN - - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN - - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - - #else - - #define LCD_PINS_RS EXP1_07_PIN - - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - - #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN - #endif - #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN - #endif - #endif // !FYSETC_MINI_12864 - - #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - - #endif - - #endif -#endif // HAS_WIRED_LCD - -// Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) - #endif -#endif - -// -// WIFI -// - -/** - * ------- - * GND | 9 | | 8 | 3.3V - * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) - * 3.3V | 11 | | 6 | PB14 (ESP-MISO) - * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) - * (ESP-IO4) PD10 | 13 | | 4 | NC - * NC | 14 | | 3 | PE15 (ESP-EN) - * (ESP-RX) PD8 | 15 | | 2 | NC - * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) - * ------- - * WIFI - */ -#define ESP_WIFI_MODULE_COM 3 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this -#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 -#define ESP_WIFI_MODULE_RESET_PIN PG7 -#define ESP_WIFI_MODULE_ENABLE_PIN PG8 -#define ESP_WIFI_MODULE_GPIO0_PIN PD7 -#define ESP_WIFI_MODULE_GPIO4_PIN PD10 +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h new file mode 100644 index 0000000000..93240c16b8 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define BOARD_INFO_NAME "BTT OCTOPUS V1.1" + +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h new file mode 100644 index 0000000000..cce21fbe8f --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -0,0 +1,526 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) +#define I2C_SCL_PIN PB8 +#define I2C_SDA_PIN PB9 + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// +// Servos +#define SERVO0_PIN PB6 + +// +// Misc. Functions +// +#define LED_PIN PA13 + +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PG6 // X-STOP +#define Y_DIAG_PIN PG9 // Y-STOP +#define Z_DIAG_PIN PG10 // Z-STOP +#define Z2_DIAG_PIN PG11 // Z2-STOP +#define E0_DIAG_PIN PG12 // E0DET +#define E1_DIAG_PIN PG13 // E1DET +#define E2_DIAG_PIN PG14 // E2DET +#define E3_DIAG_PIN PG15 // E3DET + +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif + +// +// Limit Switches +// +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_TO_MIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #else + #define X_MIN_PIN E0_DIAG_PIN // E0DET + #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #ifndef X_MIN_PIN + #define X_MIN_PIN X_DIAG_PIN // X-STOP + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #endif +#else + #define X_STOP_PIN X_DIAG_PIN // X-STOP +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_TO_MIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #else + #define Y_MIN_PIN E1_DIAG_PIN // E1DET + #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #endif +#else + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_TO_MIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #else + #define Z_MIN_PIN E2_DIAG_PIN // PWRDET + #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #endif +#else + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PG12 // E0DET +#define FIL_RUNOUT2_PIN PG13 // E1DET +#define FIL_RUNOUT3_PIN PG14 // E2DET +#define FIL_RUNOUT4_PIN PG15 // E3DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PE11 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC0 // PWRDET +#endif + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PF13 // MOTOR 0 +#define X_DIR_PIN PF12 +#define X_ENABLE_PIN PF14 +#ifndef X_CS_PIN + #define X_CS_PIN PC4 +#endif + +#define Y_STEP_PIN PG0 // MOTOR 1 +#define Y_DIR_PIN PG1 +#define Y_ENABLE_PIN PF15 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD11 +#endif + +#define Z_STEP_PIN PF11 // MOTOR 2 +#define Z_DIR_PIN PG3 +#define Z_ENABLE_PIN PG5 +#ifndef Z_CS_PIN + #define Z_CS_PIN PC6 +#endif + +#define Z2_STEP_PIN PG4 // MOTOR 3 +#define Z2_DIR_PIN PC1 +#define Z2_ENABLE_PIN PA0 +#ifndef Z2_CS_PIN + #define Z2_CS_PIN PC7 +#endif + +#define E0_STEP_PIN PF9 // MOTOR 4 +#define E0_DIR_PIN PF10 +#define E0_ENABLE_PIN PG2 +#ifndef E0_CS_PIN + #define E0_CS_PIN PF2 +#endif + +#define E1_STEP_PIN PC13 // MOTOR 5 +#define E1_DIR_PIN PF0 +#define E1_ENABLE_PIN PF1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PE4 +#endif + +#define E2_STEP_PIN PE2 // MOTOR 6 +#define E2_DIR_PIN PE3 +#define E2_ENABLE_PIN PD4 +#ifndef E2_CS_PIN + + #define E2_CS_PIN PE1 +#endif + +#define E3_STEP_PIN PE6 // MOTOR 7 +#define E3_DIR_PIN PA14 +#define E3_ENABLE_PIN PE0 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD3 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PF3 // TB +#if TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 // PT100 Connector +#else + #define TEMP_0_PIN PF4 // TH0 +#endif +#define TEMP_1_PIN PF5 // TH1 +#define TEMP_2_PIN PF6 // TH2 +#define TEMP_3_PIN PF7 // TH3 + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PA1 // Hotbed +#define HEATER_0_PIN PA2 // Heater0 +#define HEATER_1_PIN PA3 // Heater1 +#define HEATER_2_PIN PB10 // Heater2 +#define HEATER_3_PIN PB11 // Heater3 + +#define FAN_PIN PA8 // Fan0 +#define FAN1_PIN PE5 // Fan1 +#define FAN2_PIN PD12 // Fan2 +#define FAN3_PIN PD13 // Fan3 +#define FAN4_PIN PD14 // Fan4 +#define FAN5_PIN PD15 // Fan5 + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PA7 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PA6 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PA5 + #endif +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC4 + #define X_SERIAL_RX_PIN PC4 + + #define Y_SERIAL_TX_PIN PD11 + #define Y_SERIAL_RX_PIN PD11 + + #define Z_SERIAL_TX_PIN PC6 + #define Z_SERIAL_RX_PIN PC6 + + #define Z2_SERIAL_TX_PIN PC7 + #define Z2_SERIAL_RX_PIN PC7 + + #define E0_SERIAL_TX_PIN PF2 + #define E0_SERIAL_RX_PIN PF2 + + #define E1_SERIAL_TX_PIN PE4 + #define E1_SERIAL_RX_PIN PE4 + + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE1 + + #define E3_SERIAL_TX_PIN PD3 + #define E3_SERIAL_RX_PIN PD3 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +/** + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) + * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) + * ------ ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PE15 +#define EXP1_04_PIN PE14 +#define EXP1_05_PIN PE13 +#define EXP1_06_PIN PE12 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE9 +#define EXP1_09_PIN PE7 +#define EXP1_10_PIN PE8 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC15 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB2 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PB1 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// Onboard SD card +// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 +// +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT // Use SDIO for onboard SD + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE HIGH + #elif SD_DETECT_STATE == LOW + #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." + #endif + #define SD_DETECT_PIN PC14 +#elif SD_CONNECTION_IS(LCD) + + #define CUSTOM_SPI_PINS + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC15 + +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** + * ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 + */ + + // M1 on Driver Expansion Module + #define E4_STEP_PIN EXP2_05_PIN + #define E4_DIR_PIN EXP2_06_PIN + #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_DIAG_PIN EXP1_06_PIN + #define E4_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_05_PIN + #define E4_SERIAL_RX_PIN EXP1_05_PIN + #endif + + // M2 on Driver Expansion Module + #define E5_STEP_PIN EXP2_08_PIN + #define E5_DIR_PIN EXP2_07_PIN + #define E5_ENABLE_PIN EXP1_03_PIN + #define E5_DIAG_PIN EXP1_08_PIN + #define E5_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_07_PIN + #define E5_SERIAL_RX_PIN EXP1_07_PIN + #endif + + // M3 on Driver Expansion Module + #define E6_STEP_PIN EXP2_10_PIN + #define E6_DIR_PIN EXP2_09_PIN + #define E6_ENABLE_PIN EXP1_04_PIN + #define E6_DIAG_PIN EXP1_10_PIN + #define E6_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E6_SERIAL_TX_PIN EXP1_09_PIN + #define E6_SERIAL_RX_PIN EXP1_09_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION + +// +// LCDs and Controllers +// +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_08_PIN + #endif + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif + + #endif +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) + #endif +#endif + +// +// WIFI +// + +/** + * ------- + * GND | 9 | | 8 | 3.3V + * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) + * 3.3V | 11 | | 6 | PB14 (ESP-MISO) + * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) + * (ESP-IO4) PD10 | 13 | | 4 | NC + * NC | 14 | | 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) + * ------- + * WIFI + */ +#define ESP_WIFI_MODULE_COM 3 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN PG7 +#define ESP_WIFI_MODULE_ENABLE_PIN PG8 +#define ESP_WIFI_MODULE_GPIO0_PIN PD7 +#define ESP_WIFI_MODULE_GPIO4_PIN PD10 diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json index a583b5783f..ea25154079 100644 --- a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json @@ -4,7 +4,7 @@ "extra_flags": "-DSTM32F446xx", "f_cpu": "180000000L", "mcu": "stm32f446zet6", - "variant": "MARLIN_BIGTREE_OCTOPUS_V1_0" + "variant": "MARLIN_BIGTREE_OCTOPUS_V1" }, "connectivity": [ "can" diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index d730387cb9..021574ad26 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -234,9 +234,9 @@ build_flags = ${stm_flash_drive.build_flags} -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED # -# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) +# BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) # -[env:BIGTREE_OCTOPUS_V1_0] +[env:BIGTREE_OCTOPUS_V1] platform = ${common_stm32.platform} extends = common_stm32 board = marlin_BigTree_octopus_v1 @@ -246,10 +246,10 @@ build_flags = ${common_stm32.build_flags} -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 -DUSE_USB_HS_IN_FS # -# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support +# BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support # -[env:BIGTREE_OCTOPUS_V1_0_USB] -extends = env:BIGTREE_OCTOPUS_V1_0 +[env:BIGTREE_OCTOPUS_V1_USB] +extends = env:BIGTREE_OCTOPUS_V1 platform_packages = ${stm_flash_drive.platform_packages} #build_unflags = -DUSBCON -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} From 733d5fd57d6343fcd8643d322129845b57945cad Mon Sep 17 00:00:00 2001 From: Marcio T Date: Fri, 4 Jun 2021 23:35:05 -0600 Subject: [PATCH 0214/2168] =?UTF-8?q?=F0=9F=93=BA=20Fix=20and=20enhance=20?= =?UTF-8?q?FTDI=20EVE=20Touch=20UI=20(#22047)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/basic/constants.h | 1 + .../ftdi_eve_lib/basic/display_list.h | 4 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 24 +++- .../extended/command_processor.cpp | 12 ++ .../ftdi_eve_lib/extended/command_processor.h | 3 + .../ftdi_eve_lib/extended/grid_layout.h | 14 ++- .../ftdi_eve_lib/extended/text_box.cpp | 10 +- .../ftdi_eve_lib/extended/text_box.h | 2 + .../ftdi_eve_lib/extended/unicode/unicode.cpp | 2 + .../ftdi_eve_lib/scripts/bitmap2cpp.py | 108 ------------------ .../base_numeric_adjustment_screen.cpp | 4 +- .../screens/bed_mesh_base.cpp | 19 +-- .../screens/bed_mesh_edit_screen.cpp | 14 ++- .../screens/bed_mesh_edit_screen.h | 1 + 14 files changed, 86 insertions(+), 132 deletions(-) delete mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h index 507e251518..20b1a3e975 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h @@ -95,6 +95,7 @@ namespace FTDI_FT810 { namespace FTDI { constexpr uint8_t ARGB1555 = 0; constexpr uint8_t L1 = 1; + constexpr uint8_t L2 = 17; constexpr uint8_t L4 = 2; constexpr uint8_t L8 = 3; constexpr uint8_t RGB332 = 4; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h index 99a9e0e810..d6afe78f7c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h @@ -64,14 +64,14 @@ namespace FTDI { inline uint32_t CLEAR_COLOR_A(uint8_t alpha) {return DL::CLEAR_COLOR_A|(alpha&255UL);} inline uint32_t CLEAR_COLOR_RGB(uint8_t red, uint8_t green, uint8_t blue) {return DL::CLEAR_COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|rgb;} + inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|(rgb&0xFFFFFF);} inline uint32_t CLEAR_STENCIL(uint8_t s) {return DL::CLEAR_STENCIL|(s&255UL);} inline uint32_t CLEAR_TAG(uint8_t s) {return DL::CLEAR_TAG|(s&255UL);} inline uint32_t COLOR_A(uint8_t alpha) {return DL::COLOR_A|(alpha&255UL);} inline uint32_t COLOR_MASK(bool r, bool g, bool b, bool a) {return DL::COLOR_MASK|((r?1UL:0UL)<<3)|((g?1UL:0UL)<<2)|((b?1UL:0UL)<<1)|(a?1UL:0UL);} inline uint32_t COLOR_RGB(uint8_t red,uint8_t green,uint8_t blue) {return DL::COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|rgb;} + inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|(rgb&0xFFFFFF);} /* inline uint32_t DISPLAY() {return (0UL<<24)) */ inline uint32_t END() {return DL::END;} inline uint32_t JUMP(uint16_t dest) {return DL::JUMP|(dest&65535UL);} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 9be7882a39..8ae7a150f8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -195,11 +195,31 @@ #define pgm_read_ptr_far pgm_read_ptr #endif + // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments + #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT + #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + + // SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything + // Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). + #define __SEP_N(N,V...) _SEP_##N(V) + #define _SEP_N(N,V...) __SEP_N(N,V) + #define _SEP_1(PRE) SERIAL_ECHOPGM(PRE) + #define _SEP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.print(V); }while(0) + #define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0) + #define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0) + + // Print up to 1 pairs of values followed by newline + #define __SELP_N(N,V...) _SELP_##N(V) + #define _SELP_N(N,V...) __SELP_N(N,V) + #define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE) + #define _SELP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.println(V); }while(0) + #define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0) + #define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0) #define SERIAL_ECHO_START() #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) + #define SERIAL_ECHO_MSG(V...) SERIAL_ECHOLNPAIR(V) + #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp index e324cb978a..fd9c70ff3c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp @@ -26,4 +26,16 @@ CommandProcessor::btn_style_func_t *CommandProcessor::_btn_style_callback = CommandProcessor::default_button_style_func; bool CommandProcessor::is_tracking = false; +uint32_t CommandProcessor::memcrc(uint32_t ptr, uint32_t num) { + const uint16_t x = CLCD::mem_read_16(CLCD::REG::CMD_WRITE); + memcrc(ptr, num, 0); + wait(); + return CLCD::mem_read_32(CLCD::MAP::RAM_CMD + x + 12); +} + +bool CommandProcessor::wait() { + while (is_processing() && !has_fault()) { /* nada */ } + return !has_fault(); +} + #endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 2258529221..8561eb05a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -146,6 +146,9 @@ class CommandProcessor : public CLCD::CommandFifo { return *this; } + bool wait(); + uint32_t memcrc(uint32_t ptr, uint32_t num); + // Wrap all the CommandFifo routines to allow method chaining inline CommandProcessor& cmd (uint32_t cmd32) {CLCD::CommandFifo::cmd(cmd32); return *this;} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h index 47aec24d83..dd94685c98 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h @@ -47,23 +47,25 @@ #define MARGIN_DEFAULT 3 #endif -// EDGE_R adds some black space on the right edge of the display -// This shifts some of the screens left to visually center them. +// The EDGE variables adds some space on the edges of the display +#define EDGE_T 0 +#define EDGE_B 0 +#define EDGE_L 0 #define EDGE_R 0 // GRID_X and GRID_Y computes the positions of the divisions on // the layout grid. -#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R)/GRID_COLS) -#define GRID_Y(y) ((y)*FTDI::display_height/GRID_ROWS) +#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R-EDGE_L)/GRID_COLS+EDGE_L) +#define GRID_Y(y) ((y)*(FTDI::display_height-EDGE_B-EDGE_T)/GRID_ROWS+EDGE_T) // BTN_X, BTN_Y, BTN_W and BTN_X returns the top-left and width // and height of a button, taking into account the button margins. #define BTN_X(x) (GRID_X((x)-1) + MARGIN_L) #define BTN_Y(y) (GRID_Y((y)-1) + MARGIN_T) -#define BTN_W(w) (GRID_X(w) - MARGIN_L - MARGIN_R) -#define BTN_H(h) (GRID_Y(h) - MARGIN_T - MARGIN_B) +#define BTN_W(w) (GRID_X(w) - GRID_X(0) - MARGIN_L - MARGIN_R) +#define BTN_H(h) (GRID_Y(h) - GRID_Y(0) - MARGIN_T - MARGIN_B) // Abbreviations for common phrases, to allow a button to be // defined in one line of source. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index b7422a06b1..6d53d00bb8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -86,8 +86,10 @@ namespace FTDI { if (font == 26) break; } - const uint16_t dx = (options & OPT_RIGHTX) ? w : (options & OPT_CENTERX) ? w/2 : 0; - const uint16_t dy = (options & OPT_CENTERY) ? (h - box_height)/2 : 0; + const uint16_t dx = (options & OPT_RIGHTX) ? w : + (options & OPT_CENTERX) ? w/2 : 0; + const uint16_t dy = (options & OPT_BOTTOMY) ? (h - box_height) : + (options & OPT_CENTERY) ? (h - box_height)/2 : 0; const char *line_start = str; const char *line_end; @@ -105,11 +107,11 @@ namespace FTDI { #if ENABLED(TOUCH_UI_USE_UTF8) if (has_utf8_chars(line)) { - draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~OPT_CENTERY); + draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY)); } else #endif { - cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~OPT_CENTERY); + cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~(OPT_CENTERY | OPT_BOTTOMY)); cmd.CLCD::CommandFifo::str(line); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h index 9d8cd44061..3b14b020c0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h @@ -25,6 +25,8 @@ * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. */ namespace FTDI { + constexpr uint16_t OPT_BOTTOMY = 0x1000; // Non-standard + void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 39b8759204..55dd496e1c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -138,6 +138,7 @@ */ void FTDI::load_utf8_bitmaps(CommandProcessor &cmd) { + cmd.cmd(SAVE_CONTEXT()); #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET CyrillicCharSet::load_bitmaps(cmd); #endif @@ -145,6 +146,7 @@ WesternCharSet::load_bitmaps(cmd); #endif StandardCharSet::load_bitmaps(cmd); + cmd.cmd(RESTORE_CONTEXT()); } /** diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py deleted file mode 100644 index 0c4499e9aa..0000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py +++ /dev/null @@ -1,108 +0,0 @@ -#!/usr/bin/python - -# Written By Marcio Teixeira 2019 - Aleph Objects, Inc. -# -# 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. -# -# To view a copy of the GNU General Public License, go to the following -# location: . - -from __future__ import print_function -from PIL import Image -import argparse -import textwrap - -def pack_rle(data): - """Use run-length encoding to pack the bytes""" - rle = [] - value = data[0] - count = 0 - for i in data: - if i != value or count == 255: - rle.append(count) - rle.append(value) - value = i - count = 1 - else: - count += 1 - rle.append(count) - rle.append(value) - return rle - -class WriteSource: - def __init__(self, lines_in_blocks): - self.blocks = [] - self.values = [] - self.block_size = lines_in_blocks - self.rows = 0 - - def add_pixel(self, value): - self.values.append(value) - - def convert_to_4bpp(self, data, chunk_size = 0): - # Invert the image - data = list(map(lambda i: 255 - i, data)) - # Quanitize 8-bit values into 4-bits - data = list(map(lambda i: i >> 4, data)) - # Make sure there is an even number of elements - if (len(data) & 1) == 1: - data.append(0) - # Combine each two adjacent values into one - i = iter(data) - data = list(map(lambda a, b: a << 4 | b, i ,i)) - # Pack the data - data = pack_rle(data) - # Convert values into hex strings - return list(map(lambda a: "0x" + format(a, '02x'), data)) - - def end_row(self, y): - # Pad each row into even number of values - if len(self.values) & 1: - self.values.append(0) - - self.rows += 1 - if self.block_size and (self.rows % self.block_size) == 0: - self.blocks.append(self.values) - self.values = [] - - def write(self): - if len(self.values): - self.blocks.append(self.values) - - block_strs = []; - for b in self.blocks: - data = self.convert_to_4bpp(b) - data = ', '.join(data) - data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') - block_strs.append(data) - - print("const unsigned char font[] PROGMEM = {") - for i, b in enumerate(block_strs): - if i: - print(',') - print('\n /* {} */'.format(i)) - print(b, end='') - print("\n};") - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Converts a grayscale bitmap into a 16-level RLE packed C array for use as font data') - parser.add_argument("input") - parser.add_argument('--char_height', help='Adds a separator every so many lines', type=int) - args = parser.parse_args() - - writer = WriteSource(args.char_height) - - img = Image.open(args.input).convert('L') - for y in range(img.height): - for x in range(img.width): - writer.add_pixel(img.getpixel((x,y))) - writer.end_row(y) - writer.write() diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp index 3b40e7f14e..747e632d8f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp @@ -51,6 +51,8 @@ BaseNumericAdjustmentScreen::widgets_t::widgets_t(draw_mode_t what) : _what(what .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); } + else + cmd.colors(normal_btn); cmd.font(font_medium); _button(cmd, 1, @@ -319,7 +321,7 @@ void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, progmem_str lab } if (_what & FOREGROUND) { - _button_style(cmd, BTN_TOGGLE); + _button_style(cmd, is_enabled ? BTN_TOGGLE : BTN_DISABLED); cmd.tag(is_enabled ? tag : 0) .enabled(is_enabled) .font(font_small) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp index e83f09f045..83b0825802 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp @@ -141,13 +141,18 @@ void BedMeshBase::_drawMesh(CommandProcessor &cmd, int16_t x, int16_t y, int16_t if (ISVAL(x,y)) { if (opts & USE_COLORS) { const float val_dev = sq(VALUE(x, y) - val_mean); - uint8_t r = 0, b = 0; - //*(VALUE(x, y) < 0 ? &r : &b) = val_dev / sq_min * 0xFF; - if (VALUE(x, y) < 0) - r = val_dev / sq_min * 0xFF; - else - b = val_dev / sq_max * 0xFF; - cmd.cmd(COLOR_RGB(0xFF - b, 0xFF - b - r, 0xFF - r)); + float r = 0, b = 0; + if (sq_min != sq_max) { + if (VALUE(x, y) < 0) + r = val_dev / sq_min; + else + b = val_dev / sq_max; + } + #ifdef BED_MESH_POINTS_GRAY + cmd.cmd(COLOR_RGB((1.0f - b + r) * 0x7F, (1.0f - b - r) * 0x7F, (1.0f - r + b) * 0x7F)); + #else + cmd.cmd(COLOR_RGB((1.0f - b) * 0xFF, (1.0f - b - r) * 0xFF, (1.0f - r) * 0xFF)); + #endif } cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp index f2c775c993..31c6ab8fcb 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp @@ -69,9 +69,17 @@ void BedMeshEditScreen::onEntry() { mydata.zAdjustment = 0; mydata.savedMeshLevelingState = ExtUI::getLevelingActive(); mydata.savedEndstopState = ExtUI::getSoftEndstopState(); + makeMeshValid(); BaseScreen::onEntry(); } +void BedMeshEditScreen::makeMeshValid() { + bed_mesh_t &mesh = ExtUI::getMeshArray(); + GRID_LOOP(x, y) { + if (isnan(mesh[x][y])) mesh[x][y] = 0; + } +} + void BedMeshEditScreen::onExit() { ExtUI::setLevelingActive(mydata.savedMeshLevelingState); ExtUI::setSoftEndstopState(mydata.savedEndstopState); @@ -121,8 +129,9 @@ bool BedMeshEditScreen::changeHighlightedValue(uint8_t tag) { void BedMeshEditScreen::drawHighlightedPointValue() { CommandProcessor cmd; cmd.font(Theme::font_medium) - .colors(normal_btn) + .cmd(COLOR_RGB(bg_text_enabled)) .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .colors(normal_btn) .font(font_small); if (mydata.highlight.x != NONE) draw_adjuster(cmd, Z_VALUE_POS, 3, getHighlightedValue(), GET_TEXT_F(MSG_UNITS_MM), 4, 3); @@ -187,7 +196,8 @@ void BedMeshEditScreen::show() { // After the spinner, go to this screen. current_screen.forget(); PUSH_SCREEN(BedMeshEditScreen); - } else { + } + else { injectCommands_P(PSTR("G29 S1")); GOTO_SCREEN(BedMeshEditScreen); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h index b856b9b33b..45a53f0f13 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h @@ -32,6 +32,7 @@ struct BedMeshEditScreenData { class BedMeshEditScreen : public BedMeshBase, public CachedScreen { private: + static void makeMeshValid(); static float getHighlightedValue(); static void setHighlightedValue(float value); static void moveToHighlightedValue(); From 7726af9c5348c1c7d0fd9a56eca87d00cd75fee6 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Sat, 5 Jun 2021 09:18:47 +0200 Subject: [PATCH 0215/2168] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Support=20for?= =?UTF-8?q?=20up=20to=206=20linear=20axes=20(#19112)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 112 +++- Marlin/Configuration_adv.h | 112 +++- Marlin/src/HAL/AVR/endstop_interrupts.h | 46 +- Marlin/src/HAL/DUE/endstop_interrupts.h | 6 + Marlin/src/HAL/ESP32/endstop_interrupts.h | 6 + Marlin/src/HAL/LPC1768/endstop_interrupts.h | 33 + Marlin/src/HAL/SAMD51/endstop_interrupts.h | 138 ++--- Marlin/src/HAL/STM32/endstop_interrupts.h | 6 + Marlin/src/HAL/STM32F1/MarlinSerial.cpp | 9 + Marlin/src/HAL/STM32F1/endstop_interrupts.h | 6 + .../src/HAL/TEENSY31_32/endstop_interrupts.h | 6 + .../src/HAL/TEENSY35_36/endstop_interrupts.h | 6 + .../src/HAL/TEENSY40_41/endstop_interrupts.h | 6 + Marlin/src/MarlinCore.cpp | 18 + Marlin/src/core/drivers.h | 12 +- Marlin/src/core/language.h | 140 ++++- Marlin/src/core/macros.h | 9 + Marlin/src/core/serial.cpp | 13 +- Marlin/src/core/serial.h | 19 +- Marlin/src/core/types.h | 477 +++++++++------ Marlin/src/core/utility.cpp | 2 +- Marlin/src/core/utility.h | 2 +- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 124 ++-- Marlin/src/feature/tmc_util.cpp | 277 +++++---- Marlin/src/feature/tmc_util.h | 14 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/calibrate/G28.cpp | 73 ++- Marlin/src/gcode/calibrate/G425.cpp | 221 +++++-- Marlin/src/gcode/calibrate/M425.cpp | 5 +- Marlin/src/gcode/config/M200-M205.cpp | 8 +- Marlin/src/gcode/config/M92.cpp | 9 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 14 +- Marlin/src/gcode/control/M605.cpp | 37 +- Marlin/src/gcode/feature/L6470/M906.cpp | 2 +- Marlin/src/gcode/feature/pause/G60.cpp | 11 +- Marlin/src/gcode/feature/pause/G61.cpp | 4 +- Marlin/src/gcode/feature/trinamic/M122.cpp | 20 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 153 ++--- Marlin/src/gcode/feature/trinamic/M906.cpp | 23 +- .../src/gcode/feature/trinamic/M911-M914.cpp | 202 +++--- Marlin/src/gcode/gcode.cpp | 5 +- Marlin/src/gcode/gcode.h | 8 +- Marlin/src/gcode/geometry/M206_M428.cpp | 13 +- Marlin/src/gcode/host/M114.cpp | 17 +- Marlin/src/gcode/motion/G0_G1.cpp | 9 +- Marlin/src/gcode/motion/G2_G3.cpp | 44 +- Marlin/src/gcode/motion/M290.cpp | 2 +- Marlin/src/gcode/parser.cpp | 2 +- Marlin/src/gcode/parser.h | 2 +- Marlin/src/gcode/temp/M106_M107.cpp | 2 + Marlin/src/inc/Conditionals_LCD.h | 40 +- Marlin/src/inc/Conditionals_adv.h | 18 + Marlin/src/inc/Conditionals_post.h | 454 +++++++++++--- Marlin/src/inc/SanityCheck.h | 313 ++++++++-- Marlin/src/inc/Version.h | 2 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 2 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 6 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 10 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 36 +- .../screens/endstop_state_screen.cpp | 12 +- .../mks_ui/draw_tmc_step_mode_settings.cpp | 50 +- Marlin/src/lcd/language/language_en.h | 30 + Marlin/src/lcd/menu/menu_advanced.cpp | 14 +- Marlin/src/lcd/menu/menu_backlash.cpp | 17 +- Marlin/src/lcd/menu/menu_motion.cpp | 51 +- Marlin/src/lcd/menu/menu_tmc.cpp | 175 ++---- Marlin/src/lcd/tft/ui_1024x600.cpp | 10 +- Marlin/src/lcd/tft/ui_320x240.cpp | 10 +- Marlin/src/lcd/tft/ui_480x320.cpp | 10 +- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 200 ++++-- Marlin/src/libs/L64XX/L64XX_Marlin.h | 4 +- Marlin/src/libs/vector_3.cpp | 25 +- Marlin/src/libs/vector_3.h | 35 +- Marlin/src/module/delta.cpp | 6 + Marlin/src/module/endstops.cpp | 410 ++++++++++--- Marlin/src/module/endstops.h | 6 + Marlin/src/module/motion.cpp | 427 ++++++++----- Marlin/src/module/motion.h | 136 +++-- Marlin/src/module/planner.cpp | 258 ++++---- Marlin/src/module/planner.h | 53 +- Marlin/src/module/planner_bezier.cpp | 10 +- Marlin/src/module/probe.h | 20 +- Marlin/src/module/settings.cpp | 573 ++++++++---------- Marlin/src/module/stepper.cpp | 303 +++++++-- Marlin/src/module/stepper.h | 60 +- Marlin/src/module/stepper/L64xx.cpp | 18 + Marlin/src/module/stepper/L64xx.h | 60 ++ Marlin/src/module/stepper/TMC26X.cpp | 18 + Marlin/src/module/stepper/TMC26X.h | 24 + Marlin/src/module/stepper/indirection.cpp | 4 +- Marlin/src/module/stepper/indirection.h | 206 ++++++- Marlin/src/module/stepper/trinamic.cpp | 105 +++- Marlin/src/module/stepper/trinamic.h | 61 +- Marlin/src/module/tool_change.cpp | 24 +- Marlin/src/pins/pinsDebug_list.h | 99 +++ Marlin/src/pins/pins_postprocess.h | 123 +++- Marlin/src/pins/sensitive_pins.h | 278 ++++++--- Marlin/src/sd/cardreader.cpp | 1 + 98 files changed, 5040 insertions(+), 2256 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index f724d8f34c..27307eb3be 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,7 +35,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02000801 +#define CONFIGURATION_H_VERSION 02000900 //=========================================================================== //============================= Getting Started ============================= @@ -66,6 +66,14 @@ // //=========================================================================== +//=========================================================================== +//=========================== FOAMCUTTER_XYUV ============================== +//=========================================================================== +// For a hot wire cutter with parallel horizontal axes X, I where the hights +// of the two wire ends are controlled by parallel axes Y, J. +// +//#define FOAMCUTTER_XYUV + // @section info // Author info of this build printed to the host during boot and M115 @@ -149,6 +157,45 @@ // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +/** + * Define the number of coordinated linear axes. + * See https://github.com/DerAndere1/Marlin/wiki + * Each linear axis gets its own stepper control and endstop: + * + * Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON + * Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG + * Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR + * Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE + * DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES, + * MICROSTEP_MODES, MANUAL_FEEDRATE + * + * :[3, 4, 5, 6] + */ +//#define LINEAR_AXES 3 + +/** + * Axis codes for additional axes: + * This defines the axis code that is used in G-code commands to + * reference a specific axis. + * 'A' for rotational axis parallel to X + * 'B' for rotational axis parallel to Y + * 'C' for rotational axis parallel to Z + * 'U' for secondary linear axis parallel to X + * 'V' for secondary linear axis parallel to Y + * 'W' for secondary linear axis parallel to Z + * Regardless of the settings, firmware-internal axis IDs are + * I (AXIS4), J (AXIS5), K (AXIS6). + */ +#if LINEAR_AXES >= 4 + #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 5 + #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 6 + #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif + // @section extruder // This defines the number of extruders @@ -691,9 +738,15 @@ #define USE_XMIN_PLUG #define USE_YMIN_PLUG #define USE_ZMIN_PLUG +//#define USE_IMIN_PLUG +//#define USE_JMIN_PLUG +//#define USE_KMIN_PLUG //#define USE_XMAX_PLUG //#define USE_YMAX_PLUG //#define USE_ZMAX_PLUG +//#define USE_IMAX_PLUG +//#define USE_JMAX_PLUG +//#define USE_KMAX_PLUG // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS @@ -702,9 +755,15 @@ //#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_IMAX + //#define ENDSTOPPULLUP_JMAX + //#define ENDSTOPPULLUP_KMAX //#define ENDSTOPPULLUP_XMIN //#define ENDSTOPPULLUP_YMIN //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_IMIN + //#define ENDSTOPPULLUP_JMIN + //#define ENDSTOPPULLUP_KMIN //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -715,9 +774,15 @@ //#define ENDSTOPPULLDOWN_XMAX //#define ENDSTOPPULLDOWN_YMAX //#define ENDSTOPPULLDOWN_ZMAX + //#define ENDSTOPPULLDOWN_IMAX + //#define ENDSTOPPULLDOWN_JMAX + //#define ENDSTOPPULLDOWN_KMAX //#define ENDSTOPPULLDOWN_XMIN //#define ENDSTOPPULLDOWN_YMIN //#define ENDSTOPPULLDOWN_ZMIN + //#define ENDSTOPPULLDOWN_IMIN + //#define ENDSTOPPULLDOWN_JMIN + //#define ENDSTOPPULLDOWN_KMIN //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif @@ -725,9 +790,15 @@ #define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe. /** @@ -756,6 +827,9 @@ //#define Z2_DRIVER_TYPE A4988 //#define Z3_DRIVER_TYPE A4988 //#define Z4_DRIVER_TYPE A4988 +//#define I_DRIVER_TYPE A4988 +//#define J_DRIVER_TYPE A4988 +//#define K_DRIVER_TYPE A4988 #define E0_DRIVER_TYPE A4988 //#define E1_DRIVER_TYPE A4988 //#define E2_DRIVER_TYPE A4988 @@ -809,14 +883,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -829,7 +903,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } @@ -863,6 +937,9 @@ #define DEFAULT_XJERK 10.0 #define DEFAULT_YJERK 10.0 #define DEFAULT_ZJERK 0.3 + //#define DEFAULT_IJERK 0.3 + //#define DEFAULT_JJERK 0.3 + //#define DEFAULT_KJERK 0.3 //#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves @@ -1177,12 +1254,18 @@ #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders +//#define I_ENABLE_ON 0 +//#define J_ENABLE_ON 0 +//#define K_ENABLE_ON 0 // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! #define DISABLE_X false #define DISABLE_Y false #define DISABLE_Z false +//#define DISABLE_I false +//#define DISABLE_J false +//#define DISABLE_K false // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING @@ -1198,6 +1281,9 @@ #define INVERT_X_DIR false #define INVERT_Y_DIR true #define INVERT_Z_DIR false +//#define INVERT_I_DIR false +//#define INVERT_J_DIR false +//#define INVERT_K_DIR false // @section extruder @@ -1233,6 +1319,9 @@ #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 +//#define I_HOME_DIR -1 +//#define J_HOME_DIR -1 +//#define K_HOME_DIR -1 // @section machine @@ -1247,6 +1336,12 @@ #define X_MAX_POS X_BED_SIZE #define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 +//#define I_MIN_POS 0 +//#define I_MAX_POS 50 +//#define J_MIN_POS 0 +//#define J_MAX_POS 50 +//#define K_MIN_POS 0 +//#define K_MAX_POS 50 /** * Software Endstops @@ -1263,6 +1358,9 @@ #define MIN_SOFTWARE_ENDSTOP_X #define MIN_SOFTWARE_ENDSTOP_Y #define MIN_SOFTWARE_ENDSTOP_Z + #define MIN_SOFTWARE_ENDSTOP_I + #define MIN_SOFTWARE_ENDSTOP_J + #define MIN_SOFTWARE_ENDSTOP_K #endif // Max software endstops constrain movement within maximum coordinate bounds @@ -1271,6 +1369,9 @@ #define MAX_SOFTWARE_ENDSTOP_X #define MAX_SOFTWARE_ENDSTOP_Y #define MAX_SOFTWARE_ENDSTOP_Z + #define MAX_SOFTWARE_ENDSTOP_I + #define MAX_SOFTWARE_ENDSTOP_J + #define MAX_SOFTWARE_ENDSTOP_K #endif #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) @@ -1582,6 +1683,9 @@ //#define MANUAL_X_HOME_POS 0 //#define MANUAL_Y_HOME_POS 0 //#define MANUAL_Z_HOME_POS 0 +//#define MANUAL_I_HOME_POS 0 +//#define MANUAL_J_HOME_POS 0 +//#define MANUAL_K_HOME_POS 0 // Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. // diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4511aa49c7..e0c54dfbec 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -30,7 +30,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 02000801 +#define CONFIGURATION_ADV_H_VERSION 02000900 //=========================================================================== //============================= Thermal Settings ============================ @@ -918,6 +918,9 @@ #define INVERT_X_STEP_PIN false #define INVERT_Y_STEP_PIN false #define INVERT_Z_STEP_PIN false +#define INVERT_I_STEP_PIN false +#define INVERT_J_STEP_PIN false +#define INVERT_K_STEP_PIN false #define INVERT_E_STEP_PIN false /** @@ -929,6 +932,9 @@ #define DISABLE_INACTIVE_X true #define DISABLE_INACTIVE_Y true #define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! +#define DISABLE_INACTIVE_I true +#define DISABLE_INACTIVE_J true +#define DISABLE_INACTIVE_K true #define DISABLE_INACTIVE_E true // Default Minimum Feedrates for printing and travel moves @@ -969,7 +975,7 @@ #if ENABLED(BACKLASH_COMPENSATION) // Define values for backlash distance and correction. // If BACKLASH_GCODE is enabled these values are the defaults. - #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) + #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis #define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction // Add steps for motor direction changes on CORE kinematics @@ -1040,6 +1046,13 @@ #define CALIBRATION_MEASURE_LEFT #define CALIBRATION_MEASURE_BACK + //#define CALIBRATION_MEASURE_IMIN + //#define CALIBRATION_MEASURE_IMAX + //#define CALIBRATION_MEASURE_JMIN + //#define CALIBRATION_MEASURE_JMAX + //#define CALIBRATION_MEASURE_KMIN + //#define CALIBRATION_MEASURE_KMAX + // Probing at the exact top center only works if the center is flat. If // probing on a screwhead or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES @@ -2236,6 +2249,13 @@ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif + /** + * Extra G-code to run while executing tool-change commands. Can be used to use an additional + * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer. + */ + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 I0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 + /** * Tool Sensors detect when tools have been picked up or dropped. * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc. @@ -2413,6 +2433,24 @@ #define Z4_MICROSTEPS Z_MICROSTEPS #endif + #if AXIS_DRIVER_TYPE_I(TMC26X) + #define I_MAX_CURRENT 1000 + #define I_SENSE_RESISTOR 91 + #define I_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_J(TMC26X) + #define J_MAX_CURRENT 1000 + #define J_SENSE_RESISTOR 91 + #define J_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_K(TMC26X) + #define K_MAX_CURRENT 1000 + #define K_SENSE_RESISTOR 91 + #define K_MICROSTEPS 16 + #endif + #if AXIS_DRIVER_TYPE_E0(TMC26X) #define E0_MAX_CURRENT 1000 #define E0_SENSE_RESISTOR 91 @@ -2563,6 +2601,33 @@ //#define Z4_INTERPOLATE true #endif + #if AXIS_IS_TMC(I) + #define I_CURRENT 800 + #define I_CURRENT_HOME I_CURRENT + #define I_MICROSTEPS 16 + #define I_RSENSE 0.11 + #define I_CHAIN_POS -1 + //#define I_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(J) + #define J_CURRENT 800 + #define J_CURRENT_HOME J_CURRENT + #define J_MICROSTEPS 16 + #define J_RSENSE 0.11 + #define J_CHAIN_POS -1 + //#define J_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(K) + #define K_CURRENT 800 + #define K_CURRENT_HOME K_CURRENT + #define K_MICROSTEPS 16 + #define K_RSENSE 0.11 + #define K_CHAIN_POS -1 + //#define K_INTERPOLATE true + #endif + #if AXIS_IS_TMC(E0) #define E0_CURRENT 800 #define E0_MICROSTEPS 16 @@ -2638,6 +2703,10 @@ //#define Y2_CS_PIN -1 //#define Z2_CS_PIN -1 //#define Z3_CS_PIN -1 + //#define Z4_CS_PIN -1 + //#define I_CS_PIN -1 + //#define J_CS_PIN -1 + //#define K_CS_PIN -1 //#define E0_CS_PIN -1 //#define E1_CS_PIN -1 //#define E2_CS_PIN -1 @@ -2677,6 +2746,9 @@ //#define Z2_SLAVE_ADDRESS 0 //#define Z3_SLAVE_ADDRESS 0 //#define Z4_SLAVE_ADDRESS 0 + //#define I_SLAVE_ADDRESS 0 + //#define J_SLAVE_ADDRESS 0 + //#define K_SLAVE_ADDRESS 0 //#define E0_SLAVE_ADDRESS 0 //#define E1_SLAVE_ADDRESS 0 //#define E2_SLAVE_ADDRESS 0 @@ -2701,6 +2773,9 @@ */ #define STEALTHCHOP_XY #define STEALTHCHOP_Z + #define STEALTHCHOP_I + #define STEALTHCHOP_J + #define STEALTHCHOP_K #define STEALTHCHOP_E /** @@ -2772,6 +2847,9 @@ #define Z2_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3 #define Z4_HYBRID_THRESHOLD 3 + #define I_HYBRID_THRESHOLD 3 + #define J_HYBRID_THRESHOLD 3 + #define K_HYBRID_THRESHOLD 3 #define E0_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30 @@ -2818,6 +2896,9 @@ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define I_STALL_SENSITIVITY 8 + //#define J_STALL_SENSITIVITY 8 + //#define K_STALL_SENSITIVITY 8 //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif @@ -2958,6 +3039,33 @@ #define Z4_SLEW_RATE 1 #endif + #if AXIS_DRIVER_TYPE_I(L6470) + #define I_MICROSTEPS 128 + #define I_OVERCURRENT 2000 + #define I_STALLCURRENT 1500 + #define I_MAX_VOLTAGE 127 + #define I_CHAIN_POS -1 + #define I_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_J(L6470) + #define J_MICROSTEPS 128 + #define J_OVERCURRENT 2000 + #define J_STALLCURRENT 1500 + #define J_MAX_VOLTAGE 127 + #define J_CHAIN_POS -1 + #define J_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_K(L6470) + #define K_MICROSTEPS 128 + #define K_OVERCURRENT 2000 + #define K_STALLCURRENT 1500 + #define K_MAX_VOLTAGE 127 + #define K_CHAIN_POS -1 + #define K_SLEW_RATE 1 + #endif + #if AXIS_IS_L64XX(E0) #define E0_MICROSTEPS 128 #define E0_OVERCURRENT 2000 diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index 9fd9c38b86..50f29c3356 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -168,6 +168,51 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PIN); #endif #endif + #if HAS_I_MAX + #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(I_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable"); + pciSetup(I_MAX_PIN); + #endif + #elif HAS_I_MIN + #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(I_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable"); + pciSetup(I_MIN_PIN); + #endif + #endif + #if HAS_J_MAX + #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(J_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable"); + pciSetup(J_MAX_PIN); + #endif + #elif HAS_J_MIN + #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(J_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable"); + pciSetup(J_MIN_PIN); + #endif + #endif + #if HAS_K_MAX + #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(K_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable"); + pciSetup(K_MAX_PIN); + #endif + #elif HAS_K_MIN + #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(K_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable"); + pciSetup(K_MIN_PIN); + #endif + #endif #if HAS_X2_MAX #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MAX_PIN); @@ -256,6 +301,5 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PROBE_PIN); #endif #endif - // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI. } diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index 999ada5127..9c7e210488 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 743ccd99c9..4725df921b 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -59,4 +59,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h index 126d6e7d5b..23bd0cc982 100644 --- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h +++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h @@ -122,4 +122,37 @@ void setup_endstop_interrupts() { #endif _ATTACH(Z_MIN_PROBE_PIN); #endif + #if HAS_I_MAX + #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN) + #error "I_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MAX_PIN); + #elif HAS_I_MIN + #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN) + #error "I_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MIN_PIN); + #endif + #if HAS_J_MAX + #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN) + #error "J_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MAX_PIN); + #elif HAS_J_MIN + #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN) + #error "J_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MIN_PIN); + #endif + #if HAS_K_MAX + #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN) + #error "K_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MAX_PIN); + #elif HAS_K_MIN + #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN) + #error "K_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MIN_PIN); + #endif } diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index daac773387..c46b6e072f 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -47,80 +47,38 @@ #include "../../module/endstops.h" -#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#if HAS_X_MAX - #define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN) -#else - #define MATCH_X_MAX_EILINE(P) false -#endif -#if HAS_X_MIN - #define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN) -#else - #define MATCH_X_MIN_EILINE(P) false -#endif -#if HAS_Y_MAX - #define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN) -#else - #define MATCH_Y_MAX_EILINE(P) false -#endif -#if HAS_Y_MIN - #define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN) -#else - #define MATCH_Y_MIN_EILINE(P) false -#endif -#if HAS_Z_MAX - #define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN) -#else - #define MATCH_Z_MAX_EILINE(P) false -#endif -#if HAS_Z_MIN - #define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN) -#else - #define MATCH_Z_MIN_EILINE(P) false -#endif -#if HAS_Z2_MAX - #define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN) -#else - #define MATCH_Z2_MAX_EILINE(P) false -#endif -#if HAS_Z2_MIN - #define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN) -#else - #define MATCH_Z2_MIN_EILINE(P) false -#endif -#if HAS_Z3_MAX - #define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN) -#else - #define MATCH_Z3_MAX_EILINE(P) false -#endif -#if HAS_Z3_MIN - #define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN) -#else - #define MATCH_Z3_MIN_EILINE(P) false -#endif -#if HAS_Z4_MAX - #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN) -#else - #define MATCH_Z4_MAX_EILINE(P) false -#endif -#if HAS_Z4_MIN - #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN) -#else - #define MATCH_Z4_MIN_EILINE(P) false -#endif -#if HAS_Z_MIN_PROBE_PIN - #define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN) -#else - #define MATCH_Z_MIN_PROBE_EILINE(P) false -#endif -#define AVAILABLE_EILINE(P) (PIN_TO_EILINE(P) != -1 \ - && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ - && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ - && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ - && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ - && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ - && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ - && !MATCH_Z_MIN_PROBE_EILINE(P)) +#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) +#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) + +#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ + && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ + && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ + && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ + && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \ + && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \ + && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \ + && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ + && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ + && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ + && !MATCH_Z_MIN_PROBE_EILINE(P) ) // One ISR for all EXT-Interrupts void endstop_ISR() { endstops.update(); } @@ -204,5 +162,37 @@ void setup_endstop_interrupts() { #error "Z_MIN_PROBE_PIN has no EXTINT line available." #endif _ATTACH(Z_MIN_PROBE_PIN); + #elif HAS_I_MAX + #if !AVAILABLE_EILINE(I_MAX_PIN) + #error "I_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_I_MIN + #if !AVAILABLE_EILINE(I_MIN_PIN) + #error "I_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_J_MAX + #if !AVAILABLE_EILINE(J_MAX_PIN) + #error "J_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_J_MIN + #if !AVAILABLE_EILINE(J_MIN_PIN) + #error "J_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_K_MAX + #if !AVAILABLE_EILINE(K_MAX_PIN) + #error "K_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_K_MIN + #if !AVAILABLE_EILINE(K_MIN_PIN) + #error "K_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif } diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index fdff8cc644..90870881fe 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -46,4 +46,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index fa8bb7eaa8..6dabcde51e 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -167,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } #if AXIS_HAS_HW_SERIAL(Z4) CHECK_AXIS_SERIAL(Z4); #endif +#if AXIS_HAS_HW_SERIAL(I) + CHECK_AXIS_SERIAL(I); +#endif +#if AXIS_HAS_HW_SERIAL(J) + CHECK_AXIS_SERIAL(J); +#endif +#if AXIS_HAS_HW_SERIAL(K) + CHECK_AXIS_SERIAL(K); +#endif #if AXIS_HAS_HW_SERIAL(E0) CHECK_AXIS_SERIAL(E0); #endif diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index bcb07d991d..4d7edb9496 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -71,4 +71,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index 999ada5127..9c7e210488 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index 87e6a7507a..a300248885 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h index a05e911668..4c3ddec9f1 100644 --- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 75e20364f5..18bee54009 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -304,6 +304,9 @@ void enable_all_steppers() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki) + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); enable_e_steppers(); TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled()); @@ -325,6 +328,9 @@ void disable_all_steppers() { DISABLE_AXIS_X(); DISABLE_AXIS_Y(); DISABLE_AXIS_Z(); + DISABLE_AXIS_I(); + DISABLE_AXIS_J(); + DISABLE_AXIS_K(); disable_e_steppers(); TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); @@ -444,6 +450,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { 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_I)) DISABLE_AXIS_I(); + if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J(); + if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K(); if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); @@ -935,6 +944,15 @@ inline void tmc_standby_setup() { #if PIN_EXISTS(Z4_STDBY) SET_INPUT_PULLDOWN(Z4_STDBY_PIN); #endif + #if PIN_EXISTS(I_STDBY) + SET_INPUT_PULLDOWN(I_STDBY_PIN); + #endif + #if PIN_EXISTS(J_STDBY) + SET_INPUT_PULLDOWN(J_STDBY_PIN); + #endif + #if PIN_EXISTS(K_STDBY) + SET_INPUT_PULLDOWN(K_STDBY_PIN); + #endif #if PIN_EXISTS(E0_STDBY) SET_INPUT_PULLDOWN(E0_STDBY_PIN); #endif diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 3a0e620923..0a76410274 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -60,6 +60,9 @@ #define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T) #define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T) #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T) +#define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T) +#define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T) +#define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T) #define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T)) #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T)) @@ -83,6 +86,7 @@ #define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T)) #define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \ + || AXIS_DRIVER_TYPE_I(T) || AXIS_DRIVER_TYPE_J(T) || AXIS_DRIVER_TYPE_K(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) ) @@ -153,9 +157,11 @@ #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(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 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) \ + || AXIS_HAS_##T(I) || AXIS_HAS_##T(J) || AXIS_HAS_##T(K) \ + || E_AXIS_HAS(T) ) #if ANY_AXIS_HAS(STEALTHCHOP) #define HAS_STEALTHCHOP 1 diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index df6821cb1c..8e97ec66a9 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -266,18 +266,25 @@ #define STR_X_MAX "x_max" #define STR_X2_MIN "x2_min" #define STR_X2_MAX "x2_max" -#define STR_Y_MIN "y_min" -#define STR_Y_MAX "y_max" -#define STR_Y2_MIN "y2_min" -#define STR_Y2_MAX "y2_max" -#define STR_Z_MIN "z_min" -#define STR_Z_MAX "z_max" -#define STR_Z2_MIN "z2_min" -#define STR_Z2_MAX "z2_max" -#define STR_Z3_MIN "z3_min" -#define STR_Z3_MAX "z3_max" -#define STR_Z4_MIN "z4_min" -#define STR_Z4_MAX "z4_max" + +#if HAS_Y_AXIS + #define STR_Y_MIN "y_min" + #define STR_Y_MAX "y_max" + #define STR_Y2_MIN "y2_min" + #define STR_Y2_MAX "y2_max" +#endif + +#if HAS_Z_AXIS + #define STR_Z_MIN "z_min" + #define STR_Z_MAX "z_max" + #define STR_Z2_MIN "z2_min" + #define STR_Z2_MAX "z2_max" + #define STR_Z3_MIN "z3_min" + #define STR_Z3_MAX "z3_max" + #define STR_Z4_MIN "z4_min" + #define STR_Z4_MAX "z4_max" +#endif + #define STR_Z_PROBE "z_probe" #define STR_PROBE_EN "probe_en" #define STR_FILAMENT_RUNOUT_SENSOR "filament" @@ -286,6 +293,9 @@ #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" +#define STR_I AXIS4_STR +#define STR_J AXIS5_STR +#define STR_K AXIS6_STR #define STR_E "E" #if IS_KINEMATIC #define STR_A "A" @@ -305,8 +315,114 @@ #define LCD_STR_A STR_A #define LCD_STR_B STR_B #define LCD_STR_C STR_C +#define LCD_STR_I STR_I +#define LCD_STR_J STR_J +#define LCD_STR_K STR_K #define LCD_STR_E STR_E +// Extra Axis and Endstop Names +#if LINEAR_AXES >= 4 + #if AXIS4_NAME == 'A' + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #elif AXIS4_NAME == 'B' + #define AXIS4_STR "B" + #define STR_I_MIN "b_min" + #define STR_I_MAX "b_max" + #elif AXIS4_NAME == 'C' + #define AXIS4_STR "C" + #define STR_I_MIN "c_min" + #define STR_I_MAX "c_max" + #elif AXIS4_NAME == 'U' + #define AXIS4_STR "U" + #define STR_I_MIN "u_min" + #define STR_I_MAX "u_max" + #elif AXIS4_NAME == 'V' + #define AXIS4_STR "V" + #define STR_I_MIN "v_min" + #define STR_I_MAX "v_max" + #elif AXIS4_NAME == 'W' + #define AXIS4_STR "W" + #define STR_I_MIN "w_min" + #define STR_I_MAX "w_max" + #else + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #endif +#else + #define AXIS4_STR "" +#endif + +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == 'A' + #define AXIS5_STR "A" + #define STR_J_MIN "a_min" + #define STR_J_MAX "a_max" + #elif AXIS5_NAME == 'B' + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #elif AXIS5_NAME == 'C' + #define AXIS5_STR "C" + #define STR_J_MIN "c_min" + #define STR_J_MAX "c_max" + #elif AXIS5_NAME == 'U' + #define AXIS5_STR "U" + #define STR_J_MIN "u_min" + #define STR_J_MAX "u_max" + #elif AXIS5_NAME == 'V' + #define AXIS5_STR "V" + #define STR_J_MIN "v_min" + #define STR_J_MAX "v_max" + #elif AXIS5_NAME == 'W' + #define AXIS5_STR "W" + #define STR_J_MIN "w_min" + #define STR_J_MAX "w_max" + #else + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #endif +#else + #define AXIS5_STR "" +#endif + +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == 'A' + #define AXIS6_STR "A" + #define STR_K_MIN "a_min" + #define STR_K_MAX "a_max" + #elif AXIS6_NAME == 'B' + #define AXIS6_STR "B" + #define STR_K_MIN "b_min" + #define STR_K_MAX "b_max" + #elif AXIS6_NAME == 'C' + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #elif AXIS6_NAME == 'U' + #define AXIS6_STR "U" + #define STR_K_MIN "u_min" + #define STR_K_MAX "u_max" + #elif AXIS6_NAME == 'V' + #define AXIS6_STR "V" + #define STR_K_MIN "v_min" + #define STR_K_MAX "v_max" + #elif AXIS6_NAME == 'W' + #define AXIS6_STR "W" + #define STR_K_MIN "w_min" + #define STR_K_MAX "w_max" + #else + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #endif +#else + #define AXIS6_STR "" +#endif + #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 7a2d731c01..dc6147adb0 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -36,12 +36,21 @@ #define _XMIN_ 100 #define _YMIN_ 200 #define _ZMIN_ 300 +#define _IMIN_ 400 +#define _JMIN_ 500 +#define _KMIN_ 600 #define _XMAX_ 101 #define _YMAX_ 201 #define _ZMAX_ 301 +#define _IMAX_ 401 +#define _JMAX_ 501 +#define _KMAX_ 601 #define _XDIAG_ 102 #define _YDIAG_ 202 #define _ZDIAG_ 302 +#define _IDIAG_ 502 +#define _JDIAG_ 602 +#define _KDIAG_ 702 #define _E0DIAG_ 400 #define _E1DIAG_ 401 #define _E2DIAG_ 402 diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 60729440e6..2e3a39b66a 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -36,6 +36,10 @@ PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMST PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); +PGMSTR(I_STR, AXIS4_STR); PGMSTR(J_STR, AXIS5_STR); PGMSTR(K_STR, AXIS6_STR); +PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":"); +PGMSTR(SP_I_STR, " " AXIS4_STR); PGMSTR(SP_J_STR, " " AXIS5_STR); PGMSTR(SP_K_STR, " " AXIS6_STR); +PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":"); // Hook Meatpack if it's enabled on the first leaf #if ENABLED(MEATPACK_ON_SERIAL_PORT_1) @@ -101,11 +105,10 @@ void print_bin(uint16_t val) { } } -void print_pos( - LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z) - , PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/ -) { +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); - SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z)); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k) + ); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 6f893795df..a5afb9d895 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -29,12 +29,16 @@ #endif // Commonly-used strings in serial output -extern const char NUL_STR[], SP_P_STR[], SP_T_STR[], +extern const char NUL_STR[], + SP_X_STR[], SP_Y_STR[], SP_Z_STR[], + SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_E_STR[], + SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[], + SP_I_STR[], SP_J_STR[], SP_K_STR[], + SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], + SP_P_STR[], SP_T_STR[], X_STR[], Y_STR[], Z_STR[], E_STR[], X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], - SP_A_STR[], SP_B_STR[], SP_C_STR[], - SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], - SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[]; + I_LBL[], J_LBL[], K_LBL[]; // // Debugging flags for use by M111 @@ -310,13 +314,10 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_pos( - LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z), - PGM_P const prefix=nullptr, PGM_P const suffix=nullptr -); +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_pos(LINEAR_AXIS_LIST(xyz.x, xyz.y, xyz.z), prefix, suffix); + print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix); } #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index abb709d731..f8b5cef77b 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -43,11 +43,17 @@ struct IF { typedef L type; }; #define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V) #define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V) #define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) } +#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k) +#define LINEAR_AXIS_ELEM(O) LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k) +#define LINEAR_AXIS_DEFS(T,V) LINEAR_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) #define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E) #define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E) #define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E) #define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } +#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k) +#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k) +#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) #if HAS_EXTRUDERS #define LIST_ITEM_E(N) , N @@ -69,37 +75,37 @@ struct IF { typedef L type; }; enum AxisEnum : uint8_t { // Linear axes may be controlled directly or indirectly - LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS), + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS) // Extruder axes may be considered distinctly - #define _EN_ITEM(N) E##N##_AXIS, + #define _EN_ITEM(N) , E##N##_AXIS REPEAT(EXTRUDERS, _EN_ITEM) #undef _EN_ITEM // Core also keeps toolhead directions #if IS_CORE - X_HEAD, Y_HEAD, Z_HEAD, + , X_HEAD, Y_HEAD, Z_HEAD #endif // Distinct axes, including all E and Core - NUM_AXIS_ENUMS, + , NUM_AXIS_ENUMS // Most of the time we refer only to the single E_AXIS #if HAS_EXTRUDERS - E_AXIS = E0_AXIS, + , E_AXIS = E0_AXIS #endif // A, B, and C are for DELTA, SCARA, etc. - A_AXIS = X_AXIS, + , A_AXIS = X_AXIS #if LINEAR_AXES >= 2 - B_AXIS = Y_AXIS, + , B_AXIS = Y_AXIS #endif #if LINEAR_AXES >= 3 - C_AXIS = Z_AXIS, + , C_AXIS = Z_AXIS #endif // To refer to all or none - ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF + , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; @@ -241,9 +247,16 @@ struct XYval { struct { T a, b; }; T pos[2]; }; + + // Set all to 0 + FI void reset() { x = y = 0; } + + // Setters taking struct types and arrays 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]; } + #if HAS_Y_AXIS + 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]; } + #endif #if LINEAR_AXES > XY FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; } #endif @@ -253,10 +266,15 @@ struct XYval { FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } #endif #endif - FI void reset() { x = y = 0; } + + // Length reduced to one dimension FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + // Pointer to the data as a simple array FI operator T* () { return pos; } + // If any element is true then it's true FI operator bool() { return x || y; } + + // Explicit copy and copies with conversion FI XYval copy() const { return *this; } FI XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } FI XYval asInt() { return { int16_t(x), int16_t(y) }; } @@ -268,17 +286,27 @@ struct XYval { FI XYval asFloat() { return { static_cast(x), static_cast(y) }; } FI XYval asFloat() const { return { static_cast(x), static_cast(y) }; } FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + + // Marlin workspace shifting is done with G92 and M206 FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } + + // Cast to a type with more fields by making a new object FI operator XYZval() { return { x, y }; } FI operator XYZval() const { return { x, y }; } FI operator XYZEval() { return { x, y }; } FI operator XYZEval() const { return { x, y }; } + + // Accessor via an AxisEnum (or any integer) [index] FI T& operator[](const int n) { return pos[n]; } FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing FI XYval& operator= (const T v) { set(v, v ); return *this; } FI XYval& operator= (const XYZval &rs) { set(rs.x, rs.y); return *this; } FI XYval& operator= (const XYZEval &rs) { set(rs.x, rs.y); return *this; } + + // Override other operators to get intuitive behaviors FI XYval operator+ (const XYval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } FI XYval operator+ (const XYval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } FI XYval operator- (const XYval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } @@ -315,6 +343,10 @@ struct XYval { FI XYval operator>>(const int &v) { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } FI XYval operator<<(const int &v) const { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } FI XYval operator<<(const int &v) { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } + FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } + FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } + + // Modifier operators FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } @@ -328,6 +360,8 @@ struct XYval { FI XYval& operator*=(const int &v) { x *= v; y *= v; return *this; } FI XYval& operator>>=(const int &v) { _RS(x); _RS(y); return *this; } FI XYval& operator<<=(const int &v) { _LS(x); _LS(y); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. FI bool operator==(const XYval &rs) { return x == rs.x && y == rs.y; } FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y; } FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y; } @@ -340,8 +374,6 @@ struct XYval { FI bool operator!=(const XYval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } - FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } - FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } }; // @@ -350,111 +382,144 @@ struct XYval { template struct XYZval { union { - struct { T LINEAR_AXIS_LIST(x, y, z); }; - struct { T LINEAR_AXIS_LIST(a, b, c); }; + struct { T LINEAR_AXIS_ARGS(); }; + struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); }; T pos[LINEAR_AXES]; }; + + // Set all to 0 + FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays 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 XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } + FI void set(const XYval pxy, const T pz) { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); } FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } #if HAS_Z_AXIS - FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) - { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } + FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } #endif #if LOGICAL_AXES > LINEAR_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } - FI void set(LOGICAL_AXIS_LIST(const T, const T px, const T py, const T pz)) - { LINEAR_AXIS_CODE(x = px, y = py, z = pz); } + FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); } + FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } #endif #endif - FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =) 0; } - FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z)); } + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + #endif + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } + #endif + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // Length reduced to one dimension + FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } + // Pointer to the data as a simple array FI operator T* () { return pos; } - FI operator bool() { return LINEAR_AXIS_GANG(z, || x, || y); } + // If any element is true then it's true + FI operator bool() { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); } + + // Explicit copy and copies with conversion FI XYZval copy() const { XYZval o = *this; return o; } - FI XYZval ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); } - FI XYZval asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); } - FI XYZval asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); } - FI XYZval asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); } - FI XYZval asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); } - FI XYZval ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } - FI XYZval ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } - FI XYZval asFloat() { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z)); } - FI XYZval asFloat() const { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z)); } - FI XYZval reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z)); } + FI XYZval ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); } + FI XYZval asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZval ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZval asFloat() { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval asFloat() const { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // Marlin workspace shifting is done with G92 and M206 FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } + + // In-place cast to types having fewer fields FI operator XYval&() { return *(XYval*)this; } FI operator const XYval&() const { return *(const XYval*)this; } - FI operator XYZEval() const { return LINEAR_AXIS_ARRAY(x, y, z); } + + // Cast to a type with more fields by making a new object + FI operator XYZEval() const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); } + + // Accessor via an AxisEnum (or any integer) [index] FI T& operator[](const int n) { return pos[n]; } FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing FI XYZval& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; } FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } - FI XYZval& operator= (const XYZEval &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; } - FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; } - FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; } - FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; } - FI XYZval operator- (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; } - FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; } - FI XYZval operator* (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; } - FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; } - FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; } - FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZval operator* (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZval operator>>(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } - FI XYZval operator>>(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } - FI XYZval operator<<(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } - FI XYZval operator<<(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } - FI XYZval& operator+=(const XYval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP ); return *this; } - FI XYZval& operator-=(const XYval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP ); return *this; } - FI XYZval& operator*=(const XYval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP ); return *this; } - FI XYZval& operator/=(const XYval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP ); return *this; } - FI XYZval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; } - FI XYZval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; } - FI XYZval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; } - FI XYZval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; } - FI XYZval& operator+=(const XYZEval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; } - FI XYZval& operator-=(const XYZEval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; } - FI XYZval& operator*=(const XYZEval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; } - FI XYZval& operator/=(const XYZEval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; } - FI XYZval& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; } - FI XYZval& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; } - FI XYZval& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z) ); return *this; } - FI XYZval& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z) ); return *this; } - FI bool operator==(const XYZEval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } - FI bool operator==(const XYZEval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } + FI XYZval& operator= (const XYZEval &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; } + + // Override other operators to get intuitive behaviors + FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator>>(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator>>(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI const XYZval operator-() const { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + FI XYZval operator-() { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + + // Modifier operators + FI XYZval& operator+=(const XYval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator-=(const XYval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator*=(const XYval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator/=(const XYval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZval& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZEval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZEval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } - FI XYZval operator-() { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; } - FI const XYZval operator-() const { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; } }; // @@ -463,109 +528,137 @@ struct XYZval { template struct XYZEval { union { - struct{ T LOGICAL_AXIS_LIST(e, x, y, z); }; - struct{ T LINEAR_AXIS_LIST(a, b, c); }; + struct { T LOGICAL_AXIS_ARGS(); }; + struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); }; T pos[LOGICAL_AXES]; }; - FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =) 0; } - FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z)); } - FI operator T* () { return pos; } - FI operator bool() { return false LOGICAL_AXIS_GANG(|| e, || x, || y, || z); } - 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 XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYZval pxyz) { set(LINEAR_AXIS_LIST(pxyz.x, pxyz.y, pxyz.z)); } + // Reset all to 0 + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays + 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 XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYZval pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); } #if HAS_Z_AXIS - FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) { - LINEAR_AXIS_CODE(x = px, y = py, z = pz); - } + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); } #endif #if LOGICAL_AXES > LINEAR_AXES - FI void set(LOGICAL_AXIS_LIST(const T pe, const T px, const T py, const T pz)) { - LOGICAL_AXIS_CODE(e = pe, x = px, y = py, z = pz); - } - FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } - FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } + FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } #endif - FI XYZEval copy() const { XYZEval o = *this; return o; } - FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); } - FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); } - FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); } - FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); } - FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); } - FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } - FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); } - FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z)); } - FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z)); } - FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z)); } - FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } - FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } - FI operator XYval&() { return *(XYval*)this; } - FI operator const XYval&() const { return *(const XYval*)this; } - FI operator XYZval&() { return *(XYZval*)this; } - FI operator const XYZval&() const { return *(const XYZval*)this; } - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } - FI XYZEval& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; } - FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } - FI XYZEval& operator= (const XYZval &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; } - FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; } - FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; } - FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; } - FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; } - FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; } - FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; } - FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; } - FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; } - FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; } - FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; } - FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; } - FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; } - FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; } - FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; } - FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } - FI XYZEval operator>>(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; } - FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } - FI XYZEval operator<<(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; } - FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYZEval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z); return *this; } - FI XYZEval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z); return *this; } - FI XYZEval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z); return *this; } - FI XYZEval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z); return *this; } - FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z); return *this; } - FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z); return *this; } - FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z); return *this; } - FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z); return *this; } - FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v); return *this; } - FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z)); return *this; } - FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z)); return *this; } - FI bool operator==(const XYZval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } - FI bool operator==(const XYZval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); } - FI bool operator!=(const XYZval &rs) { return !operator==(rs); } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); } - FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); } + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + #endif + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } + #endif + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // Length reduced to one dimension + FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } + // Pointer to the data as a simple array + FI operator T* () { return pos; } + // If any element is true then it's true + FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k); } + + // Explicit copy and copies with conversion + FI XYZEval copy() const { XYZEval o = *this; return o; } + FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); } + FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // Marlin workspace shifting is done with G92 and M206 + FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } + FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } + + // In-place cast to types having fewer fields + FI operator XYval&() { return *(XYval*)this; } + FI operator const XYval&() const { return *(const XYval*)this; } + FI operator XYZval&() { return *(XYZval*)this; } + FI operator const XYZval&() const { return *(const XYZval*)this; } + + // Accessor via an AxisEnum (or any integer) [index] + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing + FI XYZEval& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; } + + // Override other operators to get intuitive behaviors + FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZEval operator>>(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI XYZEval operator<<(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + + // Modifier operators + FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYZEval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator!=(const XYZval &rs) { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } }; #undef _RECIP diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index f4cdef43c8..b810855d52 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -122,7 +122,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height); #endif #if ABL_PLANAR - SERIAL_ECHOPGM("ABL Adjustment X"); + SERIAL_ECHOPGM("ABL Adjustment"); LOOP_LINEAR_AXES(a) { const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; SERIAL_CHAR(' ', AXIS_CHAR(a)); diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 31d0ac6ef4..d248091ce5 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -77,7 +77,7 @@ public: // in the range 0-100 while avoiding rounding artifacts constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; } -const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z'); +const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME); #if LINEAR_AXES <= XYZ #define AXIS_CHAR(A) ((char)('X' + A)) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 4af608cce4..20408d8d1e 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -113,20 +113,22 @@ const xy_float_t ad = sign * dist; const bool use_x_dist = ad.x > ad.y; - float on_axis_distance = use_x_dist ? dist.x : dist.y, - e_position = end.e - start.e, - z_position = end.z - start.z; + float on_axis_distance = use_x_dist ? dist.x : dist.y; - const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero - z_normalized_dist = z_position / on_axis_distance; + const float z_normalized_dist = (end.z - start.z) / on_axis_distance; // Allow divide by zero + #if HAS_EXTRUDERS + const float e_normalized_dist = (end.e - start.e) / on_axis_distance; + const bool inf_normalized_flag = isinf(e_normalized_dist); + #endif xy_int8_t icell = istart; const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; - const bool inf_normalized_flag = isinf(e_normalized_dist), - inf_ratio_flag = isinf(ratio); + const bool inf_ratio_flag = isinf(ratio); + + xyze_pos_t dest; // Stores XYZE for segmented moves /** * Handle vertical lines that stay within one column. @@ -143,34 +145,36 @@ * For others the next X is the same so this can continue. * Calculate X at the next Y mesh line. */ - const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; + dest.x = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; - const float ry = mesh_index_to_ypos(icell.y); + dest.y = mesh_index_to_ypos(icell.y); /** * Without this check, it's possible to generate a zero length move, as in the case where * the line is heading down, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (ry != start.y) { + if (dest.y != start.y) { if (!inf_normalized_flag) { // fall-through faster than branch - on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder); + dest.z += z0; + planner.buffer_segment(dest, scaled_fr_mm_s, extruder); + } //else printf("FIRST MOVE PRUNED "); } @@ -188,12 +192,13 @@ */ if (iadd.y == 0) { // Horizontal line? icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move. + while (icell.x != iend.x + ineg.x) { icell.x += iadd.x; - const float rx = mesh_index_to_xpos(icell.x); - const float ry = ratio * rx + c; // Calculate Y at the next X mesh line + dest.x = mesh_index_to_xpos(icell.x); + dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. @@ -205,19 +210,20 @@ * the line is heading left, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (rx != start.x) { + if (dest.x != start.x) { if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); // Based on X or Y because the move is horizontal + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + } //else printf("FIRST MOVE PRUNED "); } @@ -239,57 +245,65 @@ while (cnt) { const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x), - next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y), - ry = ratio * next_mesh_line_x + c, // Calculate Y at the next X mesh line - rx = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line - // (No need to worry about ratio == 0. - // In that case, it was already detected - // as a vertical line move above.) + next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y); - if (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first + dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line + dest.x = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line + // (No need to worry about ratio == 0. + // In that case, it was already detected + // as a vertical line move above.) + + if (neg.x == (dest.x > next_mesh_line_x)) { // Check if we hit the Y line first // Yes! Crossing a Y Mesh Line next - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x - ineg.x, icell.y + iadd.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x - ineg.x, icell.y + iadd.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; + dest.y = next_mesh_line_y; + if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start.x : next_mesh_line_y - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + icell.y += iadd.y; cnt.y--; } else { // Yes! Crossing a X Mesh Line next - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x + iadd.x, icell.y - ineg.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x + iadd.x, icell.y - ineg.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; + dest.x = next_mesh_line_x; + if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? next_mesh_line_x - start.x : ry - start.y; - e_position = start.e + on_axis_distance * e_normalized_dist; - z_position = start.z + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + icell.x += iadd.x; cnt.x--; } @@ -438,11 +452,9 @@ #endif ; - planner.buffer_line(raw.x, raw.y, raw.z + z_cxcy, raw.e, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + const float oldz = raw.z; raw.z += z_cxcy; + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); + raw.z = oldz; if (segments == 0) // done with last segment return false; // didn't set current from destination diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 021317ea89..48b26cc101 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -417,6 +417,21 @@ } #endif + #if AXIS_IS_TMC(I) + if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperI); + #endif + + #if AXIS_IS_TMC(J) + if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperJ); + #endif + + #if AXIS_IS_TMC(K) + if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperK); + #endif + #if AXIS_IS_TMC(E0) (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting); #endif @@ -757,138 +772,148 @@ } } - static void tmc_debug_loop( - const TMC_debug_enum i, - LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) - ) { - if (print_x) { + static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_status(stepperX, i); + tmc_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_status(stepperX2, i); + tmc_status(stepperX2, n); #endif } - #if LINEAR_AXES >= XY - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_status(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_status(stepperY2, i); - #endif - } - #endif + if (TERN0(HAS_Y_AXIS, y)) { + #if AXIS_IS_TMC(Y) + tmc_status(stepperY, n); + #endif + #if AXIS_IS_TMC(Y2) + tmc_status(stepperY2, n); + #endif + } - if (TERN0(HAS_Z_AXIS, print_z)) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_status(stepperZ, i); + tmc_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_status(stepperZ2, i); + tmc_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_status(stepperZ3, i); + tmc_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_status(stepperZ4, i); + tmc_status(stepperZ4, n); #endif } - if (TERN0(HAS_EXTRUDERS, print_e)) { + #if AXIS_IS_TMC(I) + if (i) tmc_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_status(stepperE0, i); + tmc_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_status(stepperE1, i); + tmc_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_status(stepperE2, i); + tmc_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_status(stepperE3, i); + tmc_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_status(stepperE4, i); + tmc_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_status(stepperE5, i); + tmc_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_status(stepperE6, i); + tmc_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_status(stepperE7, i); + tmc_status(stepperE7, n); #endif } SERIAL_EOL(); } - static void drv_status_loop( - const TMC_drv_status_enum i, - LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) - ) { - if (print_x) { + static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_parse_drv_status(stepperX, i); + tmc_parse_drv_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_parse_drv_status(stepperX2, i); + tmc_parse_drv_status(stepperX2, n); #endif } - #if LINEAR_AXES >= XY - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_parse_drv_status(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_parse_drv_status(stepperY2, i); - #endif - } - #endif + if (TERN0(HAS_Y_AXIS, y)) { + #if AXIS_IS_TMC(Y) + tmc_parse_drv_status(stepperY, n); + #endif + #if AXIS_IS_TMC(Y2) + tmc_parse_drv_status(stepperY2, n); + #endif + } - if (TERN0(HAS_Z_AXIS, print_z)) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_parse_drv_status(stepperZ, i); + tmc_parse_drv_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_parse_drv_status(stepperZ2, i); + tmc_parse_drv_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_parse_drv_status(stepperZ3, i); + tmc_parse_drv_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_parse_drv_status(stepperZ4, i); + tmc_parse_drv_status(stepperZ4, n); #endif } - if (TERN0(HAS_EXTRUDERS, print_e)) { + #if AXIS_IS_TMC(I) + if (i) tmc_parse_drv_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_parse_drv_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_parse_drv_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_parse_drv_status(stepperE0, i); + tmc_parse_drv_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_parse_drv_status(stepperE1, i); + tmc_parse_drv_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_parse_drv_status(stepperE2, i); + tmc_parse_drv_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_parse_drv_status(stepperE3, i); + tmc_parse_drv_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_parse_drv_status(stepperE4, i); + tmc_parse_drv_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_parse_drv_status(stepperE5, i); + tmc_parse_drv_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_parse_drv_status(stepperE6, i); + tmc_parse_drv_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_parse_drv_status(stepperE7, i); + tmc_parse_drv_status(stepperE7, n); #endif } @@ -899,11 +924,9 @@ * M122 report functions */ - void tmc_report_all( - LOGICAL_AXIS_LIST(const bool print_e/*=true*/, const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/) - ) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) + void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) { + #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) @@ -1028,79 +1051,82 @@ } #endif - static void tmc_get_registers( - TMC_get_registers_enum i, - LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) - ) { - if (print_x) { + static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_get_registers(stepperX, i); + tmc_get_registers(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_get_registers(stepperX2, i); + tmc_get_registers(stepperX2, n); #endif } - #if LINEAR_AXES >= XY - if (print_y) { - #if AXIS_IS_TMC(Y) - tmc_get_registers(stepperY, i); - #endif - #if AXIS_IS_TMC(Y2) - tmc_get_registers(stepperY2, i); - #endif - } - #endif + if (TERN0(HAS_Y_AXIS, y)) { + #if AXIS_IS_TMC(Y) + tmc_get_registers(stepperY, n); + #endif + #if AXIS_IS_TMC(Y2) + tmc_get_registers(stepperY2, n); + #endif + } - if (TERN0(HAS_Z_AXIS, print_z)) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_get_registers(stepperZ, i); + tmc_get_registers(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_get_registers(stepperZ2, i); + tmc_get_registers(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_get_registers(stepperZ3, i); + tmc_get_registers(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_get_registers(stepperZ4, i); + tmc_get_registers(stepperZ4, n); #endif } - if (TERN0(HAS_EXTRUDERS, print_e)) { + #if AXIS_IS_TMC(I) + if (i) tmc_get_registers(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_get_registers(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_get_registers(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_get_registers(stepperE0, i); + tmc_get_registers(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_get_registers(stepperE1, i); + tmc_get_registers(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_get_registers(stepperE2, i); + tmc_get_registers(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_get_registers(stepperE3, i); + tmc_get_registers(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_get_registers(stepperE4, i); + tmc_get_registers(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_get_registers(stepperE5, i); + tmc_get_registers(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_get_registers(stepperE6, i); + tmc_get_registers(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_get_registers(stepperE7, i); + tmc_get_registers(stepperE7, n); #endif } SERIAL_EOL(); } - void tmc_get_registers( - LOGICAL_AXIS_LIST(bool print_e, bool print_x, bool print_y, bool print_z) - ) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0) + void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) { + #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0) #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1185,6 +1211,15 @@ #if AXIS_HAS_SPI(Z4) SET_CS_PIN(Z4); #endif + #if AXIS_HAS_SPI(I) + SET_CS_PIN(I); + #endif + #if AXIS_HAS_SPI(J) + SET_CS_PIN(J); + #endif + #if AXIS_HAS_SPI(K) + SET_CS_PIN(K); + #endif #if AXIS_HAS_SPI(E0) SET_CS_PIN(E0); #endif @@ -1234,12 +1269,10 @@ static bool test_connection(TMC &st) { return test_result; } -void test_tmc_connection( - LOGICAL_AXIS_LIST(const bool test_e/*=true*/, const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/) -) { +void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { uint8_t axis_connection = 0; - if (test_x) { + if (x) { #if AXIS_IS_TMC(X) axis_connection += test_connection(stepperX); #endif @@ -1248,18 +1281,16 @@ void test_tmc_connection( #endif } - #if LINEAR_AXES >= XY - if (test_y) { - #if AXIS_IS_TMC(Y) - axis_connection += test_connection(stepperY); - #endif - #if AXIS_IS_TMC(Y2) - axis_connection += test_connection(stepperY2); - #endif - } - #endif + if (TERN0(HAS_Y_AXIS, y)) { + #if AXIS_IS_TMC(Y) + axis_connection += test_connection(stepperY); + #endif + #if AXIS_IS_TMC(Y2) + axis_connection += test_connection(stepperY2); + #endif + } - if (TERN0(HAS_Z_AXIS, test_z)) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) axis_connection += test_connection(stepperZ); #endif @@ -1274,7 +1305,17 @@ void test_tmc_connection( #endif } - if (TERN0(HAS_EXTRUDERS, test_e)) { + #if AXIS_IS_TMC(I) + if (i) axis_connection += test_connection(stepperI); + #endif + #if AXIS_IS_TMC(J) + if (j) axis_connection += test_connection(stepperJ); + #endif + #if AXIS_IS_TMC(K) + if (k) axis_connection += test_connection(stepperK); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) axis_connection += test_connection(stepperE0); #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index a07d6ce0ee..3a856b3af8 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -335,20 +335,14 @@ void tmc_print_current(TMC &st) { #endif void monitor_tmc_drivers(); -void test_tmc_connection( - LOGICAL_AXIS_LIST(const bool test_e=true, const bool test_x=true, const bool test_y=true, const bool test_z=true) -); +void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all( - LOGICAL_AXIS_LIST(const bool print_e=true, const bool print_x=true, const bool print_y=true, const bool print_z=true) - ); - void tmc_get_registers( - LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z) - ); + void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true)); + void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool)); #endif /** @@ -361,7 +355,7 @@ void test_tmc_connection( #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool LINEAR_AXIS_LIST(x, y, z), x2, y2, z2, z3, z4; }; + struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index a8c3f45cdc..5760667bed 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -689,7 +689,7 @@ G29_TYPE GcodeSuite::G29() { TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); // Retain the last probe position - abl.probePos = points[i]; + abl.probePos = xy_pos_t(points[i]); abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); if (isnan(abl.measured_z)) { set_bed_leveling_enabled(abl.reenable); @@ -795,7 +795,7 @@ G29_TYPE GcodeSuite::G29() { const int ind = abl.indexIntoAB[xx][yy]; xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points], abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 }; - planner.bed_level_matrix.apply_rotation_xyz(tmp); + planner.bed_level_matrix.apply_rotation_xyz(tmp.x, tmp.y, tmp.z); if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z); const float subval = get_min ? abl.mean : tmp.z + min_diff, diff = abl.eqnBVector[ind] - subval; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index a71f541593..2eca66c3b0 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -323,42 +323,44 @@ void GcodeSuite::G28() { #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS)))) - const bool homeZ = parser.seen_test('Z'), - LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing - needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false // UNUSED + const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')), + LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing + needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED + needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K) ), - LINEAR_AXIS_LIST( // Home each axis if needed or flagged + LINEAR_AXIS_LIST( // Home each axis if needed or flagged homeX = needX || parser.seen_test('X'), homeY = needY || parser.seen_test('Y'), - homeZZ = homeZ // UNUSED + homeZZ = homeZ, + homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME), ), - // Home-all if all or none are flagged - home_all = true LINEAR_AXIS_GANG(&& homeX == homeX, && homeX == homeY, && homeX == homeZ), - LINEAR_AXIS_LIST(doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ); - - UNUSED(needZ); - UNUSED(homeZZ); - - #if ENABLED(HOME_Z_FIRST) - - if (doZ) homeaxis(Z_AXIS); + home_all = LINEAR_AXIS_GANG( // Home-all if all or none are flagged + homeX == homeX, && homeY == homeX, && homeZ == homeX, + && homeI == homeX, && homeJ == homeX, && homeK == homeX + ), + LINEAR_AXIS_LIST( + doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ, + doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK + ); + #if HAS_Z_AXIS + UNUSED(needZ); UNUSED(homeZZ); + #else + constexpr bool doZ = false; #endif + TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS)); + const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; - if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ)))) { + if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); TERN_(BLTOUCH, bltouch.init()); } - #if ENABLED(QUICK_HOME) - - if (doX && doY) quick_home_xy(); - - #endif + TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); // Home Y (before X) if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) @@ -397,7 +399,7 @@ void GcodeSuite::G28() { TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); // Home Z last if homing towards the bed - #if DISABLED(HOME_Z_FIRST) + #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) if (doZ) { #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) stepper.set_all_z_lock(false); @@ -409,6 +411,16 @@ void GcodeSuite::G28() { } #endif + #if LINEAR_AXES >= 4 + if (doI) homeaxis(I_AXIS); + #endif + #if LINEAR_AXES >= 5 + if (doJ) homeaxis(J_AXIS); + #endif + #if LINEAR_AXES >= 6 + if (doK) homeaxis(K_AXIS); + #endif + sync_plan_position(); #endif @@ -480,6 +492,15 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(Y2) stepperY2.rms_current(tmc_save_current_Y2); #endif + #if HAS_CURRENT_HOME(I) + stepperI.rms_current(tmc_save_current_I); + #endif + #if HAS_CURRENT_HOME(J) + stepperJ.rms_current(tmc_save_current_J); + #endif + #if HAS_CURRENT_HOME(K) + stepperK.rms_current(tmc_save_current_K); + #endif #endif // HAS_HOMING_CURRENT ui.refresh(); @@ -498,11 +519,13 @@ void GcodeSuite::G28() { // Set L6470 absolute position registers to counts // constexpr *might* move this to PROGMEM. // If not, this will need a PROGMEM directive and an accessor. + #define _EN_ITEM(N) , E_AXIS static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = { - X_AXIS, Y_AXIS, Z_AXIS, - X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, - E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS), + X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS + REPEAT(E_STEPPERS, _EN_ITEM) }; + #undef _EN_ITEM for (uint8_t j = 1; j <= L64XX::chain[0]; j++) { const uint8_t cv = L64XX::chain[j]; L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv])); diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 723f1ebd7b..56b1555fc4 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -73,11 +73,23 @@ #if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif -#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) +#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) #define HAS_Y_CENTER 1 #endif +#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX) + #define HAS_I_CENTER 1 +#endif +#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX) + #define HAS_J_CENTER 1 +#endif +#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX) + #define HAS_K_CENTER 1 +#endif -enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES }; +enum side_t : uint8_t { + TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES, + LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM) +}; static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER; static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS; @@ -105,7 +117,7 @@ struct measurements_t { #endif inline void calibration_move() { - do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); } /** @@ -174,7 +186,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta destination = current_position; for (float travel = 0; travel < limit; travel += step) { destination[axis] += dir * step; - do_blocking_move_to(destination, mms); + do_blocking_move_to((xyz_pos_t)destination, mms); planner.synchronize(); if (read_calibration_pin() == stop_state) break; } @@ -209,7 +221,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, // Move back to the starting position destination = current_position; destination[axis] = start_pos; - do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); return measured_pos; } @@ -230,7 +242,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t park_above_object(m, uncertainty); switch (side) { - #if AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(X) + case RIGHT: dir = -1; + case LEFT: axis = X_AXIS; break; + #endif + #if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y) + case BACK: dir = -1; + case FRONT: axis = Y_AXIS; break; + #endif + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) case TOP: { const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); m.obj_center.z = measurement - dimensions.z / 2; @@ -238,13 +258,17 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if AXIS_CAN_CALIBRATE(X) - case RIGHT: dir = -1; - case LEFT: axis = X_AXIS; break; + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + case IMINIMUM: dir = -1; + case IMAXIMUM: axis = I_AXIS; break; #endif - #if AXIS_CAN_CALIBRATE(Y) - case BACK: dir = -1; - case FRONT: axis = Y_AXIS; break; + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + case JMINIMUM: dir = -1; + case JMAXIMUM: axis = J_AXIS; break; + #endif + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + case KMINIMUM: dir = -1; + case KMAXIMUM: axis = K_AXIS; break; #endif default: return; } @@ -289,14 +313,23 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMIN, probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMAX, probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMIN, probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMAX, probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMIN, probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMAX, probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge)); // Compute the measured center of the calibration object. - TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); - TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); + TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2); + TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2); + TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2); // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object @@ -310,14 +343,17 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { LINEAR_AXIS_CODE( m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x), m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y), - m.pos_error.z = true_center.z - m.obj_center.z + m.pos_error.z = true_center.z - m.obj_center.z, + m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i), + m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j), + m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k) ); } #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) @@ -326,11 +362,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_MEASURE_RIGHT) SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]); #endif - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #if HAS_Y_AXIS + #if ENABLED(CALIBRATION_MEASURE_FRONT) + SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_BACK) + SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #if LINEAR_AXES >= 4 + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 6 + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]); + #endif #endif SERIAL_EOL(); } @@ -344,6 +406,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y); #endif SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z); + #if HAS_I_CENTER + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i); + #endif + #if HAS_J_CENTER + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j); + #endif + #if HAS_K_CENTER + SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k); + #endif SERIAL_EOL(); } @@ -357,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); #endif #endif - #if AXIS_CAN_CALIBRATE(Y) + #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) #if ENABLED(CALIBRATION_MEASURE_FRONT) SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); #endif @@ -365,9 +436,33 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); #endif #endif - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif + #if LINEAR_AXES >= 4 AXIS_CAN_CALIBRATE(I) + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 AXIS_CAN_CALIBRATE(J) + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 6 AXIS_CAN_CALIBRATE(K) + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); + #endif + #endif SERIAL_EOL(); } @@ -375,29 +470,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_CHAR('T'); SERIAL_ECHO(active_extruder); SERIAL_ECHOLNPGM(" Positional Error:"); - #if HAS_X_CENTER + #if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X) SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x); #endif - #if HAS_Y_CENTER + #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); #endif - if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif + #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i); + #endif + #if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J) + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j); + #endif + #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif SERIAL_EOL(); } inline void report_measured_nozzle_dimensions(const measurements_t &m) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); - #if HAS_X_CENTER || HAS_Y_CENTER - #if HAS_X_CENTER - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); - #endif - #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); - #endif - #else - UNUSED(m); + #if HAS_X_CENTER + SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); + #endif + #if HAS_Y_CENTER + SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); #endif SERIAL_EOL(); + UNUSED(m); } #if HAS_HOTEND_OFFSET @@ -446,8 +549,33 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { backlash.distance_mm.y = m.backlash[BACK]; #endif - if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]; - #endif + TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]); + + #if HAS_I_CENTER + backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_IMIN) + backlash.distance_mm.i = m.backlash[IMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_IMAX) + backlash.distance_mm.i = m.backlash[IMAXIMUM]; + #endif + + #if HAS_J_CENTER + backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_JMIN) + backlash.distance_mm.j = m.backlash[JMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_JMAX) + backlash.distance_mm.j = m.backlash[JMAXIMUM]; + #endif + + #if HAS_K_CENTER + backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_KMIN) + backlash.distance_mm.k = m.backlash[KMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_KMAX) + backlash.distance_mm.k = m.backlash[KMAXIMUM]; + #endif + + #endif // BACKLASH_GCODE } #if ENABLED(BACKLASH_GCODE) @@ -458,7 +586,8 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); const xyz_float_t move = LINEAR_AXIS_ARRAY( - AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 + AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3, + AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3 ); current_position += move; calibration_move(); current_position -= move; calibration_move(); @@ -487,11 +616,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - #if HAS_MULTI_HOTEND - set_nozzle(m, extruder); - #else - UNUSED(extruder); - #endif + TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder)); probe_sides(m, uncertainty); @@ -510,6 +635,10 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS); if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS); + TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS)); + TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS)); + TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS)); + sync_plan_position(); } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 7de33c1f2a..f30de00a0f 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -52,7 +52,10 @@ void GcodeSuite::M425() { LINEAR_AXIS_CODE( case X_AXIS: return AXIS_CAN_CALIBRATE(X), case Y_AXIS: return AXIS_CAN_CALIBRATE(Y), - case Z_AXIS: return AXIS_CAN_CALIBRATE(Z) + case Z_AXIS: return AXIS_CAN_CALIBRATE(Z), + case I_AXIS: return AXIS_CAN_CALIBRATE(I), + case J_AXIS: return AXIS_CAN_CALIBRATE(J), + case K_AXIS: return AXIS_CAN_CALIBRATE(K), ); } }; diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index e765fd55b2..a2bcb8bb86 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -154,6 +154,9 @@ void GcodeSuite::M205() { if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION + #if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J') + #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation." + #endif if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { @@ -170,7 +173,10 @@ void GcodeSuite::M205() { if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()), if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()), if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()), - if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()) + if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units()) ); #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) if (seenZ && planner.max_jerk.z <= 0.1f) diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 100cf96f15..544c66a076 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -28,8 +28,11 @@ void report_M92(const bool echo=true, const int8_t e=-1) { SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]) - )); + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) + ); #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif @@ -67,7 +70,7 @@ void GcodeSuite::M92() { // No arguments? Show M92 report. if (!parser.seen( - LOGICAL_AXIS_GANG("E", "X", "Y", "Z") + LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) TERN_(MAGIC_NUMBERS_GCODE, "HL") )) return report_M92(true, target_extruder); diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index b7cec2d48d..4ebb81cf7e 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -33,12 +33,15 @@ * M17: Enable stepper motors */ void GcodeSuite::M17() { - if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) { + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { LOGICAL_AXIS_CODE( if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), if (parser.seen_test('X')) ENABLE_AXIS_X(), if (parser.seen_test('Y')) ENABLE_AXIS_Y(), - if (parser.seen_test('Z')) ENABLE_AXIS_Z() + if (parser.seen_test('Z')) ENABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K() ); } else { @@ -56,13 +59,16 @@ void GcodeSuite::M18_M84() { stepper_inactive_time = parser.value_millis_from_seconds(); } else { - if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) { + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { planner.synchronize(); LOGICAL_AXIS_CODE( if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), if (parser.seen_test('X')) DISABLE_AXIS_X(), if (parser.seen_test('Y')) DISABLE_AXIS_Y(), - if (parser.seen_test('Z')) DISABLE_AXIS_Z() + if (parser.seen_test('Z')) DISABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K() ); } else diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index ac84ac6217..23d43dd0a6 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -70,26 +70,12 @@ dual_x_carriage_mode = (DualXMode)parser.value_byte(); idex_set_mirrored_mode(false); - if (dual_x_carriage_mode == DXC_MIRRORED_MODE) { - if (previous_mode != DXC_DUPLICATION_MODE) { - SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); - SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); - dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - return; - } - idex_set_mirrored_mode(true); - float x_jog = current_position.x - .1; - for (uint8_t i = 2; --i;) { - planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0); - x_jog += .1; - } - return; - } - switch (dual_x_carriage_mode) { + case DXC_FULL_CONTROL_MODE: case DXC_AUTO_PARK_MODE: break; + case DXC_DUPLICATION_MODE: // Set the X offset, but no less than the safety gap if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS)); @@ -97,10 +83,29 @@ // Always switch back to tool 0 if (active_extruder != 0) tool_change(0); break; + + case DXC_MIRRORED_MODE: { + if (previous_mode != DXC_DUPLICATION_MODE) { + SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); + SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); + dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; + return; + } + idex_set_mirrored_mode(true); + + // Do a small 'jog' motion in the X axis + xyze_pos_t dest = current_position; dest.x -= 0.1f; + for (uint8_t i = 2; --i;) { + planner.buffer_line(dest, feedrate_mm_s, 0); + dest.x += 0.1f; + } + } return; + default: dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; break; } + idex_set_parked(false); set_duplication_enabled(false); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 05631e99d2..90fd6c487e 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -253,7 +253,7 @@ void GcodeSuite::M906() { #endif break; - #if LINEAR_AXES >= XY + #if HAS_Y_AXIS case Y_AXIS: #if AXIS_IS_L64XX(Y) if (index == 0) L6470_SET_KVAL_HOLD(Y); diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 670ea2a58b..79451235b1 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -47,12 +47,13 @@ void GcodeSuite::G60() { SBI(saved_slots[slot >> 3], slot & 0x07); #if ENABLED(SAVED_POSITIONS_DEBUG) - const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot); - DEBUG_ECHOPAIR_F(" : X", pos.x); - DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y); - DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z); - DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e); + const xyze_pos_t &pos = stored_position[slot]; + DEBUG_ECHOLNPAIR_F_P( + LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e, + PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, + SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k) + ); #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 00a6478f3d..a10c8217ef 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -45,7 +45,7 @@ void GcodeSuite::G61(void) { const uint8_t slot = parser.byteval('S'); - #define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT))) + #define SYNC_E(POINT) TERN_(HAS_EXTRUDERS, planner.set_e_position_mm((destination.e = current_position.e = (POINT)))) #if SAVED_POSITIONS < 256 if (slot >= SAVED_POSITIONS) { @@ -68,7 +68,7 @@ void GcodeSuite::G61(void) { SYNC_E(stored_position[slot].e); } else { - if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) { + if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); LOOP_LINEAR_AXES(i) { destination[i] = parser.seen(AXIS_CHAR(i)) diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 3b4406705c..52a6920f05 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -35,7 +35,7 @@ void GcodeSuite::M122() { xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); bool print_all = true; - LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } + LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; } if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true; @@ -49,21 +49,13 @@ void GcodeSuite::M122() { tmc_set_report_interval(interval); #endif - if (parser.seen_test('V')) { - tmc_get_registers( - LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) - ); - } - else { - tmc_report_all( - LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) - ); - } + if (parser.seen_test('V')) + tmc_get_registers(LOGICAL_AXIS_ELEM(print_axis)); + else + tmc_report_all(LOGICAL_AXIS_ELEM(print_axis)); #endif - test_tmc_connection( - LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z) - ); + test_tmc_connection(LOGICAL_AXIS_ELEM(print_axis)); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 4659616467..a3fb07df13 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -43,81 +43,56 @@ void tmc_set_stealthChop(TMC &st, const bool enable) { static void set_stealth_status(const bool enable, const int8_t target_extruder) { #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable) - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \ - || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \ - || AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) \ - || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \ + || I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \ + || X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP const uint8_t index = parser.byteval('I'); #endif LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index == 0) TMC_SET_STEALTH(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (index == 1) TMC_SET_STEALTH(X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X)); + TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2)); break; - #if LINEAR_AXES >= XY + #if HAS_Y_AXIS case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index == 0) TMC_SET_STEALTH(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (index == 1) TMC_SET_STEALTH(Y2); - #endif + TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2)); break; #endif #if HAS_Z_AXIS case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index == 0) TMC_SET_STEALTH(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 1) TMC_SET_STEALTH(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 2) TMC_SET_STEALTH(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 3) TMC_SET_STEALTH(Z4); - #endif + TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4)); break; #endif + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_STEALTH(I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_STEALTH(J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_STEALTH(K); break; + #endif + #if HAS_EXTRUDERS case E_AXIS: { if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_STEALTH(E0); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_STEALTH(E1); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_STEALTH(E2); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_STEALTH(E3); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_STEALTH(E4); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_STEALTH(E5); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_STEALTH(E6); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_STEALTH(E7); break; - #endif - } + OPTCODE(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_STEALTH(E0)) + OPTCODE(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_STEALTH(E1)) + OPTCODE(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_STEALTH(E2)) + OPTCODE(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_STEALTH(E3)) + OPTCODE(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_STEALTH(E4)) + OPTCODE(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_STEALTH(E5)) + OPTCODE(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_STEALTH(E6)) + OPTCODE(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_STEALTH(E7)) } break; #endif } @@ -126,55 +101,25 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder) static void say_stealth_status() { #define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q) - - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_STEALTH_STATUS(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_STEALTH_STATUS(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_STEALTH_STATUS(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_STEALTH_STATUS(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_STEALTH_STATUS(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_STEALTH_STATUS(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_STEALTH_STATUS(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_STEALTH_STATUS(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_STEALTH_STATUS(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_STEALTH_STATUS(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_STEALTH_STATUS(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_STEALTH_STATUS(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_STEALTH_STATUS(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_STEALTH_STATUS(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_STEALTH_STATUS(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_STEALTH_STATUS(E7); - #endif + OPTCODE( X_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X)) + OPTCODE(X2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X2)) + OPTCODE( Y_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y)) + OPTCODE(Y2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y2)) + OPTCODE( Z_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z)) + OPTCODE(Z2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z2)) + OPTCODE(Z3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z3)) + OPTCODE(Z4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z4)) + OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I)) + OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J)) + OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K)) + OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0)) + OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1)) + OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2)) + OPTCODE(E3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E3)) + OPTCODE(E4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E4)) + OPTCODE(E5_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E5)) + OPTCODE(E6_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E6)) + OPTCODE(E7_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E7)) } /** diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 848735b900..70e6a00b36 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -48,7 +48,7 @@ void GcodeSuite::M906() { bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif @@ -64,7 +64,7 @@ void GcodeSuite::M906() { #endif break; - #if LINEAR_AXES >= XY + #if HAS_Y_AXIS case Y_AXIS: #if AXIS_IS_TMC(Y) if (index == 0) TMC_SET_CURRENT(Y); @@ -92,6 +92,16 @@ void GcodeSuite::M906() { break; #endif + #if AXIS_IS_TMC(I) + case I_AXIS: TMC_SET_CURRENT(I); break; + #endif + #if AXIS_IS_TMC(J) + case J_AXIS: TMC_SET_CURRENT(J); break; + #endif + #if AXIS_IS_TMC(K) + case K_AXIS: TMC_SET_CURRENT(K); break; + #endif + #if HAS_EXTRUDERS case E_AXIS: { const int8_t target_extruder = get_target_extruder_from_command(); @@ -152,6 +162,15 @@ void GcodeSuite::M906() { #if AXIS_IS_TMC(Z4) TMC_SAY_CURRENT(Z4); #endif + #if AXIS_IS_TMC(I) + TMC_SAY_CURRENT(I); + #endif + #if AXIS_IS_TMC(J) + TMC_SAY_CURRENT(J); + #endif + #if AXIS_IS_TMC(K) + TMC_SAY_CURRENT(K); + #endif #if AXIS_IS_TMC(E0) TMC_SAY_CURRENT(E0); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index c4b4a8772e..747f1c9516 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -38,18 +38,27 @@ #if M91x_USE(X) || M91x_USE(X2) #define M91x_SOME_X 1 #endif - #if M91x_USE(Y) || M91x_USE(Y2) + #if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2)) #define M91x_SOME_Y 1 #endif - #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4) + #if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) #define M91x_SOME_Z 1 #endif + #if LINEAR_AXES >= 4 && M91x_USE(I) + #define M91x_USE_I 1 + #endif + #if LINEAR_AXES >= 5 && M91x_USE(J) + #define M91x_USE_J 1 + #endif + #if LINEAR_AXES >= 6 && M91x_USE(K) + #define M91x_USE_K 1 + #endif #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7) #define M91x_SOME_E 1 #endif - #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E + #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." #endif @@ -82,6 +91,9 @@ #if M91x_USE(Z4) tmc_report_otpw(stepperZ4); #endif + TERN_(M91x_USE_I, tmc_report_otpw(stepperI)); + TERN_(M91x_USE_J, tmc_report_otpw(stepperJ)); + TERN_(M91x_USE_K, tmc_report_otpw(stepperK)); #if M91x_USE_E(0) tmc_report_otpw(stepperE0); #endif @@ -124,9 +136,12 @@ const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)), hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)), hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)), + hasI = TERN0(M91x_USE_I, parser.seen(axis_codes.i)), + hasJ = TERN0(M91x_USE_J, parser.seen(axis_codes.j)), + hasK = TERN0(M91x_USE_K, parser.seen(axis_codes.k)), hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e)); - const bool hasNone = !hasE && !hasX && !hasY && !hasZ; + const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK; #if M91x_SOME_X const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); @@ -164,6 +179,19 @@ #endif #endif + #if M91x_USE_I + const int8_t ival = int8_t(parser.byteval(axis_codes.i, 0xFF)); + if (hasNone || ival == 1 || (hasI && ival < 0)) tmc_clear_otpw(stepperI); + #endif + #if M91x_USE_J + const int8_t jval = int8_t(parser.byteval(axis_codes.j, 0xFF)); + if (hasNone || jval == 1 || (hasJ && jval < 0)) tmc_clear_otpw(stepperJ); + #endif + #if M91x_USE_K + const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF)); + if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK); + #endif + #if M91x_SOME_E const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF)); #if M91x_USE_E(0) @@ -206,126 +234,76 @@ #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value) bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index < 2) TMC_SET_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (!(index & 1)) TMC_SET_PWMTHRS(X,X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2)); break; case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index < 2) TMC_SET_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2); - #endif + TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2)); break; + + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_PWMTHRS(I,I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_PWMTHRS(J,J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_PWMTHRS(K,K); break; + #endif + case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index < 2) TMC_SET_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4); - #endif + TERN_(Z_HAS_STEALTCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); break; case E_AXIS: { #if E_STEPPERS const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_PWMTHRS_E(0); break; - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_PWMTHRS_E(1); break; - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_PWMTHRS_E(2); break; - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_PWMTHRS_E(3); break; - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_PWMTHRS_E(4); break; - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_PWMTHRS_E(5); break; - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_PWMTHRS_E(6); break; - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_PWMTHRS_E(7); break; - #endif - } + TERN_(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_PWMTHRS_E(0)); + TERN_(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_PWMTHRS_E(1)); + TERN_(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_PWMTHRS_E(2)); + TERN_(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_PWMTHRS_E(3)); + TERN_(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_PWMTHRS_E(4)); + TERN_(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_PWMTHRS_E(5)); + TERN_(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_PWMTHRS_E(6)); + TERN_(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_PWMTHRS_E(7)); #endif // E_STEPPERS } break; } } if (report) { - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_PWMTHRS(X,X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_PWMTHRS(Y,Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_PWMTHRS(Z,Z4); - #endif - #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_PWMTHRS_E(0); - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_PWMTHRS_E(1); - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_PWMTHRS_E(2); - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_PWMTHRS_E(3); - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_PWMTHRS_E(4); - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_PWMTHRS_E(5); - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_PWMTHRS_E(6); - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_PWMTHRS_E(7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z4)); + + TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I)); + TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J)); + TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K)); + + TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7)); } } #endif // HYBRID_THRESHOLD @@ -378,6 +356,15 @@ #endif break; #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + case I_AXIS: stepperI.homing_threshold(value); break; + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + case J_AXIS: stepperJ.homing_threshold(value); break; + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + case K_AXIS: stepperK.homing_threshold(value); break; + #endif } } @@ -412,6 +399,15 @@ tmc_print_sgt(stepperZ4); #endif #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + tmc_print_sgt(stepperI); + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + tmc_print_sgt(stepperJ); + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + tmc_print_sgt(stepperK); + #endif } } #endif // USE_SENSORLESS diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index b7a842ece7..eb650851f8 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -78,7 +78,10 @@ uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( | (ar_init.e << REL_E), | (ar_init.x << REL_X), | (ar_init.y << REL_Y), - | (ar_init.z << REL_Z) + | (ar_init.z << REL_Z), + | (ar_init.i << REL_I), + | (ar_init.j << REL_J), + | (ar_init.k << REL_K) ); #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 05b6c0cdd5..abd7f07916 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -315,7 +315,7 @@ #endif enum AxisRelative : uint8_t { - LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z) + LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K) #if HAS_EXTRUDERS , E_MODE_ABS, E_MODE_REL #endif @@ -338,7 +338,11 @@ public: return TEST(axis_relative, a); } static inline void set_relative_mode(const bool rel) { - axis_relative = rel ? (0 LOGICAL_AXIS_GANG(| _BV(REL_E), | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z))) : 0; + axis_relative = rel ? (0 LOGICAL_AXIS_GANG( + | _BV(REL_E), + | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z), + | _BV(REL_I), | _BV(REL_J), | _BV(REL_K) + )) : 0; } #if HAS_EXTRUDERS static inline void set_e_relative() { diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index e65540eb8c..51f3e7c14c 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -31,7 +31,16 @@ #include "../../MarlinCore.h" void M206_report() { - SERIAL_ECHOLNPAIR_P(PSTR("M206 X"), home_offset.x, SP_Y_STR, home_offset.y, SP_Z_STR, home_offset.z); + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + PSTR("M206 X"), home_offset.x, + SP_Y_STR, home_offset.y, + SP_Z_STR, home_offset.z, + SP_I_STR, home_offset.i, + SP_J_STR, home_offset.j, + SP_K_STR, home_offset.k, + ) + ); } /** @@ -51,7 +60,7 @@ void GcodeSuite::M206() { if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi #endif - if (!parser.seen("XYZ")) + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K"))) M206_report(); else report_current_position(); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index d28373696a..2fdce1edfd 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -125,6 +125,15 @@ #if AXIS_IS_L64XX(Z4) REPORT_ABSOLUTE_POS(Z4); #endif + #if AXIS_IS_L64XX(I) + REPORT_ABSOLUTE_POS(I); + #endif + #if AXIS_IS_L64XX(J) + REPORT_ABSOLUTE_POS(J); + #endif + #if AXIS_IS_L64XX(K) + REPORT_ABSOLUTE_POS(K); + #endif #if AXIS_IS_L64XX(E0) REPORT_ABSOLUTE_POS(E0); #endif @@ -170,7 +179,13 @@ SERIAL_ECHOPGM("FromStp:"); get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) - xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(planner.get_axis_position_mm(E_AXIS), cartes.x, cartes.y, cartes.z); + xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) + ); report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 30f8248037..eb79180c69 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -52,7 +52,10 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { LINEAR_AXIS_GANG( (parser.seen_test('X') ? _BV(X_AXIS) : 0), | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0), - | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0)) + | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0), + | (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0), + | (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0), + | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0)) ) #endif ) { @@ -85,7 +88,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (fwretract.autoretract_enabled && parser.seen_test('E') && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) { + if (fwretract.autoretract_enabled && parser.seen_test('E') + && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) + ) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 4d9f5559fe..170789d827 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -63,7 +63,7 @@ void plan_arc( case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break; } #else - constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS; + constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS); #endif // Radius vector from center to current location @@ -73,8 +73,8 @@ void plan_arc( center_P = current_position[p_axis] - rvec.a, center_Q = current_position[q_axis] - rvec.b, rt_X = cart[p_axis] - center_P, - rt_Y = cart[q_axis] - center_Q, - start_L = current_position[l_axis]; + rt_Y = cart[q_axis] - center_Q + OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]); #ifdef MIN_ARC_SEGMENTS uint16_t min_segments = MIN_ARC_SEGMENTS; @@ -109,8 +109,9 @@ void plan_arc( #endif } - float linear_travel = cart[l_axis] - start_L; - + #if HAS_Z_AXIS + float linear_travel = cart[l_axis] - start_L; + #endif #if HAS_EXTRUDERS float extruder_travel = cart.e - current_position.e; #endif @@ -118,9 +119,11 @@ void plan_arc( // If circling around... if (ENABLED(ARC_P_CIRCLES) && circles) { const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder - part_per_circle = RADIANS(360) / total_angular, // Each circle's part of the total - l_per_circle = linear_travel * part_per_circle; // L movement per circle + part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total + #if HAS_Z_AXIS + const float l_per_circle = linear_travel * part_per_circle; // L movement per circle + #endif #if HAS_EXTRUDERS const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle #endif @@ -128,17 +131,15 @@ void plan_arc( xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position for (uint16_t n = circles; n--;) { TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis - temp_position[l_axis] += l_per_circle; // Destination L axis + TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle); // Destination L axis plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle } - linear_travel = cart[l_axis] - current_position[l_axis]; - #if HAS_EXTRUDERS - extruder_travel = cart.e - current_position.e; - #endif + TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]); + TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e); } const float flat_mm = radius * angular_travel, - mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm); + mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) ABS(flat_mm); if (mm_of_travel < 0.001f) return; const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); @@ -187,17 +188,19 @@ void plan_arc( // Vector rotation matrix values xyze_pos_t raw; const float theta_per_segment = angular_travel / segments, - linear_per_segment = linear_travel / segments, sq_theta_per_segment = sq(theta_per_segment), sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6, cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation + #if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL) + const float linear_per_segment = linear_travel / segments; + #endif #if HAS_EXTRUDERS const float extruder_per_segment = extruder_travel / segments; #endif // Initialize the linear axis - raw[l_axis] = current_position[l_axis]; + TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]); // Initialize the extruder axis TERN_(HAS_EXTRUDERS, raw.e = current_position.e); @@ -246,11 +249,8 @@ void plan_arc( // Update raw location raw[p_axis] = center_P + rvec.a; raw[q_axis] = center_Q + rvec.b; - #if ENABLED(AUTO_BED_LEVELING_UBL) - raw[l_axis] = start_L; - UNUSED(linear_per_segment); - #else - raw[l_axis] += linear_per_segment; + #if HAS_Z_AXIS + raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment); #endif TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment); @@ -268,7 +268,7 @@ void plan_arc( // Ensure last segment arrives at target location. raw = cart; - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); apply_motion_limits(raw); @@ -280,7 +280,7 @@ void plan_arc( OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); current_position = raw; } // plan_arc diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 1f0d494baf..2b57a6b99a 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M290() { } #endif - if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z")) || parser.seen('R')) { + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index b07e92555c..e4e2973449 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -248,7 +248,7 @@ void GCodeParser::parse(char *p) { case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return; #endif - LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':) + LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:) case 'F': if (motion_mode_codenum < 0) return; command_letter = 'G'; diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index dc3f3c35fb..5a1748cc4d 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -226,7 +226,7 @@ public: // Seen any axis parameter static inline bool seen_axis() { - return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z")); + return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)); } #if ENABLED(GCODE_QUOTED_STRINGS) diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 73dc82b8df..dcb0d34ffe 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -83,6 +83,8 @@ void GcodeSuite::M106() { if (!got_preset && parser.seenval('S')) speed = parser.value_ushort(); + TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat + // Set speed, with constraint thermalManager.set_fan_speed(pfan, speed); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 8e4241bf64..07c0439e28 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -612,6 +612,12 @@ #ifndef LINEAR_AXES #define LINEAR_AXES XYZ #endif +#if LINEAR_AXES >= XY + #define HAS_Y_AXIS 1 + #if LINEAR_AXES >= XYZ + #define HAS_Z_AXIS 1 + #endif +#endif /** * Number of Logical Axes (e.g., XYZE) @@ -624,10 +630,6 @@ #define LOGICAL_AXES LINEAR_AXES #endif -#if LINEAR_AXES >= XYZ - #define HAS_Z_AXIS 1 -#endif - /** * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. * @@ -852,6 +854,21 @@ #elif Z_HOME_DIR < 0 #define Z_HOME_TO_MIN 1 #endif +#if I_HOME_DIR > 0 + #define I_HOME_TO_MAX 1 +#elif I_HOME_DIR < 0 + #define I_HOME_TO_MIN 1 +#endif +#if J_HOME_DIR > 0 + #define J_HOME_TO_MAX 1 +#elif J_HOME_DIR < 0 + #define J_HOME_TO_MIN 1 +#endif +#if K_HOME_DIR > 0 + #define K_HOME_TO_MAX 1 +#elif K_HOME_DIR < 0 + #define K_HOME_TO_MIN 1 +#endif /** * Conditionals based on the type of Bed Probe @@ -1110,13 +1127,22 @@ #ifndef INVERT_X_DIR #define INVERT_X_DIR false #endif -#ifndef INVERT_Y_DIR +#if HAS_Y_AXIS && !defined(INVERT_Y_DIR) #define INVERT_Y_DIR false #endif -#ifndef INVERT_Z_DIR +#if HAS_Z_AXIS && !defined(INVERT_Z_DIR) #define INVERT_Z_DIR false #endif -#ifndef INVERT_E_DIR +#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR) + #define INVERT_I_DIR false +#endif +#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR) + #define INVERT_J_DIR false +#endif +#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR) + #define INVERT_K_DIR false +#endif +#if HAS_EXTRUDERS && !defined(INVERT_E_DIR) #define INVERT_E_DIR false #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 18082044e0..f88d28e1a1 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -26,6 +26,10 @@ * Defines that depend on advanced configuration. */ +#ifndef AXIS_RELATIVE_MODES + #define AXIS_RELATIVE_MODES {} +#endif + #ifdef SWITCHING_NOZZLE_E1_SERVO_NR #define SWITCHING_NOZZLE_TWO_SERVOS 1 #endif @@ -488,12 +492,26 @@ // Remove unused STEALTHCHOP flags #if LINEAR_AXES < 6 #undef STEALTHCHOP_K + #undef CALIBRATION_MEASURE_KMIN + #undef CALIBRATION_MEASURE_KMAX #if LINEAR_AXES < 5 #undef STEALTHCHOP_J + #undef CALIBRATION_MEASURE_JMIN + #undef CALIBRATION_MEASURE_JMAX #if LINEAR_AXES < 4 #undef STEALTHCHOP_I + #undef CALIBRATION_MEASURE_IMIN + #undef CALIBRATION_MEASURE_IMAX #if LINEAR_AXES < 3 + #undef Z_IDLE_HEIGHT #undef STEALTHCHOP_Z + #undef Z_PROBE_SLED + #undef Z_SAFE_HOMING + #undef HOME_Z_FIRST + #undef HOMING_Z_WITH_PROBE + #undef ENABLE_LEVELING_FADE_HEIGHT + #undef NUM_Z_STEPPER_DRIVERS + #undef CNC_WORKSPACE_PLANES #if LINEAR_AXES < 2 #undef STEALTHCHOP_Y #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index a0e5db301e..d28822cf38 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -78,17 +78,49 @@ /** * Axis lengths and center */ +#ifndef AXIS4_NAME + #define AXIS4_NAME 'A' +#endif +#ifndef AXIS5_NAME + #define AXIS5_NAME 'B' +#endif +#ifndef AXIS6_NAME + #define AXIS6_NAME 'C' +#endif + #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS)) -#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) -#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#if HAS_Y_AXIS + #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) +#endif +#if HAS_Z_AXIS + #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#endif +#if LINEAR_AXES >= 4 + #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS)) +#endif +#if LINEAR_AXES >= 5 + #define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS)) +#endif +#if LINEAR_AXES >= 6 + #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS)) +#endif // Defined only if the sanity-check is bypassed #ifndef X_BED_SIZE #define X_BED_SIZE X_MAX_LENGTH #endif -#ifndef Y_BED_SIZE +#if HAS_Y_AXIS && !defined(Y_BED_SIZE) #define Y_BED_SIZE Y_MAX_LENGTH #endif +#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE) + #define I_BED_SIZE I_MAX_LENGTH +#endif +#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE) + #define J_BED_SIZE J_MAX_LENGTH +#endif +#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE) + #define K_BED_SIZE K_MAX_LENGTH +#endif // Require 0,0 bed center for Delta and SCARA #if IS_KINEMATIC @@ -97,16 +129,53 @@ // Define center values for future use #define _X_HALF_BED ((X_BED_SIZE) / 2) -#define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#if HAS_Y_AXIS + #define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 4 + #define _I_HALF_IMAX ((I_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 5 + #define _J_HALF_JMAX ((J_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 6 + #define _K_HALF_KMAX ((K_BED_SIZE) / 2) +#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) -#define XY_CENTER { X_CENTER, Y_CENTER } +#if HAS_Y_AXIS + #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) + #define XY_CENTER { X_CENTER, Y_CENTER } +#endif +#if LINEAR_AXES >= 4 + #define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED) +#endif +#if LINEAR_AXES >= 5 + #define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED) +#endif +#if LINEAR_AXES >= 6 + #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED) +#endif // Get the linear boundaries of the bed #define X_MIN_BED (X_CENTER - _X_HALF_BED) #define X_MAX_BED (X_MIN_BED + X_BED_SIZE) -#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) -#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#if HAS_Y_AXIS + #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) + #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#endif +#if LINEAR_AXES >= 4 + #define I_MINIM (I_CENTER - _I_HALF_BED_SIZE) + #define I_MAXIM (I_MINIM + I_BED_SIZE) +#endif +#if LINEAR_AXES >= 5 + #define J_MINIM (J_CENTER - _J_HALF_BED_SIZE) + #define J_MAXIM (J_MINIM + J_BED_SIZE) +#endif +#if LINEAR_AXES >= 6 + #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE) + #define K_MAXIM (K_MINIM + K_BED_SIZE) +#endif /** * Dual X Carriage @@ -163,14 +232,16 @@ #endif #endif -#ifdef MANUAL_Y_HOME_POS - #define Y_HOME_POS MANUAL_Y_HOME_POS -#else - #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) - #if ENABLED(BED_CENTER_AT_0_0) - #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) +#if HAS_Y_AXIS + #ifdef MANUAL_Y_HOME_POS + #define Y_HOME_POS MANUAL_Y_HOME_POS #else - #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) + #else + #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #endif #endif #endif @@ -180,6 +251,28 @@ #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) #endif +#if LINEAR_AXES >= 4 + #ifdef MANUAL_I_HOME_POS + #define I_HOME_POS MANUAL_I_HOME_POS + #else + #define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 5 + #ifdef MANUAL_J_HOME_POS + #define J_HOME_POS MANUAL_J_HOME_POS + #else + #define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 6 + #ifdef MANUAL_K_HOME_POS + #define K_HOME_POS MANUAL_K_HOME_POS + #else + #define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS) + #endif +#endif + /** * If DELTA_HEIGHT isn't defined use the old setting */ @@ -374,15 +467,24 @@ #ifndef DISABLE_INACTIVE_X #define DISABLE_INACTIVE_X DISABLE_X #endif -#ifndef DISABLE_INACTIVE_Y +#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y) #define DISABLE_INACTIVE_Y DISABLE_Y #endif -#ifndef DISABLE_INACTIVE_Z +#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z) #define DISABLE_INACTIVE_Z DISABLE_Z #endif #ifndef DISABLE_INACTIVE_E #define DISABLE_INACTIVE_E DISABLE_E #endif +#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I) + #define DISABLE_INACTIVE_I DISABLE_I +#endif +#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J) + #define DISABLE_INACTIVE_J DISABLE_J +#endif +#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K) + #define DISABLE_INACTIVE_K DISABLE_K +#endif /** * Power Supply @@ -1418,6 +1520,15 @@ #if ENABLED(USE_ZMAX_PLUG) #define ENDSTOPPULLUP_ZMAX #endif + #if ENABLED(USE_IMAX_PLUG) + #define ENDSTOPPULLUP_IMAX + #endif + #if ENABLED(USE_JMAX_PLUG) + #define ENDSTOPPULLUP_JMAX + #endif + #if ENABLED(USE_KMAX_PLUG) + #define ENDSTOPPULLUP_KMAX + #endif #if ENABLED(USE_XMIN_PLUG) #define ENDSTOPPULLUP_XMIN #endif @@ -1427,6 +1538,15 @@ #if ENABLED(USE_ZMIN_PLUG) #define ENDSTOPPULLUP_ZMIN #endif + #if ENABLED(USE_IMIN_PLUG) + #define ENDSTOPPULLUP_IMIN + #endif + #if ENABLED(USE_JMIN_PLUG) + #define ENDSTOPPULLUP_JMIN + #endif + #if ENABLED(USE_KMIN_PLUG) + #define ENDSTOPPULLUP_KMIN + #endif #endif /** @@ -1484,82 +1604,137 @@ #define HAS_X2_MS_PINS 1 #endif -#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) - #define HAS_Y_ENABLE 1 -#endif -#if PIN_EXISTS(Y_DIR) - #define HAS_Y_DIR 1 -#endif -#if PIN_EXISTS(Y_STEP) - #define HAS_Y_STEP 1 -#endif -#if PIN_EXISTS(Y_MS1) - #define HAS_Y_MS_PINS 1 +#if HAS_Y_AXIS + #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) + #define HAS_Y_ENABLE 1 + #endif + #if PIN_EXISTS(Y_DIR) + #define HAS_Y_DIR 1 + #endif + #if PIN_EXISTS(Y_STEP) + #define HAS_Y_STEP 1 + #endif + #if PIN_EXISTS(Y_MS1) + #define HAS_Y_MS_PINS 1 + #endif + + #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) + #define HAS_Y2_ENABLE 1 + #endif + #if PIN_EXISTS(Y2_DIR) + #define HAS_Y2_DIR 1 + #endif + #if PIN_EXISTS(Y2_STEP) + #define HAS_Y2_STEP 1 + #endif + #if PIN_EXISTS(Y2_MS1) + #define HAS_Y2_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) - #define HAS_Y2_ENABLE 1 -#endif -#if PIN_EXISTS(Y2_DIR) - #define HAS_Y2_DIR 1 -#endif -#if PIN_EXISTS(Y2_STEP) - #define HAS_Y2_STEP 1 -#endif -#if PIN_EXISTS(Y2_MS1) - #define HAS_Y2_MS_PINS 1 +#if HAS_Z_AXIS + #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) + #define HAS_Z_ENABLE 1 + #endif + #if PIN_EXISTS(Z_DIR) + #define HAS_Z_DIR 1 + #endif + #if PIN_EXISTS(Z_STEP) + #define HAS_Z_STEP 1 + #endif + #if PIN_EXISTS(Z_MS1) + #define HAS_Z_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) - #define HAS_Z_ENABLE 1 -#endif -#if PIN_EXISTS(Z_DIR) - #define HAS_Z_DIR 1 -#endif -#if PIN_EXISTS(Z_STEP) - #define HAS_Z_STEP 1 -#endif -#if PIN_EXISTS(Z_MS1) - #define HAS_Z_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 2 + #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) + #define HAS_Z2_ENABLE 1 + #endif + #if PIN_EXISTS(Z2_DIR) + #define HAS_Z2_DIR 1 + #endif + #if PIN_EXISTS(Z2_STEP) + #define HAS_Z2_STEP 1 + #endif + #if PIN_EXISTS(Z2_MS1) + #define HAS_Z2_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) - #define HAS_Z2_ENABLE 1 -#endif -#if PIN_EXISTS(Z2_DIR) - #define HAS_Z2_DIR 1 -#endif -#if PIN_EXISTS(Z2_STEP) - #define HAS_Z2_STEP 1 -#endif -#if PIN_EXISTS(Z2_MS1) - #define HAS_Z2_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 3 + #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) + #define HAS_Z3_ENABLE 1 + #endif + #if PIN_EXISTS(Z3_DIR) + #define HAS_Z3_DIR 1 + #endif + #if PIN_EXISTS(Z3_STEP) + #define HAS_Z3_STEP 1 + #endif + #if PIN_EXISTS(Z3_MS1) + #define HAS_Z3_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) - #define HAS_Z3_ENABLE 1 -#endif -#if PIN_EXISTS(Z3_DIR) - #define HAS_Z3_DIR 1 -#endif -#if PIN_EXISTS(Z3_STEP) - #define HAS_Z3_STEP 1 -#endif -#if PIN_EXISTS(Z3_MS1) - #define HAS_Z3_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 4 + #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) + #define HAS_Z4_ENABLE 1 + #endif + #if PIN_EXISTS(Z4_DIR) + #define HAS_Z4_DIR 1 + #endif + #if PIN_EXISTS(Z4_STEP) + #define HAS_Z4_STEP 1 + #endif + #if PIN_EXISTS(Z4_MS1) + #define HAS_Z4_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) - #define HAS_Z4_ENABLE 1 +#if LINEAR_AXES >= 4 + #if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) + #define HAS_I_ENABLE 1 + #endif + #if PIN_EXISTS(I_DIR) + #define HAS_I_DIR 1 + #endif + #if PIN_EXISTS(I_STEP) + #define HAS_I_STEP 1 + #endif + #if PIN_EXISTS(I_MS1) + #define HAS_I_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_DIR) - #define HAS_Z4_DIR 1 + +#if LINEAR_AXES >= 5 + #if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) + #define HAS_J_ENABLE 1 + #endif + #if PIN_EXISTS(J_DIR) + #define HAS_J_DIR 1 + #endif + #if PIN_EXISTS(J_STEP) + #define HAS_J_STEP 1 + #endif + #if PIN_EXISTS(J_MS1) + #define HAS_J_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_STEP) - #define HAS_Z4_STEP 1 -#endif -#if PIN_EXISTS(Z4_MS1) - #define HAS_Z4_MS_PINS 1 + +#if LINEAR_AXES >= 6 + #if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) + #define HAS_K_ENABLE 1 + #endif + #if PIN_EXISTS(K_DIR) + #define HAS_K_DIR 1 + #endif + #if PIN_EXISTS(K_STEP) + #define HAS_K_STEP 1 + #endif + #if PIN_EXISTS(K_MS1) + #define HAS_K_MS_PINS 1 + #endif #endif // Extruder steppers and solenoids @@ -1700,7 +1875,7 @@ // #if HAS_TRINAMIC_CONFIG - #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) + #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K) #define STEALTHCHOP_ENABLED 1 #endif #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) @@ -1737,6 +1912,65 @@ #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) #define Z4_SENSORLESS 1 #endif + + #if AXIS_HAS_STEALTHCHOP(X) + #define X_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X2) + #define X2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + #define Y_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + #define Y2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + #define Z_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z3) + #define Z3_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z4) + #define Z4_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(I) + #define I_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(J) + #define J_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(K) + #define K_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0) + #define E0_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) + #define E1_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) + #define E2_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) + #define E3_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) + #define E4_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) + #define E5_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) + #define E6_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) + #define E7_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) #define X_SPI_SENSORLESS X_SENSORLESS #define Y_SPI_SENSORLESS Y_SENSORLESS @@ -1766,6 +2000,21 @@ #ifndef Z4_INTERPOLATE #define Z4_INTERPOLATE INTERPOLATE #endif + #if LINEAR_AXES >= 4 + #ifndef I_INTERPOLATE + #define I_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 5 + #ifndef J_INTERPOLATE + #define J_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 6 + #ifndef K_INTERPOLATE + #define K_INTERPOLATE INTERPOLATE + #endif + #endif #ifndef E0_INTERPOLATE #define E0_INTERPOLATE INTERPOLATE #endif @@ -1799,6 +2048,15 @@ #ifndef Z_SLAVE_ADDRESS #define Z_SLAVE_ADDRESS 0 #endif + #ifndef I_SLAVE_ADDRESS + #define I_SLAVE_ADDRESS 0 + #endif + #ifndef J_SLAVE_ADDRESS + #define J_SLAVE_ADDRESS 0 + #endif + #ifndef K_SLAVE_ADDRESS + #define K_SLAVE_ADDRESS 0 + #endif #ifndef X2_SLAVE_ADDRESS #define X2_SLAVE_ADDRESS 0 #endif @@ -1853,6 +2111,10 @@ #define HAS_TMC_SW_SERIAL 1 #endif +#if !USE_SENSORLESS + #undef SENSORLESS_BACKOFF_MM +#endif + // // Set USING_HW_SERIALn flags for used Serial Ports // @@ -1972,18 +2234,36 @@ #if _HAS_STOP(X,MAX) #define HAS_X_MAX 1 #endif -#if _HAS_STOP(Y,MIN) +#if HAS_Y_AXIS && _HAS_STOP(Y,MIN) #define HAS_Y_MIN 1 #endif -#if _HAS_STOP(Y,MAX) +#if HAS_Y_AXIS && _HAS_STOP(Y,MAX) #define HAS_Y_MAX 1 #endif -#if _HAS_STOP(Z,MIN) +#if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN) #define HAS_Z_MIN 1 #endif -#if _HAS_STOP(Z,MAX) +#if BOTH(HAS_Z_AXIS, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif +#if _HAS_STOP(I,MIN) + #define HAS_I_MIN 1 +#endif +#if _HAS_STOP(I,MAX) + #define HAS_I_MAX 1 +#endif +#if _HAS_STOP(J,MIN) + #define HAS_J_MIN 1 +#endif +#if _HAS_STOP(J,MAX) + #define HAS_J_MAX 1 +#endif +#if _HAS_STOP(K,MIN) + #define HAS_K_MIN 1 +#endif +#if _HAS_STOP(K,MAX) + #define HAS_K_MAX 1 +#endif #if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif @@ -2365,7 +2645,7 @@ #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS) +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 936f83915f..ee6fae0976 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -34,6 +34,10 @@ #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain." #endif +// Strings for sanity check messages +#define _LINEAR_AXES_STR LINEAR_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ") +#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ") + // Make sure macros aren't borked #define TEST1 #define TEST2 1 @@ -566,6 +570,9 @@ #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." #endif +constexpr float sbm[] = AXIS_RELATIVE_MODES; +static_assert(COUNT(sbm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements."); + /** * Probe temp compensation requirements */ @@ -644,14 +651,18 @@ #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y) #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined." -#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) - #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." -#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) - #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." -#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) - #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." -#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) - #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." +#endif + +#if HAS_Z_AXIS + #if !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) + #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." + #elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) + #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." + #elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) + #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." + #elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) + #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." + #endif #endif /** @@ -704,6 +715,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN." #elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN." +#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) + #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN." +#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) + #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN." +#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) + #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN." #endif /** @@ -926,6 +943,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif +/** + * Instant Freeze + */ +#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) + #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." +#endif + /** * Individual axis homing is useless for DELTAS */ @@ -1266,6 +1290,42 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER." #endif +/** + * Features that require a min/max/specific LINEAR_AXES + */ +#if HAS_LEVELING && !HAS_Z_AXIS + #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis." +#elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS + #error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3" +#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ + #error "DIRECT_STEPPING currently requires LINEAR_AXES 3" +#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5 + #error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5." +#endif + +/** + * Allow only extra axis codes that do not conflict with G-code parameter names + */ +#if LINEAR_AXES >= 4 + #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W' + #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME + #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME" + #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' + #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME + #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME." + #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' + #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif + /** * Kinematics */ @@ -1273,8 +1333,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only one kinematic type to be defined */ -#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY) - #error "Please enable only one of DELTA, MORGAN_SCARA, AXEL_TPARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY." +#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV) + #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV." #endif /** @@ -1597,15 +1657,60 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * Homing + * Homing checks */ -constexpr float hbm[] = HOMING_BUMP_MM; -static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM requires one element per linear axis."); -LINEAR_AXIS_CODE( - static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."), - static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."), - static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0.") -); +#ifndef HOMING_BUMP_MM + #error "Required setting HOMING_BUMP_MM is missing!" +#elif !defined(HOMING_BUMP_DIVISOR) + #error "Required setting HOMING_BUMP_DIVISOR is missing!" +#else + constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR; + static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."), + static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."), + static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."), + static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."), + static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."), + static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.") + ); + static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."), + static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."), + static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."), + static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."), + static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."), + static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.") + ); +#endif + +#ifdef HOMING_BACKOFF_POST_MM + constexpr float hbp[] = HOMING_BACKOFF_POST_MM; + static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."), + static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."), + static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."), + static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."), + static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."), + static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.") + ); +#endif + +#ifdef SENSORLESS_BACKOFF_MM + constexpr float sbm[] = SENSORLESS_BACKOFF_MM; + static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."), + static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."), + static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."), + static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."), + static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."), + static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.") + ); +#endif + #if ENABLED(CODEPENDENT_XY_HOMING) #if ENABLED(QUICK_HOME) #error "QUICK_HOME is incompatible with CODEPENDENT_XY_HOMING." @@ -1625,9 +1730,9 @@ LINEAR_AXIS_CODE( /** * Make sure DISABLE_[XYZ] compatible with selected homing options */ -#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z) +#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K) #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) - #error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." + #error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." #endif #endif @@ -2085,7 +2190,7 @@ LINEAR_AXIS_CODE( #define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \ && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \ && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) ) -#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z)) +#define _AXIS_PLUG_UNUSED_TEST(A) (1 LINEAR_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K) ) ) // A machine with endstops must have a minimum of 3 #if HAS_ENDSTOPS @@ -2098,6 +2203,15 @@ LINEAR_AXIS_CODE( #if _AXIS_PLUG_UNUSED_TEST(Z) #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG." #endif + #if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I) + #error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG." + #endif + #if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J) + #error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG." + #endif + #if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K) + #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG." + #endif // Delta and Cartesian use 3 homing endstops #if NONE(IS_SCARA, SPI_ENDSTOPS) @@ -2109,6 +2223,18 @@ LINEAR_AXIS_CODE( #error "Enable USE_YMIN_PLUG when homing Y to MIN." #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) #error "Enable USE_YMAX_PLUG when homing Y to MAX." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG) + #error "Enable USE_IMIN_PLUG when homing I to MIN." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG) + #error "Enable USE_IMAX_PLUG when homing I to MAX." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG) + #error "Enable USE_JMIN_PLUG when homing J to MIN." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG) + #error "Enable USE_JMAX_PLUG when homing J to MAX." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG) + #error "Enable USE_KMIN_PLUG when homing K to MIN." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG) + #error "Enable USE_KMAX_PLUG when homing K to MAX." #endif #endif @@ -2503,6 +2629,12 @@ LINEAR_AXIS_CODE( #error "An SPI driven TMC driver on E6 requires E6_CS_PIN." #elif INVALID_TMC_SPI(E7) #error "An SPI driven TMC driver on E7 requires E7_CS_PIN." +#elif INVALID_TMC_SPI(I) + #error "An SPI driven TMC on I requires I_CS_PIN." +#elif INVALID_TMC_SPI(J) + #error "An SPI driven TMC on J requires J_CS_PIN." +#elif INVALID_TMC_SPI(K) + #error "An SPI driven TMC on K requires K_CS_PIN." #endif #undef INVALID_TMC_SPI @@ -2542,6 +2674,12 @@ LINEAR_AXIS_CODE( #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E7) #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I) + #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J) + #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K) + #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN." #endif #undef INVALID_TMC_UART @@ -2565,6 +2703,12 @@ LINEAR_AXIS_CODE( INVALID_TMC_ADDRESS(Z3); #elif AXIS_DRIVER_TYPE_Z4(TMC2209) INVALID_TMC_ADDRESS(Z4); +#elif AXIS_DRIVER_TYPE_I(TMC2209) + INVALID_TMC_ADDRESS(I); +#elif AXIS_DRIVER_TYPE_J(TMC2209) + INVALID_TMC_ADDRESS(J); +#elif AXIS_DRIVER_TYPE_K(TMC2209) + INVALID_TMC_ADDRESS(K); #elif AXIS_DRIVER_TYPE_E0(TMC2209) INVALID_TMC_ADDRESS(E0); #elif AXIS_DRIVER_TYPE_E1(TMC2209) @@ -2620,6 +2764,12 @@ LINEAR_AXIS_CODE( INVALID_TMC_MS(E6) #elif !TMC_MICROSTEP_IS_VALID(E7) INVALID_TMC_MS(E7) +#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I) + INVALID_TMC_MS(I) +#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J) + INVALID_TMC_MS(J) +#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K) + INVALID_TMC_MS(K) #endif #undef INVALID_TMC_MS #undef TMC_MICROSTEP_IS_VALID @@ -2640,6 +2790,15 @@ LINEAR_AXIS_CODE( #define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209) #define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209) #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) + #if LINEAR_AXES >= 4 + #define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209) + #endif + #if LINEAR_AXES >= 5 + #define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209) + #endif + #if LINEAR_AXES >= 6 + #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209) + #endif #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS) #if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN) @@ -2654,6 +2813,12 @@ LINEAR_AXIS_CODE( #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX." + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX." + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX." #endif #endif @@ -2698,6 +2863,42 @@ LINEAR_AXIS_CODE( #else #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX." #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN." + #else + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN." + #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX." + #else + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN." + #else + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX." + #else + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN." + #else + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX." + #else + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX." + #endif #endif #endif @@ -2712,6 +2913,9 @@ LINEAR_AXIS_CODE( #undef X_ENDSTOP_INVERTING #undef Y_ENDSTOP_INVERTING #undef Z_ENDSTOP_INVERTING + #undef I_ENDSTOP_INVERTING + #undef J_ENDSTOP_INVERTING + #undef K_ENDSTOP_INVERTING #endif // Sensorless probing requirements @@ -2774,6 +2978,12 @@ LINEAR_AXIS_CODE( #define CS_COMPARE Z2_CS_PIN #elif IN_CHAIN(Z3) #define CS_COMPARE Z3_CS_PIN + #elif IN_CHAIN(I) + #define CS_COMPARE I_CS_PIN + #elif IN_CHAIN(J) + #define CS_COMPARE J_CS_PIN + #elif IN_CHAIN(K) + #define CS_COMPARE K_CS_PIN #elif IN_CHAIN(E0) #define CS_COMPARE E0_CS_PIN #elif IN_CHAIN(E1) @@ -2793,6 +3003,7 @@ LINEAR_AXIS_CODE( #endif #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(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \ || 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 @@ -2803,6 +3014,13 @@ LINEAR_AXIS_CODE( #endif #undef IN_CHAIN +/** + * L64XX requirement + */ +#if HAS_L64XX && LINEAR_AXES >= 4 + #error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3." +#endif + /** * Digipot requirement */ @@ -2820,43 +3038,48 @@ LINEAR_AXIS_CODE( */ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, sanity_arr_2[] = DEFAULT_MAX_FEEDRATE, - sanity_arr_3[] = DEFAULT_MAX_ACCELERATION; + sanity_arr_3[] = DEFAULT_MAX_ACCELERATION, + sanity_arr_7[] = HOMING_FEEDRATE_MM_M; #define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0) #if HAS_MULTI_EXTRUDER #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" -#elif EXTRUDERS == 0 - #define _EXTRA_NOTE " (Note: EXTRUDERS is set to 0.)" #else - #define _EXTRA_NOTE "" + #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")" #endif -static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); -static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), "DEFAULT_MAX_FEEDRATE values must be positive."); -static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), "DEFAULT_MAX_ACCELERATION values must be positive."); +static_assert(COUNT(sanity_arr_7) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); +static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) + && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) + && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), + "HOMING_FEEDRATE_MM_M values must be positive."); + #if ENABLED(LIMITED_MAX_ACCEL_EDITING) #ifdef MAX_ACCEL_EDIT_VALUES constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES; - static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2) && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5) && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8), @@ -2867,8 +3090,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_MAX_FR_EDITING) #ifdef MAX_FEEDRATE_EDIT_VALUES constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES; - static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2) && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5) && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8), @@ -2879,8 +3102,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_JERK_EDITING) #ifdef MAX_JERK_EDIT_VALUES constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES; - static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2) && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5) && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8), @@ -3280,6 +3503,22 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if _BAD_DRIVER(Z) #error "Z_DRIVER_TYPE is not recognized." #endif +#if LINEAR_AXES >= 4 + #if _BAD_DRIVER(I) + #error "I_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 5 + #if _BAD_DRIVER(J) + #error "J_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 6 + #if _BAD_DRIVER(K) + #error "K_DRIVER_TYPE is not recognized." + #endif +#endif + #if _BAD_DRIVER(X2) #error "X2_DRIVER_TYPE is not recognized." #endif @@ -3323,7 +3562,5 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) // Misc. Cleanup #undef _TEST_PWM - -#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) - #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." -#endif +#undef _LINEAR_AXES_STR +#undef _LOGICAL_AXES_STR diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cba2db71c4..722c63e117 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02000801 +#define MARLIN_HEX_VERSION 02000900 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 76118d6814..777b56ac0e 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -1235,7 +1235,7 @@ inline ENCODER_DiffState get_encoder_state() { void HMI_Plan_Move(const feedRate_t fr_mm_s) { if (!planner.is_full()) { planner.synchronize(); - planner.buffer_line(current_position, fr_mm_s, active_extruder); + planner.buffer_line(current_position, fr_mm_s); DWIN_UpdateLCD(); } } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 4f9021064d..a18fcb14fa 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -697,13 +697,13 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif #endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index f174f38d96..fef7002ad8 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -59,19 +59,19 @@ extern xyz_int_t tmc_step; extern uint16_t lcd_default_light; -#if AXIS_HAS_STEALTHCHOP(X) +#if X_HAS_STEALTHCHOP extern uint16_t tmc_x_current; #endif -#if AXIS_HAS_STEALTHCHOP(Y) +#if Y_HAS_STEALTHCHOP extern uint16_t tmc_y_current; #endif -#if AXIS_HAS_STEALTHCHOP(Z) +#if Z_HAS_STEALTHCHOP extern uint16_t tmc_z_current; #endif -#if AXIS_HAS_STEALTHCHOP(E0) +#if E0_HAS_STEALTHCHOP extern uint16_t tmc_e0_current; #endif -#if AXIS_HAS_STEALTHCHOP(E1) +#if E1_HAS_STEALTHCHOP extern uint16_t tmc_e1_current; #endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 6d12d529a9..c648d06218 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -134,15 +134,15 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variabl void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { #if ENABLED(SENSORLESS_HOMING) - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP tmc_step.x = stepperX.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP tmc_step.y = stepperY.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP tmc_step.z = stepperZ.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif @@ -659,7 +659,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { case VP_TMC_X_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP stepperX.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.x = stepperX.homing_threshold(); @@ -668,7 +668,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; case VP_TMC_Y_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP stepperY.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.y = stepperY.homing_threshold(); @@ -677,7 +677,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; case VP_TMC_Z_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP stepperZ.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.z = stepperZ.homing_threshold(); @@ -737,15 +737,9 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; } #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) - tmc_step.x = stepperX.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_step.y = stepperY.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_step.z = stepperZ.homing_threshold(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); #endif } @@ -1419,15 +1413,9 @@ bool DGUSScreenHandler::loop() { if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) { booted = true; #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) - tmc_step.x = stepperX.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_step.y = stepperY.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_step.z = stepperZ.homing_threshold(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); #endif #if ENABLED(PREVENT_COLD_EXTRUSION) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp index 3648321dce..e79e88b6b0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp @@ -60,32 +60,32 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { ) .text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) .font(font_tiny); - #if PIN_EXISTS(X_MAX) + #if HAS_X_MAX PIN_ENABLED (1, 2, PSTR(STR_X_MAX), X_MAX, X_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(1, 2, PSTR(STR_X_MAX), X_MAX) #endif - #if PIN_EXISTS(Y_MAX) + #if HAS_Y_MAX PIN_ENABLED (3, 2, PSTR(STR_Y_MAX), Y_MAX, Y_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(3, 2, PSTR(STR_Y_MAX), Y_MAX) #endif - #if PIN_EXISTS(Z_MAX) + #if HAS_Z_MAX PIN_ENABLED (5, 2, PSTR(STR_Z_MAX), Z_MAX, Z_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(5, 2, PSTR(STR_Z_MAX), Z_MAX) #endif - #if PIN_EXISTS(X_MIN) + #if HAS_X_MIN PIN_ENABLED (1, 3, PSTR(STR_X_MIN), X_MIN, X_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(1, 3, PSTR(STR_X_MIN), X_MIN) #endif - #if PIN_EXISTS(Y_MIN) + #if HAS_Y_MIN PIN_ENABLED (3, 3, PSTR(STR_Y_MIN), Y_MIN, Y_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(3, 3, PSTR(STR_Y_MIN), Y_MIN) #endif - #if PIN_EXISTS(Z_MIN) + #if HAS_Z_MIN PIN_ENABLED (5, 3, PSTR(STR_Z_MIN), Z_MIN, Z_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(5, 3, PSTR(STR_Z_MIN), Z_MIN) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index b0f55a1d45..bf1b9c3459 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -68,30 +68,20 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { draw_return_ui(); break; - #if AXIS_HAS_STEALTHCHOP(X) - case ID_TMC_MODE_X: - toggle_chop(stepperX, buttonXState); - break; + #if X_HAS_STEALTHCHOP + case ID_TMC_MODE_X: toggle_chop(stepperX, buttonXState); break; #endif - #if AXIS_HAS_STEALTHCHOP(Y) - case ID_TMC_MODE_Y: - toggle_chop(stepperY, buttonYState); - break; + #if Y_HAS_STEALTHCHOP + case ID_TMC_MODE_Y: toggle_chop(stepperY, buttonYState); break; #endif - #if AXIS_HAS_STEALTHCHOP(Z) - case ID_TMC_MODE_Z: - toggle_chop(stepperZ, buttonZState); - break; + #if Z_HAS_STEALTHCHOP + case ID_TMC_MODE_Z: toggle_chop(stepperZ, buttonZState); break; #endif - #if AXIS_HAS_STEALTHCHOP(E0) - case ID_TMC_MODE_E0: - toggle_chop(stepperE0, buttonE0State); - break; + #if E0_HAS_STEALTHCHOP + case ID_TMC_MODE_E0: toggle_chop(stepperE0, buttonE0State); break; #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case ID_TMC_MODE_E1: - toggle_chop(stepperE1, buttonE1State); - break; + #if E1_HAS_STEALTHCHOP + case ID_TMC_MODE_E1: toggle_chop(stepperE1, buttonE1State); break; #endif case ID_TMC_MODE_UP: @@ -113,21 +103,11 @@ void lv_draw_tmc_step_mode_settings() { scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle); bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false; - #if AXIS_HAS_STEALTHCHOP(X) - stealth_X = stepperX.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - stealth_Y = stepperY.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - stealth_Z = stepperZ.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - stealth_E0 = stepperE0.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - stealth_E1 = stepperE1.get_stealthChop(); - #endif + TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop()); if (!uiCfg.para_ui_page) { buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 34b2c0bb5b..33f11c9ffd 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -72,6 +72,9 @@ namespace Language_en { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); @@ -85,6 +88,9 @@ namespace Language_en { PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); @@ -265,6 +271,9 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); @@ -329,12 +338,18 @@ namespace Language_en { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-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("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -343,6 +358,9 @@ namespace Language_en { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); @@ -353,6 +371,9 @@ namespace Language_en { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); @@ -486,6 +507,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; 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"); @@ -566,6 +590,9 @@ namespace Language_en { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("I Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("J Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("K Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); @@ -683,6 +710,9 @@ namespace Language_en { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 5c5ec9d3e1..a6719f1847 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -356,7 +356,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_FR_EDITING) DEFAULT_MAX_FEEDRATE #else - LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999) + LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999) #endif ; #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES) @@ -399,7 +399,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_ACCEL_EDITING) DEFAULT_MAX_ACCELERATION #else - LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000) + LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000) #endif ; #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES) @@ -477,7 +477,10 @@ void menu_backlash(); #else #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c) #endif - LINEAR_AXIS_CODE(EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C()); + LINEAR_AXIS_CODE( + EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(), + EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K) + ); #if HAS_EXTRUDERS EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e); @@ -515,7 +518,10 @@ void menu_advanced_steps_per_mm() { BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) - LINEAR_AXIS_CODE(EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C)); + LINEAR_AXIS_CODE( + EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C), + EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K) + ); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index c1dca025b1..b9adacc502 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -45,8 +45,21 @@ void menu_backlash() { #endif #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); - if (_CAN_CALI(B)) EDIT_BACKLASH_DISTANCE(B); - if (_CAN_CALI(C)) EDIT_BACKLASH_DISTANCE(C); + #if HAS_Y_AXIS && _CAN_CALI(B) + EDIT_BACKLASH_DISTANCE(B); + #endif + #if HAS_Z_AXIS && _CAN_CALI(C) + EDIT_BACKLASH_DISTANCE(C); + #endif + #if LINEAR_AXES >= 4 && _CAN_CALI(I) + EDIT_BACKLASH_DISTANCE(I); + #endif + #if LINEAR_AXES >= 5 && _CAN_CALI(J) + EDIT_BACKLASH_DISTANCE(J); + #endif + #if LINEAR_AXES >= 6 && _CAN_CALI(K) + EDIT_BACKLASH_DISTANCE(K); + #endif #ifdef BACKLASH_SMOOTHING_MM EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 516f04632e..076ece33b0 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -89,8 +89,21 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } -void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } -void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#if HAS_Y_AXIS + void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } +#endif +#if HAS_Z_AXIS + void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#endif +#if LINEAR_AXES >= 4 + void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); } +#endif +#if LINEAR_AXES >= 5 + void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); } +#endif +#if LINEAR_AXES >= 6 + void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); } +#endif #if E_MANUAL @@ -217,14 +230,27 @@ void menu_move() { if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) { if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) { SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); }); - SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #if HAS_Y_AXIS + SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #endif } #if ENABLED(DELTA) else ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); }); #endif - SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #if HAS_Z_AXIS + SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #endif + #if LINEAR_AXES >= 4 + SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); }); + #endif + #if LINEAR_AXES >= 5 + SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); }); + #endif + #if LINEAR_AXES >= 6 + SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); }); + #endif } else GCODES_ITEM(MSG_AUTO_HOME, G28_STR); @@ -321,8 +347,21 @@ void menu_motion() { GCODES_ITEM(MSG_AUTO_HOME, G28_STR); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #if HAS_Y_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + #endif + #if HAS_Z_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #endif + #if LINEAR_AXES >= 4 + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" I_STR)); + #endif + #if LINEAR_AXES >= 5 + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" J_STR)); + #endif + #if LINEAR_AXES >= 6 + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" K_STR)); + #endif #endif // diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 69193701eb..ad7d632058 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -95,54 +95,22 @@ void menu_tmc_current() { void menu_tmc_hybrid_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STORED_HYBRID_THRS(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7); - #endif + TERN_(X_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X, STR_X)); + TERN_(Y_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y)); + TERN_(Z_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7)); END_MENU(); } @@ -155,30 +123,17 @@ void menu_tmc_current() { void menu_tmc_homing_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if X_SENSORLESS - TMC_EDIT_STORED_SGT(X); - #if X2_SENSORLESS - TMC_EDIT_STORED_SGT(X2); - #endif - #endif - #if Y_SENSORLESS - TMC_EDIT_STORED_SGT(Y); - #if Y2_SENSORLESS - TMC_EDIT_STORED_SGT(Y2); - #endif - #endif - #if Z_SENSORLESS - TMC_EDIT_STORED_SGT(Z); - #if Z2_SENSORLESS - TMC_EDIT_STORED_SGT(Z2); - #endif - #if Z3_SENSORLESS - TMC_EDIT_STORED_SGT(Z3); - #endif - #if Z4_SENSORLESS - TMC_EDIT_STORED_SGT(Z4); - #endif - #endif + TERN_( X_SENSORLESS, TMC_EDIT_STORED_SGT(X)); + TERN_(X2_SENSORLESS, TMC_EDIT_STORED_SGT(X2)); + TERN_( Y_SENSORLESS, TMC_EDIT_STORED_SGT(Y)); + TERN_(Y2_SENSORLESS, TMC_EDIT_STORED_SGT(Y2)); + TERN_( Z_SENSORLESS, TMC_EDIT_STORED_SGT(Z)); + TERN_(Z2_SENSORLESS, TMC_EDIT_STORED_SGT(Z2)); + TERN_(Z3_SENSORLESS, TMC_EDIT_STORED_SGT(Z3)); + TERN_(Z4_SENSORLESS, TMC_EDIT_STORED_SGT(Z4)); + TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I)); + TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J)); + TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K)); END_MENU(); } @@ -192,54 +147,22 @@ void menu_tmc_current() { START_MENU(); STATIC_ITEM(MSG_TMC_STEALTH_ENABLED); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STEP_MODE(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STEP_MODE(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STEP_MODE(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STEP_MODE(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STEP_MODE(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STEP_MODE(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STEP_MODE(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STEP_MODE(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STEP_MODE(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STEP_MODE(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STEP_MODE(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STEP_MODE(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STEP_MODE(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STEP_MODE(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STEP_MODE(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STEP_MODE(E7, LCD_STR_E7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X, STR_X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X2, STR_X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y, STR_Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y2, STR_Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z, STR_Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7)); END_MENU(); } @@ -249,15 +172,9 @@ void menu_tmc() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_TMC_CURRENT, menu_tmc_current); - #if ENABLED(HYBRID_THRESHOLD) - SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs); - #endif - #if ENABLED(SENSORLESS_HOMING) - SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs); - #endif - #if HAS_STEALTHCHOP - SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode); - #endif + TERN_(HYBRID_THRESHOLD, SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs)); + TERN_(SENSORLESS_HOMING, SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs)); + TERN_(HAS_STEALTHCHOP, SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode)); END_MENU(); } diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 631d6d8582..18c50c92f7 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -653,10 +653,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index f7b6ffc75d..786dc61f60 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -638,10 +638,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 93df6eb961..02e3354d93 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -640,10 +640,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index a6aed2ad24..876405a40c 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -37,19 +37,27 @@ L64XX_Marlin L64xxManager; #include "../../module/planner.h" #include "../../HAL/shared/Delay.h" -static const char str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", +static const char LINEAR_AXIS_LIST( + str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", + str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " " + ), str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2", str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4", - str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", - str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", - str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", - str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + LIST_N(EXTRUDERS, + str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", + str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", + str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", + str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + ) ; +#define _EN_ITEM(N) , str_E##N PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = { - str_X, str_Y, str_Z, str_X2, str_Y2, str_Z2, str_Z3, str_Z4, - str_E0, str_E1, str_E2, str_E3, str_E4, str_E5, str_E6, str_E7 + LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K), + str_X2, str_Y2, str_Z2, str_Z3, str_Z4 + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../core/debug_out.h" @@ -58,16 +66,17 @@ void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" N uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver +#define _EN_ITEM(N) , INVERT_E##N##_DIR const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { - INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR + LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR) , (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2 , (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4 - , INVERT_E0_DIR, INVERT_E1_DIR, INVERT_E2_DIR, INVERT_E3_DIR - , INVERT_E4_DIR, INVERT_E5_DIR, INVERT_E6_DIR, INVERT_E7_DIR + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM volatile uint8_t L64XX_Marlin::spi_abort = false; uint8_t L64XX_Marlin::spi_active = false; @@ -326,6 +335,15 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const #if AXIS_IS_L64XX(Z) case Z : SET_L6470_PARAM(Z); break; #endif + #if AXIS_IS_L64XX(I) + case I : SET_L6470_PARAM(I); break; + #endif + #if AXIS_IS_L64XX(J) + case J : SET_L6470_PARAM(J); break; + #endif + #if AXIS_IS_L64XX(K) + case K : SET_L6470_PARAM(K); break; + #endif #if AXIS_IS_L64XX(X2) case X2: SET_L6470_PARAM(X2); break; #endif @@ -370,8 +388,7 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const inline void echo_min_max(const char a, const_float_t min, const_float_t max) { DEBUG_CHAR(' '); DEBUG_CHAR(a); - DEBUG_ECHOPAIR(" min = ", min); - DEBUG_ECHOLNPAIR(" max = ", max); + DEBUG_ECHOLNPAIR(" min = ", min, " max = ", max); } inline void echo_oct_used(const_float_t oct, const uint8_t stall) { DEBUG_ECHOPAIR("over_current_threshold used : ", oct); @@ -433,10 +450,15 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in // Position calcs & checks // - const float X_center = LOGICAL_X_POSITION(current_position.x), - Y_center = LOGICAL_Y_POSITION(current_position.y), - Z_center = LOGICAL_Z_POSITION(current_position.z), - E_center = current_position.e; + const float LOGICAL_AXIS_LIST( + E_center = current_position.e, + X_center = LOGICAL_X_POSITION(current_position.x), + Y_center = LOGICAL_Y_POSITION(current_position.y), + Z_center = LOGICAL_Z_POSITION(current_position.z), + I_center = LOGICAL_I_POSITION(current_position.i), + J_center = LOGICAL_J_POSITION(current_position.j), + K_center = LOGICAL_K_POSITION(current_position.k) + ); switch (axis_mon[0][0]) { default: position_max = position_min = 0; break; @@ -451,31 +473,73 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } } break; - case 'Y': { - position_min = Y_center - displacement; - position_max = Y_center + displacement; - echo_min_max('Y', position_min, position_max); - if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Y_AXIS + case 'Y': { + position_min = Y_center - displacement; + position_max = Y_center + displacement; + echo_min_max('Y', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'Z': { - position_min = Z_center - displacement; - position_max = Z_center + displacement; - echo_min_max('Z', position_min, position_max); - if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Z_AXIS + case 'Z': { + position_min = Z_center - displacement; + position_max = Z_center + displacement; + echo_min_max('Z', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'E': { - position_min = E_center - displacement; - position_max = E_center + displacement; - echo_min_max('E', position_min, position_max); - } break; + #if LINEAR_AXES >= 4 + case AXIS4_NAME: { + position_min = I_center - displacement; + position_max = I_center + displacement; + echo_min_max(AXIS4_NAME, position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 5 + case AXIS5_NAME: { + position_min = J_center - displacement; + position_max = J_center + displacement; + echo_min_max(AXIS5_NAME, position_min, position_max); + if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 6 + case AXIS6_NAME: { + position_min = K_center - displacement; + position_max = K_center + displacement; + echo_min_max(AXIS6_NAME, position_min, position_max); + if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if HAS_EXTRUDERS + case 'E': { + position_min = E_center - displacement; + position_max = E_center + displacement; + echo_min_max('E', position_min, position_max); + } break; + #endif } // @@ -660,7 +724,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc. struct L6470_driver_data { - uint8_t driver_index; + L64XX_axis_t driver_index; uint32_t driver_status; uint8_t is_otw; uint8_t otw_counter; @@ -671,52 +735,61 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* L6470_driver_data driver_L6470_data[] = { #if AXIS_IS_L64XX(X) - { 0, 0, 0, 0, 0, 0, 0 }, + { X, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y) - { 1, 0, 0, 0, 0, 0, 0 }, + { Y, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z) - { 2, 0, 0, 0, 0, 0, 0 }, + { Z, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(I) + { I, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(J) + { J, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(K) + { K, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(X2) - { 3, 0, 0, 0, 0, 0, 0 }, + { X2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y2) - { 4, 0, 0, 0, 0, 0, 0 }, + { Y2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z2) - { 5, 0, 0, 0, 0, 0, 0 }, + { Z2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z3) - { 6, 0, 0, 0, 0, 0, 0 }, + { Z3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z4) - { 7, 0, 0, 0, 0, 0, 0 }, + { Z4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E0) - { 8, 0, 0, 0, 0, 0, 0 }, + { E0, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E1) - { 9, 0, 0, 0, 0, 0, 0 }, + { E1, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E2) - { 10, 0, 0, 0, 0, 0, 0 }, + { E2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E3) - { 11, 0, 0, 0, 0, 0, 0 }, + { E3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E4) - { 12, 0, 0, 0, 0, 0, 0 }, + { E4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E5) - { 13, 0, 0, 0, 0, 0, 0 } + { E5, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E6) - { 14, 0, 0, 0, 0, 0, 0 } + { E6, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E7) - { 16, 0, 0, 0, 0, 0, 0 } + { E7, 0, 0, 0, 0, 0, 0 } #endif }; @@ -863,6 +936,15 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(Z) monitor_update(Z); #endif + #if AXIS_IS_L64XX(I) + monitor_update(I); + #endif + #if AXIS_IS_L64XX(J) + monitor_update(J); + #endif + #if AXIS_IS_L64XX(K) + monitor_update(K); + #endif #if AXIS_IS_L64XX(X2) monitor_update(X2); #endif @@ -896,6 +978,12 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(E5) monitor_update(E5); #endif + #if AXIS_IS_L64XX(E6) + monitor_update(E6); + #endif + #if AXIS_IS_L64XX(E7) + monitor_update(E7); + #endif if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL(); diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.h b/Marlin/src/libs/L64XX/L64XX_Marlin.h index c8d273990f..e11d8e872e 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.h +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.h @@ -35,7 +35,9 @@ #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1 #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7)) -enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX }; +#define _EN_ITEM(N) , E##N +enum L64XX_axis_t : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX }; +#undef _EN_ITEM class L64XX_Marlin : public L64XXHelper { public: diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index f1bff7d4c6..b8202217dd 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -52,10 +52,9 @@ */ vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) { - const xyz_float_t &lv = left, &rv = right; - return vector_3(lv.y * rv.z - lv.z * rv.y, // YZ cross - lv.z * rv.x - lv.x * rv.z, // ZX cross - lv.x * rv.y - lv.y * rv.x); // XY cross + return vector_3(left.y * right.z - left.z * right.y, // YZ cross + left.z * right.x - left.x * right.z, // ZX cross + left.x * right.y - left.y * right.x); // XY cross } vector_3 vector_3::get_normal() const { @@ -64,16 +63,16 @@ vector_3 vector_3::get_normal() const { return normalized; } -void vector_3::normalize() { - *this *= RSQRT(sq(x) + sq(y) + sq(z)); -} +float vector_3::magnitude() const { return SQRT(sq(x) + sq(y) + sq(z)); } + +void vector_3::normalize() { *this *= RSQRT(sq(x) + sq(y) + sq(z)); } // Apply a rotation to the matrix void vector_3::apply_rotation(const matrix_3x3 &matrix) { const float _x = x, _y = y, _z = z; - *this = { matrix.vectors[0][0] * _x + matrix.vectors[1][0] * _y + matrix.vectors[2][0] * _z, - matrix.vectors[0][1] * _x + matrix.vectors[1][1] * _y + matrix.vectors[2][1] * _z, - matrix.vectors[0][2] * _x + matrix.vectors[1][2] * _y + matrix.vectors[2][2] * _z }; + *this = { matrix.vectors[0].x * _x + matrix.vectors[1].x * _y + matrix.vectors[2].x * _z, + matrix.vectors[0].y * _x + matrix.vectors[1].y * _y + matrix.vectors[2].y * _z, + matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z }; } void vector_3::debug(PGM_P const title) { @@ -105,9 +104,9 @@ matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &r //row_1.debug(PSTR("row_1")); //row_2.debug(PSTR("row_2")); matrix_3x3 new_matrix; - new_matrix.vectors[0] = row_0; - new_matrix.vectors[1] = row_1; - new_matrix.vectors[2] = row_2; + new_matrix.vectors[0].x = row_0.x; new_matrix.vectors[1].y = row_0.y; new_matrix.vectors[2].z = row_0.z; + new_matrix.vectors[3].x = row_1.x; new_matrix.vectors[4].y = row_1.y; new_matrix.vectors[5].z = row_1.z; + new_matrix.vectors[6].x = row_2.x; new_matrix.vectors[7].y = row_2.y; new_matrix.vectors[8].z = row_2.z; //new_matrix.debug(PSTR("new_matrix")); return new_matrix; } diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 5ce5914961..5d99fcec20 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -44,12 +44,16 @@ class matrix_3x3; -struct vector_3 : xyz_float_t { - vector_3(const_float_t _x, const_float_t _y, const_float_t _z) { set(_x, _y, _z); } - vector_3(const xy_float_t &in) { set(in.x, in.y); } - vector_3(const xyz_float_t &in) { set(in.x, in.y, in.z); } - vector_3(const xyze_float_t &in) { set(in.x, in.y, in.z); } - vector_3() { reset(); } +struct vector_3 { + union { + struct { float x, y, z; }; + float pos[3]; + }; + vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {} + vector_3(const xy_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); } + vector_3(const xyz_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3() { x = y = z = 0; } // Factory method static vector_3 cross(const vector_3 &a, const vector_3 &b); @@ -59,19 +63,26 @@ struct vector_3 : xyz_float_t { void apply_rotation(const matrix_3x3 &matrix); // Accessors - float get_length() const; + float magnitude() const; vector_3 get_normal() const; // Operators - FORCE_INLINE vector_3 operator+(const vector_3 &v) const { vector_3 o = *this; o += v; return o; } - FORCE_INLINE vector_3 operator-(const vector_3 &v) const { vector_3 o = *this; o -= v; return o; } - FORCE_INLINE vector_3 operator*(const float &v) const { vector_3 o = *this; o *= v; return o; } + float& operator[](const int n) { return pos[n]; } + const float& operator[](const int n) const { return pos[n]; } + + vector_3& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } + vector_3 operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); } + vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); } + vector_3 operator*(const float &v) { return vector_3(x * v, y * v, z * v); } + + operator xy_float_t() { return xy_float_t({ x, y }); } + operator xyz_float_t() { return xyz_float_t({ x, y, z }); } void debug(PGM_P const title); }; struct matrix_3x3 { - abc_float_t vectors[3]; + vector_3 vectors[3]; // Factory methods static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2); @@ -83,6 +94,4 @@ struct matrix_3x3 { void debug(PGM_P const title); void apply_rotation_xyz(float &x, float &y, float &z); - - FORCE_INLINE void apply_rotation_xyz(xyz_pos_t &pos) { apply_rotation_xyz(pos.x, pos.y, pos.z); } }; diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 1be3df220f..96d8841f13 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -245,6 +245,9 @@ void home_delta() { TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS)); + TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS)); + TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS)); #endif // Move all carriages together linearly until an endstop is hit. @@ -257,6 +260,9 @@ void home_delta() { TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x)); TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y)); TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z)); + TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i)); + TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j)); + TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k)); #endif endstops.validate_homing_move(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index cf152ff028..c750d56713 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -259,6 +259,66 @@ void Endstops::init() { #endif #endif + #if HAS_I_MIN + #if ENABLED(ENDSTOPPULLUP_IMIN) + SET_INPUT_PULLUP(I_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(I_MIN_PIN); + #else + SET_INPUT(I_MIN_PIN); + #endif + #endif + + #if HAS_I_MAX + #if ENABLED(ENDSTOPPULLUP_IMAX) + SET_INPUT_PULLUP(I_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMAX) + SET_INPUT_PULLDOWN(I_MAX_PIN); + #else + SET_INPUT(I_MAX_PIN); + #endif + #endif + + #if HAS_J_MIN + #if ENABLED(ENDSTOPPULLUP_JMIN) + SET_INPUT_PULLUP(J_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(J_MIN_PIN); + #else + SET_INPUT(J_MIN_PIN); + #endif + #endif + + #if HAS_J_MAX + #if ENABLED(ENDSTOPPULLUP_JMAX) + SET_INPUT_PULLUP(J_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_JMAX) + SET_INPUT_PULLDOWN(J_MAX_PIN); + #else + SET_INPUT(J_MAX_PIN); + #endif + #endif + + #if HAS_K_MIN + #if ENABLED(ENDSTOPPULLUP_KMIN) + SET_INPUT_PULLUP(K_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MIN_PIN); + #else + SET_INPUT(K_MIN_PIN); + #endif + #endif + + #if HAS_K_MAX + #if ENABLED(ENDSTOPPULLUP_KMAX) + SET_INPUT_PULLUP(K_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MAX_PIN); + #else + SET_INPUT(K_MAX_PIN); + #endif + #endif + #if PIN_EXISTS(CALIBRATION) #if ENABLED(CALIBRATION_PIN_PULLUP) SET_INPUT_PULLUP(CALIBRATION_PIN); @@ -361,7 +421,7 @@ void Endstops::event_handler() { prev_hit_state = hit_state; if (hit_state) { #if HAS_STATUS_MESSAGE - char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' '), + char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '), chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else @@ -378,12 +438,20 @@ void Endstops::event_handler() { #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X') #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y') #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z') + #define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I') + #define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J') + #define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K') SERIAL_ECHO_START(); SERIAL_ECHOPGM(STR_ENDSTOPS_HIT); - ENDSTOP_HIT_TEST_X(); - ENDSTOP_HIT_TEST_Y(); - ENDSTOP_HIT_TEST_Z(); + LINEAR_AXIS_CODE( + ENDSTOP_HIT_TEST_X(), + ENDSTOP_HIT_TEST_Y(), + ENDSTOP_HIT_TEST_Z(), + _ENDSTOP_HIT_TEST(I,'I'), + _ENDSTOP_HIT_TEST(J,'J'), + _ENDSTOP_HIT_TEST(K,'K') + ); #if HAS_CUSTOM_PROBE_PIN #define P_AXIS Z_AXIS @@ -395,7 +463,7 @@ void Endstops::event_handler() { ui.status_printf_P(0, PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), GET_TEXT(MSG_LCD_ENDSTOPS), - LINEAR_AXIS_LIST(chrX, chrY, chrZ), chrP + LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP ) ); @@ -477,6 +545,24 @@ void _O2 Endstops::report_states() { #if HAS_Z4_MAX ES_REPORT(Z4_MAX); #endif + #if HAS_I_MIN + ES_REPORT(I_MIN); + #endif + #if HAS_I_MAX + ES_REPORT(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT(K_MAX); + #endif #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN)); #endif @@ -549,6 +635,10 @@ void Endstops::update() { #define Z_AXIS_HEAD Z_AXIS #endif + #define I_AXIS_HEAD I_AXIS + #define J_AXIS_HEAD J_AXIS + #define K_AXIS_HEAD K_AXIS + /** * Check and update endstops */ @@ -656,6 +746,84 @@ void Endstops::update() { #endif #endif + #if HAS_I_MIN + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MIN); + #if HAS_I2_MIN + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MIN, I2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MIN); + #endif + #endif + + #if HAS_I_MAX + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MAX); + #if HAS_I2_MAX + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MAX, I2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MAX); + #endif + #endif + + #if HAS_J_MIN + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MIN); + #if HAS_J2_MIN + UPDATE_ENDSTOP_BIT(J2, MIN); + #else + COPY_LIVE_STATE(J_MIN, J2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MIN); + #endif + #endif + + #if HAS_J_MAX + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MAX); + #if HAS_J2_MAX + UPDATE_ENDSTOP_BIT(J2, MAX); + #else + COPY_LIVE_STATE(J_MAX, J2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MAX); + #endif + #endif + + #if HAS_K_MIN + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MIN); + #if HAS_K2_MIN + UPDATE_ENDSTOP_BIT(K2, MIN); + #else + COPY_LIVE_STATE(K_MIN, K2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MIN); + #endif + #endif + + #if HAS_K_MAX + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MAX); + #if HAS_K2_MAX + UPDATE_ENDSTOP_BIT(K2, MAX); + #else + COPY_LIVE_STATE(K_MAX, K2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MAX); + #endif + #endif + #if ENDSTOP_NOISE_THRESHOLD /** @@ -804,79 +972,128 @@ void Endstops::update() { } } - if (stepper.axis_is_moving(Y_AXIS)) { - if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) - PROCESS_ENDSTOP_Y(MIN); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #if HAS_Y_AXIS + if (stepper.axis_is_moving(Y_AXIS)) { + if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction + #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) + PROCESS_ENDSTOP_Y(MIN); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #endif #endif - #endif - } - else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) - PROCESS_ENDSTOP_Y(MAX); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + } + else { // +direction + #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) + PROCESS_ENDSTOP_Y(MAX); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif #endif - #endif + } } - } + #endif - if (stepper.axis_is_moving(Z_AXIS)) { - if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. + #if HAS_Z_AXIS + if (stepper.axis_is_moving(Z_AXIS)) { + if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. - #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) - if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) - && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) - ) PROCESS_ENDSTOP_Z(MIN); - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) + if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) + && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) + ) PROCESS_ENDSTOP_Z(MIN); + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #endif #endif - #endif - // When closing the gap check the enabled probe - #if HAS_CUSTOM_PROBE_PIN - if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); - #endif - } - else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) - #if ENABLED(Z_MULTI_ENDSTOPS) - PROCESS_ENDSTOP_Z(MAX); - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX - PROCESS_ENDSTOP(Z, MAX); + // When closing the gap check the enabled probe + #if HAS_CUSTOM_PROBE_PIN + if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); #endif - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + } + else { // Z +direction. Gantry up, bed down. + #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) + #if ENABLED(Z_MULTI_ENDSTOPS) + PROCESS_ENDSTOP_Z(MAX); + #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX + PROCESS_ENDSTOP(Z, MAX); + #endif + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + #endif #endif - #endif + } } - } + #endif + + #if LINEAR_AXES >= 4 + if (stepper.axis_is_moving(I_AXIS)) { + if (stepper.motor_direction(I_AXIS_HEAD)) { // -direction + #if HAS_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN) + PROCESS_ENDSTOP(I, MIN); + #endif + } + else { // +direction + #if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX) + PROCESS_ENDSTOP(I, MAX); + #endif + } + } + #endif + + #if LINEAR_AXES >= 5 + if (stepper.axis_is_moving(J_AXIS)) { + if (stepper.motor_direction(J_AXIS_HEAD)) { // -direction + #if HAS_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN) + PROCESS_ENDSTOP(J, MIN); + #endif + } + else { // +direction + #if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX) + PROCESS_ENDSTOP(J, MAX); + #endif + } + } + #endif + + #if LINEAR_AXES >= 6 + if (stepper.axis_is_moving(K_AXIS)) { + if (stepper.motor_direction(K_AXIS_HEAD)) { // -direction + #if HAS_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN) + PROCESS_ENDSTOP(K, MIN); + #endif + } + else { // +direction + #if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX) + PROCESS_ENDSTOP(K, MAX); + #endif + } + } + #endif } // Endstops::update() #if ENABLED(SPI_ENDSTOPS) @@ -919,6 +1136,24 @@ void Endstops::update() { hit = true; } #endif + #if I_SPI_SENSORLESS + if (tmc_spi_homing.i && stepperI.test_stall_status()) { + SBI(live_state, I_ENDSTOP); + hit = true; + } + #endif + #if J_SPI_SENSORLESS + if (tmc_spi_homing.j && stepperJ.test_stall_status()) { + SBI(live_state, J_ENDSTOP); + hit = true; + } + #endif + #if K_SPI_SENSORLESS + if (tmc_spi_homing.k && stepperK.test_stall_status()) { + SBI(live_state, K_ENDSTOP); + hit = true; + } + #endif if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update(); @@ -929,6 +1164,9 @@ void Endstops::update() { TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); + TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP)); + TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP)); + TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP)); } #endif // SPI_ENDSTOPS @@ -1005,6 +1243,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_GET_STATE(Z4_MAX); #endif + #if HAS_I_MAX + ES_GET_STATE(I_MAX); + #endif + #if HAS_I_MIN + ES_GET_STATE(I_MIN); + #endif + #if HAS_J_MAX + ES_GET_STATE(J_MAX); + #endif + #if HAS_J_MIN + ES_GET_STATE(J_MIN); + #endif + #if HAS_K_MAX + ES_GET_STATE(K_MAX); + #endif + #if HAS_K_MIN + ES_GET_STATE(K_MIN); + #endif uint16_t endstop_change = live_state_local ^ old_live_state_local; #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S)) @@ -1061,6 +1317,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_REPORT_CHANGE(Z4_MAX); #endif + #if HAS_I_MIN + ES_REPORT_CHANGE(I_MIN); + #endif + #if HAS_I_MAX + ES_REPORT_CHANGE(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT_CHANGE(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT_CHANGE(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT_CHANGE(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT_CHANGE(K_MAX); + #endif SERIAL_ECHOLNPGM("\n"); analogWrite(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 5da09f41cf..01f33099e9 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -39,6 +39,12 @@ enum EndstopEnum : char { _ES_ITEM(HAS_Y_MAX, Y_MAX) _ES_ITEM(HAS_Z_MIN, Z_MIN) _ES_ITEM(HAS_Z_MAX, Z_MAX) + _ES_ITEM(HAS_I_MIN, I_MIN) + _ES_ITEM(HAS_I_MAX, I_MAX) + _ES_ITEM(HAS_J_MIN, J_MIN) + _ES_ITEM(HAS_J_MAX, J_MAX) + _ES_ITEM(HAS_K_MIN, K_MIN) + _ES_ITEM(HAS_K_MAX, K_MAX) // Extra Endstops for XYZ #if ENABLED(X_DUAL_ENDSTOPS) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index ad0537b5cf..1d40d3a253 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -89,7 +89,7 @@ bool relative_mode; // = false; #define Z_INIT_POS Z_HOME_POS #endif -xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS); +xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS); /** * Cartesian Destination @@ -143,7 +143,7 @@ xyz_pos_t cartes; #if IS_KINEMATIC - abc_pos_t delta; + abce_pos_t delta; #if HAS_SCARA_OFFSET abc_pos_t scara_home_offset; @@ -196,7 +196,14 @@ inline void report_more_positions() { inline void report_logical_position(const xyze_pos_t &rpos) { const xyze_pos_t lpos = rpos.asLogical(); SERIAL_ECHOPAIR_P( - LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z) + LIST_N(DOUBLE(LINEAR_AXES), + X_LBL, lpos.x, + SP_Y_LBL, lpos.y, + SP_Z_LBL, lpos.z, + SP_I_LBL, lpos.i, + SP_J_LBL, lpos.j, + SP_K_LBL, lpos.k + ) #if HAS_EXTRUDERS , SP_E_LBL, lpos.e #endif @@ -209,7 +216,10 @@ void report_real_position() { get_cartesian_from_steppers(); xyze_pos_t npos = LOGICAL_AXIS_ARRAY( planner.get_axis_position_mm(E_AXIS), - cartes.x, cartes.y, cartes.z + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) ); TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); @@ -334,20 +344,21 @@ void sync_plan_position() { void get_cartesian_from_steppers() { #if ENABLED(DELTA) forward_kinematics(planner.get_axis_positions_mm()); - #else - #if IS_SCARA - forward_kinematics( - planner.get_axis_position_degrees(A_AXIS) - , planner.get_axis_position_degrees(B_AXIS) - #if ENABLED(AXEL_TPARA) - , planner.get_axis_position_degrees(C_AXIS) - #endif - ); - #else - cartes.x = planner.get_axis_position_mm(X_AXIS); - cartes.y = planner.get_axis_position_mm(Y_AXIS); - #endif + #elif IS_SCARA + forward_kinematics( + planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS) + OPTARG(AXEL_TPARA, planner.get_axis_position_degrees(C_AXIS)) + ); cartes.z = planner.get_axis_position_mm(Z_AXIS); + #else + LINEAR_AXIS_CODE( + cartes.x = planner.get_axis_position_mm(X_AXIS), + cartes.y = planner.get_axis_position_mm(Y_AXIS), + cartes.z = planner.get_axis_position_mm(Z_AXIS), + cartes.i = planner.get_axis_position_mm(I_AXIS), + cartes.j = planner.get_axis_position_mm(J_AXIS), + cartes.k = planner.get_axis_position_mm(K_AXIS) + ); #endif } @@ -366,13 +377,9 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { get_cartesian_from_steppers(); xyze_pos_t pos = cartes; - #if HAS_EXTRUDERS - pos.e = planner.get_axis_position_mm(E_AXIS); - #endif + TERN_(HAS_EXTRUDERS, pos.e = planner.get_axis_position_mm(E_AXIS)); - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(pos, true); - #endif + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(pos, true)); if (axis == ALL_AXES_ENUM) current_position = pos; @@ -385,7 +392,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { * (or from wherever it has been told it is located). */ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { - planner.buffer_line(current_position, fr_mm_s, active_extruder); + planner.buffer_line(current_position, fr_mm_s); } #if HAS_EXTRUDERS @@ -411,7 +418,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { #else if (current_position == destination) return; - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); #endif current_position = destination; @@ -449,25 +456,26 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ } /** - * Plan a move to (X, Y, Z) with separation of the XY and Z components. + * Plan a move to (X, Y, Z, [I, [J, [K]]]) and set the current_position + * Plan a move to (X, Y, Z) with separation of Z from other components. * - * - If Z is moving up, the Z move is done before XY. - * - If Z is moving down, the Z move is done after XY. + * - If Z is moving up, the Z move is done before XY, etc. + * - If Z is moving down, the Z move is done after XY, etc. * - Delta may lower Z first to get into the free motion zone. * - Before returning, wait for the planner buffer to empty. */ -void do_blocking_move_to( - LINEAR_AXIS_LIST(const float rx, const float ry, const float rz), - const_feedRate_t fr_mm_s/*=0.0f*/ -) { +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) { DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_LIST(rx, ry, rz)); + if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS()); - const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS), - xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); + const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); + + #if HAS_Z_AXIS + const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); + #endif #if EITHER(DELTA, IS_SCARA) - if (!position_is_reachable(rx, ry)) return; + if (!position_is_reachable(x, y)) return; destination = current_position; // sync destination at the start #endif @@ -479,8 +487,8 @@ void do_blocking_move_to( // when in the danger zone if (current_position.z > delta_clip_start_height) { - if (rz > delta_clip_start_height) { // staying in the danger zone - destination.set(rx, ry, rz); // move directly (uninterpolated) + if (z > delta_clip_start_height) { // staying in the danger zone + destination.set(x, y, z); // move directly (uninterpolated) prepare_internal_fast_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position); return; @@ -490,18 +498,18 @@ void do_blocking_move_to( if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position); } - if (rz > current_position.z) { // raising? - destination.z = rz; + if (z > current_position.z) { // raising? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position); - if (rz < current_position.z) { // lowering? - destination.z = rz; + if (z < current_position.z) { // lowering? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); } @@ -509,36 +517,40 @@ void do_blocking_move_to( #elif IS_SCARA // If Z needs to raise, do it before moving XY - if (destination.z < rz) { - destination.z = rz; + if (destination.z < z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_fast_move_to_destination(xy_feedrate); // If Z needs to lower, do it after moving XY - if (destination.z > rz) { - destination.z = rz; + if (destination.z > z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } #else - // If Z needs to raise, do it before moving XY - if (current_position.z < rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to raise, do it before moving XY + if (current_position.z < z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif - current_position.set(rx, ry); + current_position.set(x, y); line_to_current_position(xy_feedrate); - // If Z needs to lower, do it after moving XY - if (current_position.z > rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to lower, do it after moving XY + if (current_position.z > z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif #endif @@ -546,53 +558,94 @@ void do_blocking_move_to( } void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i), fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k), fr_mm_s); } void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s); } void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s); + do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s); } - void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to( - LINEAR_AXIS_LIST(rx, current_position.y, current_position.z), - fr_mm_s - ); -} -void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to( - LINEAR_AXIS_LIST(current_position.x, ry, current_position.z), - fr_mm_s - ); -} -void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); -} - -void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to( - LINEAR_AXIS_LIST(rx, ry, current_position.z), - fr_mm_s - ); -} -void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); -} - -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to( - LINEAR_AXIS_LIST(raw.x, raw.y, z), + LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k), fr_mm_s ); } -void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { - float zdest = zclear; - if (!lower_allowed) NOLESS(zdest, current_position.z); - do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS))); -} +#if HAS_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } +#endif + +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); + } +#endif + +#if LINEAR_AXES == 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); + } + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to(raw.x, raw.y, raw.z, i, fr_mm_s); + } +#endif + +#if LINEAR_AXES >= 5 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); + } + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to(raw.x, raw.y, raw.z, i, raw.j, fr_mm_s); + } + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s); + } + void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, j, fr_mm_s); + } +#endif + +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s); + } + void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, raw.j, k, fr_mm_s); + } +#endif + +#if HAS_Y_AXIS + void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); + } +#endif + +#if HAS_Z_AXIS + void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { + float zdest = zclear; + if (!lower_allowed) NOLESS(zdest, current_position.z); + do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS))); + } +#endif // // Prepare to do endstop or probe moves with custom feedrates. @@ -618,8 +671,8 @@ void restore_feedrate_and_scaling() { // Software Endstops are based on the configured limits. soft_endstops_t soft_endstop = { true, false, - LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS), - LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS) + LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS), + LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS) }; /** @@ -746,25 +799,59 @@ void restore_feedrate_and_scaling() { #endif } - if (axis_was_homed(Y_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - NOLESS(target.y, soft_endstop.min.y); - #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - NOMORE(target.y, soft_endstop.max.y); - #endif - } + #if HAS_Y_AXIS + if (axis_was_homed(Y_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) + NOLESS(target.y, soft_endstop.min.y); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) + NOMORE(target.y, soft_endstop.max.y); + #endif + } + #endif #endif - if (axis_was_homed(Z_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - NOLESS(target.z, soft_endstop.min.z); - #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - NOMORE(target.z, soft_endstop.max.z); - #endif - } + #if HAS_Z_AXIS + if (axis_was_homed(Z_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) + NOLESS(target.z, soft_endstop.min.z); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) + NOMORE(target.z, soft_endstop.max.z); + #endif + } + #endif + #if LINEAR_AXES >= 4 // TODO (DerAndere): Find out why this was missing / removed + if (axis_was_homed(I_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I) + NOLESS(target.i, soft_endstop.min.i); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_I) + NOMORE(target.i, soft_endstop.max.i); + #endif + } + #endif + #if LINEAR_AXES >= 5 + if (axis_was_homed(J_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J) + NOLESS(target.j, soft_endstop.min.j); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_J) + NOMORE(target.j, soft_endstop.max.j); + #endif + } + #endif + #if LINEAR_AXES >= 6 + if (axis_was_homed(K_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K) + NOLESS(target.k, soft_endstop.min.k); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_K) + NOMORE(target.k, soft_endstop.max.k); + #endif + } + #endif } #else // !HAS_SOFTWARE_ENDSTOPS @@ -824,7 +911,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -880,15 +967,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - )) break; + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Ensure last segment arrives at target location. - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - ); + planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); return false; // caller will update current_position } @@ -910,7 +993,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, fr_mm_s, active_extruder); + planner.buffer_line(destination, fr_mm_s); return; } @@ -947,18 +1030,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - )) break; + if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Since segment_distance is only approximate, // the final move must be to the exact destination. - planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); } #endif // SEGMENT_LEVELED_MOVES @@ -998,7 +1075,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { } #endif // HAS_MESH - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -1080,12 +1157,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // Un-park the active extruder // const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS]; - #define CURPOS current_position - #define RAISED raised_parked_position // 1. Move to the raised parked XYZ. Presumably the tool is already at XY. - if (planner.buffer_line(RAISED.x, RAISED.y, RAISED.z, CURPOS.e, fr_zfast, active_extruder)) { + xyze_pos_t raised = raised_parked_position; raised.e = current_position.e; + if (planner.buffer_line(raised, fr_zfast)) { // 2. Move to the current native XY and raised Z. Presumably this is a null move. - if (planner.buffer_line(CURPOS.x, CURPOS.y, RAISED.z, CURPOS.e, PLANNER_XY_FEEDRATE(), active_extruder)) { + xyze_pos_t curpos = current_position; curpos.z = raised_parked_position.z; + if (planner.buffer_line(curpos, PLANNER_XY_FEEDRATE())) { // 3. Lower Z back down line_to_current_position(fr_zfast); } @@ -1099,21 +1176,24 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { case DXC_MIRRORED_MODE: case DXC_DUPLICATION_MODE: if (active_extruder == 0) { - xyze_pos_t new_pos = current_position; + // Restore planner to parked head (T1) X position + xyze_pos_t pos_now = current_position; + pos_now.x = inactive_extruder_x; + planner.set_position_mm(pos_now); + + // Keep the same X or add the duplication X offset + xyze_pos_t new_pos = pos_now; if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) new_pos.x += duplicate_extruder_x_offset; - else - new_pos.x = inactive_extruder_x; - // Move duplicate extruder into correct duplication position. + + // Move duplicate extruder into the correct position if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); - planner.set_position_mm(inactive_extruder_x, current_position.y, current_position.z, current_position.e); if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break; - planner.synchronize(); - sync_plan_position(); - set_duplication_enabled(true); - idex_set_parked(false); + sync_plan_position(); // Extra sync for good measure + set_duplication_enabled(true); // Enable Duplication + idex_set_parked(false); // No longer parked if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)"); } else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0"); @@ -1207,22 +1287,24 @@ void prepare_line_to_destination() { }; // Clear test bits that are trusted LINEAR_AXIS_CODE( - set_should(axis_bits, X_AXIS), - set_should(axis_bits, Y_AXIS), - set_should(axis_bits, Z_AXIS) + set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS), + set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS) ); return axis_bits; } bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { if ((axis_bits = axes_should_home(axis_bits))) { - PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); + PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); // TODO: (DerAndere) Set this up for extra axes char msg[strlen_P(home_first)+1]; sprintf_P(msg, home_first, LINEAR_AXIS_LIST( TEST(axis_bits, X_AXIS) ? "X" : "", TEST(axis_bits, Y_AXIS) ? "Y" : "", - TEST(axis_bits, Z_AXIS) ? "Z" : "" + TEST(axis_bits, Z_AXIS) ? "Z" : "", + TEST(axis_bits, I_AXIS) ? AXIS4_STR : "", + TEST(axis_bits, J_AXIS) ? AXIS5_STR : "", + TEST(axis_bits, K_AXIS) ? AXIS6_STR : "" ) ); SERIAL_ECHO_START(); @@ -1374,6 +1456,9 @@ void prepare_line_to_destination() { 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; + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; default: break; } #endif @@ -1446,12 +1531,7 @@ void prepare_line_to_destination() { // Set delta/cartesian axes directly target[axis] = distance; // The move will be towards the endstop - planner.buffer_segment(target - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif - , home_fr_mm_s, active_extruder - ); + planner.buffer_segment(target OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), home_fr_mm_s, active_extruder); #endif planner.synchronize(); @@ -1531,6 +1611,30 @@ void prepare_line_to_destination() { stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir; break; #endif + #ifdef I_MICROSTEPS + case I_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(I); + phaseCurrent = stepperI.get_microstep_counter(); + effectorBackoutDir = -I_HOME_DIR; + stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef J_MICROSTEPS + case J_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(J); + phaseCurrent = stepperJ.get_microstep_counter(); + effectorBackoutDir = -J_HOME_DIR; + stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef K_MICROSTEPS + case K_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(K); + phaseCurrent = stepperK.get_microstep_counter(); + effectorBackoutDir = -K_HOME_DIR; + stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif default: return; } @@ -1583,11 +1687,18 @@ void prepare_line_to_destination() { #else #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ ENABLED(A##_SPI_SENSORLESS) \ - || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ + || TERN0(HAS_Z_AXIS, TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS)) \ || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ )) - if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; + if (LINEAR_AXIS_GANG( + !_CAN_HOME(X), + && !_CAN_HOME(Y), + && !_CAN_HOME(Z), + && !_CAN_HOME(I), + && !_CAN_HOME(J), + && !_CAN_HOME(K)) + ) return; #endif if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); @@ -1636,9 +1747,9 @@ void prepare_line_to_destination() { // Determine if a homing bump will be done and the bumps distance // When homing Z with probe respect probe clearance - const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS)); + const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(axis)); const float bump = axis_home_dir * ( - use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(Z_AXIS)) : home_bump_mm(axis) + use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(axis)) : home_bump_mm(axis) ); // diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 0706b721b3..9095290cc7 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -44,7 +44,7 @@ extern xyze_pos_t current_position, // High-level current tool position // G60/G61 Position Save and Return #if SAVED_POSITIONS - extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; + extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for LINEAR_AXES >= 4 extern xyze_pos_t stored_position[SAVED_POSITIONS]; #endif @@ -53,7 +53,7 @@ extern xyz_pos_t cartes; // Until kinematics.cpp is created, declare this here #if IS_KINEMATIC - extern abc_pos_t delta; + extern abce_pos_t delta; #endif #if HAS_ABL_NOT_UBL @@ -75,16 +75,16 @@ extern xyz_pos_t cartes; */ constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M; FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) { - float v; - #if ENABLED(DELTA) - v = homing_feedrate_mm_m.z; - #else - switch (a) { - case X_AXIS: v = homing_feedrate_mm_m.x; break; - case Y_AXIS: v = homing_feedrate_mm_m.y; break; - case Z_AXIS: - default: v = homing_feedrate_mm_m.z; - } + float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z); + #if DISABLED(DELTA) + LINEAR_AXIS_CODE( + if (a == X_AXIS) v = homing_feedrate_mm_m.x, + else if (a == Y_AXIS) v = homing_feedrate_mm_m.y, + else if (a == Z_AXIS) v = homing_feedrate_mm_m.z, + else if (a == I_AXIS) v = homing_feedrate_mm_m.i, + else if (a == J_AXIS) v = homing_feedrate_mm_m.j, + else if (a == K_AXIS) v = homing_feedrate_mm_m.k + ); #endif return MMM_TO_MMS(v); } @@ -124,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT); \ + static const XYZval NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); @@ -168,13 +168,36 @@ inline float home_bump_mm(const AxisEnum axis) { TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x); TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x); break; - case Y_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); - TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); - break; - case Z_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); - TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + #if HAS_Y_AXIS + case Y_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); + break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + break; + #endif + #if LINEAR_AXES >= 4 // TODO (DerAndere): Test for LINEAR_AXES >= 4 + case I_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i); + TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i); + break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j); + TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j); + break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k); + TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k); + break; + #endif default: break; } #endif @@ -298,32 +321,53 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) /** * Blocking movement and shorthand functions */ -void do_blocking_move_to( - LINEAR_AXIS_LIST(const float rx, const float ry, const float rz), - const_feedRate_t fr_mm_s=0.0f -); +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); +#if HAS_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); +#endif +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 5 + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f); +#endif -void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#if HAS_Y_AXIS + void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); + FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#endif -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#if HAS_Z_AXIS + void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f); + FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#endif void remember_feedrate_and_scaling(); void remember_feedrate_scaling_off(); void restore_feedrate_and_scaling(); -void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); +#if HAS_Z_AXIS + void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); +#else + inline void do_z_clearance(float, bool=false) {} +#endif /** * Homing and Trusted Axes @@ -421,11 +465,27 @@ FORCE_INLINE bool all_axes_trusted() { return linear_bits FORCE_INLINE void toNative(xyze_pos_t&) {} #endif #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) -#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) -#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) #define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS) -#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) -#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#if HAS_Y_AXIS + #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) + #define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) +#endif +#if HAS_Z_AXIS + #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) + #define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#endif +#if LINEAR_AXES >= 4 + #define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS) + #define RAW_I_POSITION(POS) LOGICAL_TO_NATIVE(POS, I_AXIS) +#endif +#if LINEAR_AXES >= 5 + #define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS) + #define RAW_J_POSITION(POS) LOGICAL_TO_NATIVE(POS, J_AXIS) +#endif +#if LINEAR_AXES >= 6 + #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS) + #define RAW_K_POSITION(POS) LOGICAL_TO_NATIVE(POS, K_AXIS) +#endif /** * position_is_reachable family of functions diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 1ea333e926..eb0d204cb0 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1310,7 +1310,7 @@ void Planner::recalculate() { */ void Planner::check_axes_activity() { - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E) xyze_bool_t axis_active = { false }; #endif @@ -1342,14 +1342,17 @@ void Planner::check_axes_activity() { TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure); #endif - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E) for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; LOGICAL_AXIS_CODE( if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true, if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true, if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true, - if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true + if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true, + if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true, + if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true, + if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true ); } #endif @@ -1375,7 +1378,10 @@ void Planner::check_axes_activity() { if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(), if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(), if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(), - if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z() + if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(), + if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(), + if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(), + if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K() ); // @@ -1445,7 +1451,7 @@ void Planner::check_axes_activity() { float high = 0.0; for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; - if (block->steps.x || block->steps.y || block->steps.z) { + if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, block->steps.i, || block->steps.j, || block->steps.k)) { const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; NOLESS(high, se); } @@ -1831,7 +1837,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, de = target.e - position.e, da = target.a - position.a, db = target.b - position.b, - dc = target.c - position.c + dc = target.c - position.c, + di = target.i - position.i, + dj = target.j - position.j, + dk = target.k - position.k ); /* <-- add a slash to enable @@ -1910,7 +1919,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, LINEAR_AXIS_CODE( if (da < 0) SBI(dm, X_AXIS), if (db < 0) SBI(dm, Y_AXIS), - if (dc < 0) SBI(dm, Z_AXIS) + if (dc < 0) SBI(dm, Z_AXIS), + if (di < 0) SBI(dm, I_AXIS), + if (dj < 0) SBI(dm, J_AXIS), + if (dk < 0) SBI(dm, K_AXIS) ); #endif #if HAS_EXTRUDERS @@ -1951,7 +1963,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(ABS(da), ABS(db), ABS(dc)); #else // default non-h-bot planning - block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc))); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #endif /** @@ -1997,7 +2009,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, LINEAR_AXIS_CODE( steps_dist_mm.a = da * steps_to_mm[A_AXIS], steps_dist_mm.b = db * steps_to_mm[B_AXIS], - steps_dist_mm.c = dc * steps_to_mm[C_AXIS] + steps_dist_mm.c = dc * steps_to_mm[C_AXIS], + steps_dist_mm.i = di * steps_to_mm[I_AXIS], + steps_dist_mm.j = dj * steps_to_mm[J_AXIS], + steps_dist_mm.k = dk * steps_to_mm[K_AXIS] ); #endif @@ -2010,7 +2025,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (true LINEAR_AXIS_GANG( && block->steps.a < MIN_STEPS_PER_SEGMENT, && block->steps.b < MIN_STEPS_PER_SEGMENT, - && block->steps.c < MIN_STEPS_PER_SEGMENT + && block->steps.c < MIN_STEPS_PER_SEGMENT, + && block->steps.i < MIN_STEPS_PER_SEGMENT, + && block->steps.j < MIN_STEPS_PER_SEGMENT, + && block->steps.k < MIN_STEPS_PER_SEGMENT ) ) { block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); @@ -2022,19 +2040,30 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->millimeters = SQRT( #if EITHER(CORE_IS_XY, MARKFORGED_XY) LINEAR_AXIS_GANG( - sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z) + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) ) #elif CORE_IS_XZ LINEAR_AXIS_GANG( - sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z) + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) ) #elif CORE_IS_YZ LINEAR_AXIS_GANG( - sq(steps_dist_mm.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.head.z) + sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) ) + #elif ENABLED(FOAMCUTTER_XYUV) + // Return the largest distance move from either X/Y or I/J plane + #if LINEAR_AXES >= 5 + _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) + #else + sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + #endif #else LINEAR_AXIS_GANG( - sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z) + sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) ) #endif ); @@ -2055,7 +2084,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(HAS_EXTRUDERS, block->steps.e = esteps); block->step_event_count = _MAX(LOGICAL_AXIS_LIST( - esteps, block->steps.a, block->steps.b, block->steps.c + esteps, block->steps.a, block->steps.b, block->steps.c, block->steps.i, block->steps.j, block->steps.k )); // Bail if this is a zero-length block @@ -2082,7 +2111,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (LINEAR_AXIS_GANG( block->steps.x, || block->steps.y, - || block->steps.z + || block->steps.z, + || block->steps.i, + || block->steps.j, + || block->steps.k )) powerManager.power_on(); #endif @@ -2111,7 +2143,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, LINEAR_AXIS_CODE( if (block->steps.x) ENABLE_AXIS_X(), if (block->steps.y) ENABLE_AXIS_Y(), - if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z() + if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(), + if (block->steps.i) ENABLE_AXIS_I(), + if (block->steps.j) ENABLE_AXIS_J(), + if (block->steps.k) ENABLE_AXIS_K() ); #endif @@ -2301,8 +2336,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, const float steps_per_mm = block->step_event_count * inverse_millimeters; uint32_t accel; if (LINEAR_AXIS_GANG( - !block->steps.a, && !block->steps.b, && !block->steps.c - )) { // Is this a retract / recover move? + !block->steps.a, && !block->steps.b, && !block->steps.c, + && !block->steps.i, && !block->steps.j, && !block->steps.k) + ) { // Is this a retract / recover move? accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2 TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover } @@ -2371,7 +2407,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)), LIMIT_ACCEL_LONG(A_AXIS, 0), LIMIT_ACCEL_LONG(B_AXIS, 0), - LIMIT_ACCEL_LONG(C_AXIS, 0) + LIMIT_ACCEL_LONG(C_AXIS, 0), + LIMIT_ACCEL_LONG(I_AXIS, 0), + LIMIT_ACCEL_LONG(J_AXIS, 0), + LIMIT_ACCEL_LONG(K_AXIS, 0) ); } else { @@ -2379,7 +2418,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)), LIMIT_ACCEL_FLOAT(A_AXIS, 0), LIMIT_ACCEL_FLOAT(B_AXIS, 0), - LIMIT_ACCEL_FLOAT(C_AXIS, 0) + LIMIT_ACCEL_FLOAT(C_AXIS, 0), + LIMIT_ACCEL_FLOAT(I_AXIS, 0), + LIMIT_ACCEL_FLOAT(J_AXIS, 0), + LIMIT_ACCEL_FLOAT(K_AXIS, 0) ); } } @@ -2444,7 +2486,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_DIST_MM_ARG cart_dist_mm #else - LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z) + LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.i, steps_dist_mm.j, steps_dist_mm.k) #endif ; @@ -2467,7 +2509,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, + (-prev_unit_vec.e * unit_vec.e), (-prev_unit_vec.x * unit_vec.x), + (-prev_unit_vec.y * unit_vec.y), - + (-prev_unit_vec.z * unit_vec.z) + + (-prev_unit_vec.z * unit_vec.z), + + (-prev_unit_vec.i * unit_vec.i), + + (-prev_unit_vec.j * unit_vec.j), + + (-prev_unit_vec.k * unit_vec.k) ); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). @@ -2783,10 +2828,9 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ * * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc. */ -bool Planner::buffer_segment( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) +bool Planner::buffer_segment(const abce_pos_t &abce OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ + , const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const_float_t millimeters/*=0.0*/ ) { // If we are cleaning, do not accept queuing of movements @@ -2804,54 +2848,70 @@ bool Planner::buffer_segment( // Calculate target position in absolute steps const abce_long_t target = { LOGICAL_AXIS_LIST( - int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])), - int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])), - int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])), - int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS])) + int32_t(LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])), + int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])), + int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])), + int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])), + int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), // FIXME (DerAndere): Multiplication by 4.0 is a work-around for issue with wrong internal steps per mm + int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])), + int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])) ) }; #if HAS_POSITION_FLOAT - const xyze_pos_t target_float = LOGICAL_AXIS_ARRAY(e, a, b, c); + const xyze_pos_t target_float = abce; #endif #if HAS_EXTRUDERS // DRYRUN prevents E moves from taking place if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { position.e = target.e; - TERN_(HAS_POSITION_FLOAT, position_float.e = e); + TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e); } #endif /* <-- add a slash to enable SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); #if IS_KINEMATIC - SERIAL_ECHOPAIR(" A:", a); - SERIAL_ECHOPAIR(" (", position.a); - SERIAL_ECHOPAIR("->", target.a); - SERIAL_ECHOPAIR(") B:", b); + SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b); #else - SERIAL_ECHOPAIR_P(SP_X_LBL, a); - SERIAL_ECHOPAIR(" (", position.x); - SERIAL_ECHOPAIR("->", target.x); + SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a); + SERIAL_ECHOPAIR(" (", position.x, "->", target.x); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Y_LBL, b); + SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b); #endif - SERIAL_ECHOPAIR(" (", position.y); - SERIAL_ECHOPAIR("->", target.y); - #if ENABLED(DELTA) - SERIAL_ECHOPAIR(") C:", c); + SERIAL_ECHOPAIR(" (", position.y, "->", target.y); + #if LINEAR_AXES >= ABC + #if ENABLED(DELTA) + SERIAL_ECHOPAIR(") C:", abce.c); + #else + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c); + #endif + SERIAL_ECHOPAIR(" (", position.z, "->", target.z); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 4 + SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i); + SERIAL_ECHOPAIR(" (", position.i, "->", target.i); // FIXME (DerAndere): Introduce work-around for issue with wrong internal steps per mm and feedrate for I_AXIS + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 5 + SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j); + SERIAL_ECHOPAIR(" (", position.j, "->", target.j); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 6 + SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k); + SERIAL_ECHOPAIR(" (", position.k, "->", target.k); + SERIAL_CHAR(')'); + #endif + #if HAS_EXTRUDERS + SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e); + SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")"); #else - SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Z_LBL, c); + SERIAL_EOL(); #endif - SERIAL_ECHOPAIR(" (", position.z); - SERIAL_ECHOPAIR("->", target.z); - SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_E_LBL, e); - SERIAL_ECHOPAIR(" (", position.e); - SERIAL_ECHOPAIR("->", target.e); - SERIAL_ECHOLNPGM(")"); //*/ // Queue the movement. Return 'false' if the move was not queued. @@ -2874,34 +2934,34 @@ bool Planner::buffer_segment( * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees - * fr_mm_s - (target) speed of the move (mm/s) - * extruder - target extruder - * millimeters - the length of the movement, if known - * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) + * cart - target position in mm or degrees + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder + * millimeters - the length of the movement, if known + * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ -bool Planner::buffer_line( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) - , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters - OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration) +bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const float millimeters/*=0.0*/ + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration/*=0.0*/) ) { - xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz); + xyze_pos_t machine = cart; TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); #if IS_KINEMATIC #if HAS_JUNCTION_DEVIATION - const xyze_pos_t cart_dist_mm = { - rx - position_cart.x, ry - position_cart.y, - rz - position_cart.z, e - position_cart.e - }; + const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY( + cart.e - position_cart.e, + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #else - const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY( + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #endif - float mm = millimeters; - if (mm == 0.0) - mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z); + const float mm = millimeters ?: (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z)); // Cartesian XYZ to kinematic ABC, stored in global 'delta' inverse_kinematics(machine); @@ -2915,17 +2975,12 @@ bool Planner::buffer_line( #else const feedRate_t feedrate = fr_mm_s; #endif - if (buffer_segment(delta.a, delta.b, delta.c, machine.e - #if HAS_JUNCTION_DEVIATION - , cart_dist_mm - #endif - , feedrate, extruder, mm - )) { - position_cart.set(rx, ry, rz, e); + delta.e = machine.e; + if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) { + position_cart = cart; return true; } - else - return false; + return false; #else return buffer_segment(machine, fr_mm_s, extruder, millimeters); #endif @@ -2991,23 +3046,23 @@ bool Planner::buffer_line( #endif // DIRECT_STEPPING /** - * Directly set the planner ABC position (and stepper positions) + * Directly set the planner ABCE position (and stepper positions) * converting mm (or angles for SCARA) into steps. * - * The provided ABC position is in machine units. + * The provided ABCE position is in machine units. */ - -void Planner::set_machine_position_mm( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) -) { +void Planner::set_machine_position_mm(const abce_pos_t &abce) { TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - TERN_(HAS_POSITION_FLOAT, position_float.set(LOGICAL_AXIS_LIST(e, a, b, c))); + TERN_(HAS_POSITION_FLOAT, position_float = abce); position.set( LOGICAL_AXIS_LIST( - LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]), - LROUND(a * settings.axis_steps_per_mm[A_AXIS]), - LROUND(b * settings.axis_steps_per_mm[B_AXIS]), - LROUND(c * settings.axis_steps_per_mm[C_AXIS]) + LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]), + LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS]), + LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS]), + LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]), + LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]), + LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]), + LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]) ) ); if (has_blocks_queued()) { @@ -3019,15 +3074,14 @@ void Planner::set_machine_position_mm( stepper.set_position(position); } -void Planner::set_position_mm( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) -) { - xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz); +void Planner::set_position_mm(const xyze_pos_t &xyze) { + xyze_pos_t machine = xyze; TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true)); #if IS_KINEMATIC - position_cart.set(rx, ry, rz, e); + position_cart = xyze; inverse_kinematics(machine); - set_machine_position_mm(delta.a, delta.b, delta.c, machine.e); + delta.e = machine.e; + set_machine_position_mm(delta); #else set_machine_position_mm(machine); #endif @@ -3045,7 +3099,7 @@ void Planner::set_position_mm( const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); - TERN_(IS_KINEMATIC, position_cart.e = e); + TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e)); if (has_blocks_queued()) buffer_sync_block(); @@ -3057,15 +3111,11 @@ void Planner::set_position_mm( // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 void Planner::reset_acceleration_rates() { - #if ENABLED(DISTINCT_E_FACTORS) - #define AXIS_CONDITION (i < E_AXIS || i == E_AXIS_N(active_extruder)) - #else - #define AXIS_CONDITION true - #endif uint32_t highest_rate = 1; LOOP_DISTINCT_AXES(i) { max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i]; - if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); + if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder))) + NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk()); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 02b7179c5a..10114ebfc6 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -76,7 +76,9 @@ // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, - manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f); + manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, + _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, + _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f); #endif #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION @@ -758,23 +760,11 @@ class Planner { * extruder - target extruder * millimeters - the length of the movement, if known */ - static bool buffer_segment( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) + static bool buffer_segment(const abce_pos_t &abce OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 + , const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const_float_t millimeters=0.0 ); - FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 - ) { - return buffer_segment( - LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c) - OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) - , fr_mm_s, extruder, millimeters - ); - } - public: /** @@ -782,28 +772,16 @@ class Planner { * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees + * cart - target position in mm or degrees * fr_mm_s - (target) speed of the move (mm/s) * extruder - target extruder * millimeters - the length of the movement, if known * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ - static bool buffer_line( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) - , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 + static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const float millimeters=0.0 OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) ); - FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0) - ) { - return buffer_line( - LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z) - , fr_mm_s, extruder, millimeters - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - ); - } - #if ENABLED(DIRECT_STEPPING) static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps); #endif @@ -821,12 +799,7 @@ class Planner { * * Clears previous speed values. */ - static void set_position_mm( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz) - ); - FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) { - set_position_mm(LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z, cart.i, cart.j, cart.k)); - } + static void set_position_mm(const xyze_pos_t &xyze); #if HAS_EXTRUDERS static void set_e_position_mm(const_float_t e); @@ -838,12 +811,7 @@ class Planner { * The supplied position is in machine space, and no additional * conversions are applied. */ - static void set_machine_position_mm( - LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c) - ); - FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) { - set_machine_position_mm(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)); - } + static void set_machine_position_mm(const abce_pos_t &abce); /** * Get an axis position according to stepper position(s) @@ -854,7 +822,8 @@ class Planner { static inline abce_pos_t get_axis_positions_mm() { const abce_pos_t out = LOGICAL_AXIS_ARRAY( get_axis_position_mm(E_AXIS), - get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS) + get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS), + get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS) ); return out; } diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index a5e7696e0b..848906705f 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -182,9 +182,13 @@ void cubic_b_spline( // Compute and send new position xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY( - interp(position.e, target.e, t), // FIXME. These two are wrong, since the parameter t is not linear in the distance. - new_pos0, new_pos1, - interp(position.z, target.z, t) + interp(position.e, target.e, t), // FIXME. Wrong, since t is not linear in the distance. + new_pos0, + new_pos1, + interp(position.z, target.z, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.i, target.i, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.j, target.j, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.k, target.k, t) // FIXME. Wrong, since t is not linear in the distance. ); apply_motion_limits(new_bez); bez_target = new_bez; diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 7438a56614..da46c830f6 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -110,7 +110,7 @@ public: #else - static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767 + static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767 static bool set_deployed(const bool) { return false; } @@ -222,20 +222,20 @@ public: #define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \ "PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN"); VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3); - 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); + points[0] = xy_float_t({ PROBE_PT_1_X, PROBE_PT_1_Y }); + points[1] = xy_float_t({ PROBE_PT_2_X, PROBE_PT_2_Y }); + points[2] = xy_float_t({ PROBE_PT_3_X, PROBE_PT_3_Y }); #else #if IS_KINEMATIC constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025, COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5; - points[0].set((X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0); - points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120); - points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240); + points[0] = xy_float_t({ (X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0 }); + points[1] = xy_float_t({ (X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120 }); + points[2] = xy_float_t({ (X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240 }); #else - points[0].set(min_x(), min_y()); - points[1].set(max_x(), min_y()); - points[2].set((min_x() + max_x()) / 2, max_y()); + points[0] = xy_float_t({ min_x(), min_y() }); + points[1] = xy_float_t({ max_x(), min_y() }); + points[2] = xy_float_t({ (min_x() + max_x()) / 2, max_y() }); #endif #endif } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index fc4fdc1f92..aae0f97361 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -168,10 +168,14 @@ void M554_report(); #endif -typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; -typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; -typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; -typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; +#define _EN_ITEM(N) , E##N + +typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t; +typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t; +typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; +typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t; + +#undef _EN_ITEM // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) @@ -387,7 +391,7 @@ typedef struct SettingsDataStruct { #ifndef MOTOR_CURRENT_COUNT #define MOTOR_CURRENT_COUNT LINEAR_AXES #endif - uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E + uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E ... // // CNC_COORDINATE_SYSTEMS @@ -654,7 +658,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummyf); #endif #else - const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4); + const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4); EEPROM_WRITE(planner_max_jerk); #endif @@ -1087,6 +1091,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z) tmc_stepper_current.Z = stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + tmc_stepper_current.I = stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + tmc_stepper_current.J = stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + tmc_stepper_current.K = stepperK.getMilliamps(); + #endif #if AXIS_IS_TMC(X2) tmc_stepper_current.X2 = stepperX2.getMilliamps(); #endif @@ -1138,61 +1151,33 @@ void MarlinSettings::postprocess() { #if ENABLED(HYBRID_THRESHOLD) tmc_hybrid_threshold_t tmc_hybrid_threshold{0}; - #if AXIS_HAS_STEALTHCHOP(X) - tmc_hybrid_threshold.X = stepperX.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_hybrid_threshold.X = stepperX.get_pwm_thrs()); + TERN_(Y_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs()); + TERN_(Z_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs()); + TERN_(I_HAS_STEALTHCHOP, tmc_hybrid_threshold.I = stepperI.get_pwm_thrs()); + TERN_(J_HAS_STEALTHCHOP, tmc_hybrid_threshold.J = stepperJ.get_pwm_thrs()); + TERN_(K_HAS_STEALTHCHOP, tmc_hybrid_threshold.K = stepperK.get_pwm_thrs()); + TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs()); + TERN_(E0_HAS_STEALTHCHOP, tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs()); + TERN_(E1_HAS_STEALTHCHOP, tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs()); + TERN_(E2_HAS_STEALTHCHOP, tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs()); + TERN_(E3_HAS_STEALTHCHOP, tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs()); + TERN_(E4_HAS_STEALTHCHOP, tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs()); + TERN_(E5_HAS_STEALTHCHOP, tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs()); + TERN_(E6_HAS_STEALTHCHOP, tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs()); + TERN_(E7_HAS_STEALTHCHOP, tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs()); #else + #define _EN_ITEM(N) , .E##N = 30 const tmc_hybrid_threshold_t tmc_hybrid_threshold = { - LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3), - .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3, - .E0 = 30, .E1 = 30, .E2 = 30, .E3 = 30, - .E4 = 30, .E5 = 30, .E6 = 30, .E7 = 30 + LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3), + .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3 + REPEAT(EXTRUDERS, _EN_ITEM) }; + #undef _EN_ITEM #endif EEPROM_WRITE(tmc_hybrid_threshold); } @@ -1203,11 +1188,16 @@ void MarlinSettings::postprocess() { { tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS - TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()), + TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()), + TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()), + TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()), + TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()), + TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold()) + ); TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold()); - TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold()); - TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold()); TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold()); TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold()); @@ -1222,54 +1212,25 @@ void MarlinSettings::postprocess() { _FIELD_TEST(tmc_stealth_enabled); tmc_stealth_enabled_t tmc_stealth_enabled = { false }; - #if AXIS_HAS_STEALTHCHOP(X) - tmc_stealth_enabled.X = stepperX.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_stealth_enabled.X = stepperX.get_stored_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop()); + TERN_(I_HAS_STEALTHCHOP, tmc_stealth_enabled.I = stepperI.get_stored_stealthChop()); + TERN_(J_HAS_STEALTHCHOP, tmc_stealth_enabled.J = stepperJ.get_stored_stealthChop()); + TERN_(K_HAS_STEALTHCHOP, tmc_stealth_enabled.K = stepperK.get_stored_stealthChop()); + TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop()); + TERN_(E2_HAS_STEALTHCHOP, tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop()); + TERN_(E3_HAS_STEALTHCHOP, tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop()); + TERN_(E4_HAS_STEALTHCHOP, tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop()); + TERN_(E5_HAS_STEALTHCHOP, tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop()); + TERN_(E6_HAS_STEALTHCHOP, tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop()); + TERN_(E7_HAS_STEALTHCHOP, tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop()); EEPROM_WRITE(tmc_stealth_enabled); } @@ -1992,6 +1953,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z4) SET_CURR(Z4); #endif + #if AXIS_IS_TMC(I) + SET_CURR(I); + #endif + #if AXIS_IS_TMC(J) + SET_CURR(J); + #endif + #if AXIS_IS_TMC(K) + SET_CURR(K); + #endif #if AXIS_IS_TMC(E0) SET_CURR(E0); #endif @@ -2028,54 +1998,25 @@ void MarlinSettings::postprocess() { #if ENABLED(HYBRID_THRESHOLD) if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - stepperX.set_pwm_thrs(tmc_hybrid_threshold.X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7); - #endif + TERN_(X_HAS_STEALTHCHOP, stepperX.set_pwm_thrs(tmc_hybrid_threshold.X)); + TERN_(Y_HAS_STEALTHCHOP, stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y)); + TERN_(Z_HAS_STEALTHCHOP, stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z)); + TERN_(X2_HAS_STEALTHCHOP, stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2)); + TERN_(Y2_HAS_STEALTHCHOP, stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2)); + TERN_(Z2_HAS_STEALTHCHOP, stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2)); + TERN_(Z3_HAS_STEALTHCHOP, stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3)); + TERN_(Z4_HAS_STEALTHCHOP, stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4)); + TERN_(I_HAS_STEALTHCHOP, stepperI.set_pwm_thrs(tmc_hybrid_threshold.I)); + TERN_(J_HAS_STEALTHCHOP, stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J)); + TERN_(K_HAS_STEALTHCHOP, stepperK.set_pwm_thrs(tmc_hybrid_threshold.K)); + TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0)); + TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1)); + TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2)); + TERN_(E3_HAS_STEALTHCHOP, stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3)); + TERN_(E4_HAS_STEALTHCHOP, stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4)); + TERN_(E5_HAS_STEALTHCHOP, stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5)); + TERN_(E6_HAS_STEALTHCHOP, stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6)); + TERN_(E7_HAS_STEALTHCHOP, stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7)); } #endif } @@ -2089,11 +2030,16 @@ void MarlinSettings::postprocess() { EEPROM_READ(tmc_sgt); #if USE_SENSORLESS if (!validating) { - TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)), + TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)), + TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)), + TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)), + TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)), + TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K)) + ); TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2)); - TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)); TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2)); - TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)); TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2)); TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3)); TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4)); @@ -2112,54 +2058,25 @@ void MarlinSettings::postprocess() { #define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode(); if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - SET_STEPPING_MODE(X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - SET_STEPPING_MODE(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - SET_STEPPING_MODE(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - SET_STEPPING_MODE(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - SET_STEPPING_MODE(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - SET_STEPPING_MODE(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - SET_STEPPING_MODE(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - SET_STEPPING_MODE(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - SET_STEPPING_MODE(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - SET_STEPPING_MODE(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - SET_STEPPING_MODE(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - SET_STEPPING_MODE(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - SET_STEPPING_MODE(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - SET_STEPPING_MODE(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - SET_STEPPING_MODE(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - SET_STEPPING_MODE(E7); - #endif + TERN_(X_HAS_STEALTHCHOP, SET_STEPPING_MODE(X)); + TERN_(Y_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y)); + TERN_(Z_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z)); + TERN_(I_HAS_STEALTHCHOP, SET_STEPPING_MODE(I)); + TERN_(J_HAS_STEALTHCHOP, SET_STEPPING_MODE(J)); + TERN_(K_HAS_STEALTHCHOP, SET_STEPPING_MODE(K)); + TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2)); + TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2)); + TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z4)); + TERN_(E0_HAS_STEALTHCHOP, SET_STEPPING_MODE(E0)); + TERN_(E1_HAS_STEALTHCHOP, SET_STEPPING_MODE(E1)); + TERN_(E2_HAS_STEALTHCHOP, SET_STEPPING_MODE(E2)); + TERN_(E3_HAS_STEALTHCHOP, SET_STEPPING_MODE(E3)); + TERN_(E4_HAS_STEALTHCHOP, SET_STEPPING_MODE(E4)); + TERN_(E5_HAS_STEALTHCHOP, SET_STEPPING_MODE(E5)); + TERN_(E6_HAS_STEALTHCHOP, SET_STEPPING_MODE(E6)); + TERN_(E7_HAS_STEALTHCHOP, SET_STEPPING_MODE(E7)); } #endif } @@ -2598,14 +2515,25 @@ void MarlinSettings::reset() { #ifndef DEFAULT_XJERK #define DEFAULT_XJERK 0 #endif - #ifndef DEFAULT_YJERK + #if HAS_Y_AXIS && !defined(DEFAULT_YJERK) #define DEFAULT_YJERK 0 #endif - #ifndef DEFAULT_ZJERK + #if HAS_Z_AXIS && !defined(DEFAULT_ZJERK) #define DEFAULT_ZJERK 0 #endif - planner.max_jerk.set(LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK)); - TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); + #if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK) + #define DEFAULT_IJERK 0 + #endif + #if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK) + #define DEFAULT_JJERK 0 + #endif + #if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK) + #define DEFAULT_KJERK 0 + #endif + planner.max_jerk.set( + LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK) + ); + TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK); #endif #if HAS_JUNCTION_DEVIATION @@ -2703,11 +2631,11 @@ void MarlinSettings::reset() { #if HAS_BED_PROBE constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; - static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z."); + static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z...."); #if HAS_PROBE_XY_OFFSET LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a]; #else - probe.offset.set(0, 0, dpo[Z_AXIS]); + probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0)); #endif #endif @@ -3145,7 +3073,10 @@ void MarlinSettings::reset() { LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]) + SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]) ) #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) @@ -3167,7 +3098,10 @@ void MarlinSettings::reset() { LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) + SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]) ) #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) @@ -3210,9 +3144,14 @@ void MarlinSettings::reset() { , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) #endif #if HAS_CLASSIC_JERK - , SP_X_STR, LINEAR_UNIT(planner.max_jerk.x) - , SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y) - , SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), + SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), + SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), + SP_I_STR, LINEAR_UNIT(planner.max_jerk.i), + SP_J_STR, LINEAR_UNIT(planner.max_jerk.j), + SP_K_STR, LINEAR_UNIT(planner.max_jerk.k) + ) #if HAS_CLASSIC_E_JERK , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e) #endif @@ -3224,13 +3163,17 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( #if IS_CARTESIAN - PSTR(" M206 X"), LINEAR_UNIT(home_offset.x) - , SP_Y_STR, LINEAR_UNIT(home_offset.y) - , SP_Z_STR + LIST_N(LINEAR_AXES, + PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), + SP_Y_STR, LINEAR_UNIT(home_offset.y), + SP_Z_STR, LINEAR_UNIT(home_offset.z), + SP_I_STR, LINEAR_UNIT(home_offset.i), + SP_J_STR, LINEAR_UNIT(home_offset.j), + SP_K_STR, LINEAR_UNIT(home_offset.k) + ) #else - PSTR(" M206 Z") + PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z) #endif - , LINEAR_UNIT(home_offset.z) ); #endif @@ -3582,6 +3525,19 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); #endif + #if AXIS_IS_TMC(I) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); + #endif + #if AXIS_IS_TMC(J) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); + #endif + #if AXIS_IS_TMC(K) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); + #endif + #if AXIS_IS_TMC(E0) say_M906(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); @@ -3621,74 +3577,87 @@ void MarlinSettings::reset() { */ #if ENABLED(HYBRID_THRESHOLD) CONFIG_ECHO_HEADING("Hybrid Threshold:"); - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP say_M913(forReplay); - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2) + #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOPGM(" I1"); - #if AXIS_HAS_STEALTHCHOP(X2) + #if X2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y2) + #if Y2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z2) + #if Z2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(Z3) + #if Z3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z4) + #if Z4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E0) + #if I_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); + #endif + #if J_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); + #endif + #if K_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); + #endif + + #if E0_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E1) + #if E1_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E2) + #if E2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E3) + #if E3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E4) + #if E4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E5) + #if E5_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E6) + #if E6_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E7) + #if E7_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); #endif @@ -3743,6 +3712,22 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); #endif + #if I_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); + #endif + #if J_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); + #endif + #if K_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); + #endif + #endif // USE_SENSORLESS /** @@ -3750,45 +3735,29 @@ void MarlinSettings::reset() { */ #if HAS_STEALTHCHOP CONFIG_ECHO_HEADING("Driver stepping mode:"); - #if AXIS_HAS_STEALTHCHOP(X) - const bool chop_x = stepperX.get_stored_stealthChop(); - #else - constexpr bool chop_x = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - const bool chop_y = stepperY.get_stored_stealthChop(); - #else - constexpr bool chop_y = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - const bool chop_z = stepperZ.get_stored_stealthChop(); - #else - constexpr bool chop_z = false; - #endif + const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()), + chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()), + chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()), + chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()), + chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()), + chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()); - if (chop_x || chop_y || chop_z) { + if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) { say_M569(forReplay); - if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR); - if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR); - if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR); + LINEAR_AXIS_CODE( + if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR), + if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR), + if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR), + if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR), + if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR), + if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR) + ); SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(X2) - const bool chop_x2 = stepperX2.get_stored_stealthChop(); - #else - constexpr bool chop_x2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - const bool chop_y2 = stepperY2.get_stored_stealthChop(); - #else - constexpr bool chop_y2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - const bool chop_z2 = stepperZ2.get_stored_stealthChop(); - #else - constexpr bool chop_z2 = false; - #endif + const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()), + chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()), + chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop()); if (chop_x2 || chop_y2 || chop_z2) { say_M569(forReplay, PSTR("I1")); @@ -3798,38 +3767,21 @@ void MarlinSettings::reset() { SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(Z3) - if (stepperZ3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I2 Z"), true); } - #endif + if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); } - #if AXIS_HAS_STEALTHCHOP(Z4) - if (stepperZ4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I3 Z"), true); } - #endif + if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); } + if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); } + if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); } - #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T0 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T1 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - if (stepperE2.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T2 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - if (stepperE3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T3 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - if (stepperE4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T4 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - if (stepperE5.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T5 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - if (stepperE6.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T6 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - if (stepperE7.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T7 E"), true); } - #endif + if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); } + if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); } + if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); } + if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); } + if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); } + if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); } + if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); } + if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); } #endif // HAS_STEALTHCHOP @@ -3859,7 +3811,7 @@ void MarlinSettings::reset() { ); #elif HAS_MOTOR_CURRENT_SPI SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: - LOOP_LOGICAL_AXES(q) { // X Y Z E (map to X Y Z E0 by default) + LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default) SERIAL_CHAR(' ', axis_codes[q]); SERIAL_ECHO(stepper.motor_current_setting[q]); } @@ -3869,7 +3821,7 @@ void MarlinSettings::reset() { #elif ENABLED(HAS_MOTOR_CURRENT_I2C) // i2c-based has any number of values // Values sent over i2c are not stored. // Indexes map directly to drivers, not axes. - #elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z E + #elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z (I J K) E // Values sent over i2c are not stored. Uses indirect mapping. #endif @@ -3901,7 +3853,10 @@ void MarlinSettings::reset() { , LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), - SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z) + SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), + SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), + SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), + SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) ) #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 05286a6566..062049ec77 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -378,7 +378,7 @@ xyze_int8_t Stepper::count_direction{0}; #else #define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Y_AXIS #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v) #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v) #endif @@ -415,11 +415,24 @@ xyze_int8_t Stepper::count_direction{0}; #else #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Z_AXIS #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v) #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v) #endif +#if LINEAR_AXES >= 4 + #define I_APPLY_DIR(v,Q) I_DIR_WRITE(v) + #define I_APPLY_STEP(v,Q) I_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 5 + #define J_APPLY_DIR(v,Q) J_DIR_WRITE(v) + #define J_APPLY_STEP(v,Q) J_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 6 + #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v) + #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v) +#endif + #if DISABLED(MIXING_EXTRUDER) #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v) #endif @@ -486,6 +499,18 @@ void Stepper::set_directions() { SET_STEP_DIR(Z); // C #endif + #if HAS_I_DIR + SET_STEP_DIR(I); // I + #endif + + #if HAS_J_DIR + SET_STEP_DIR(J); // J + #endif + + #if HAS_K_DIR + SET_STEP_DIR(K); // K + #endif + #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) // Because this is valid for the whole block we don't know @@ -1584,7 +1609,7 @@ void Stepper::pulse_phase_isr() { const bool is_page = IS_PAGE(current_block); #if ENABLED(DIRECT_STEPPING) - + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 if (is_page) { #if STEPPER_PAGE_FORMAT == SP_4x4D_128 @@ -1700,6 +1725,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_PREP(Z); #endif + #if HAS_I_STEP + PULSE_PREP(I); + #endif + #if HAS_J_STEP + PULSE_PREP(J); + #endif + #if HAS_K_STEP + PULSE_PREP(K); + #endif #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) delta_error.e += advance_dividend.e; @@ -1735,6 +1769,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_START(Z); #endif + #if HAS_I_STEP + PULSE_START(I); + #endif + #if HAS_J_STEP + PULSE_START(J); + #endif + #if HAS_K_STEP + PULSE_START(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1764,6 +1807,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_STOP(Z); #endif + #if HAS_I_STEP + PULSE_STOP(I); + #endif + #if HAS_J_STEP + PULSE_STOP(J); + #endif + #if HAS_K_STEP + PULSE_STOP(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1798,6 +1850,7 @@ uint32_t Stepper::block_phase_isr() { // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { #if ENABLED(DIRECT_STEPPING) + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 #if STEPPER_PAGE_FORMAT == SP_4x4D_128 #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; @@ -2104,9 +2157,12 @@ uint32_t Stepper::block_phase_isr() { uint8_t axis_bits = 0; LINEAR_AXIS_CODE( - if (X_MOVE_TEST) SBI(axis_bits, A_AXIS), - if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS), - if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS) + if (X_MOVE_TEST) SBI(axis_bits, A_AXIS), + if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS), + if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS), + if (current_block->steps.i) SBI(axis_bits, I_AXIS), + if (current_block->steps.j) SBI(axis_bits, J_AXIS), + if (current_block->steps.k) SBI(axis_bits, K_AXIS) ); //if (current_block->steps.e) SBI(axis_bits, E_AXIS); //if (current_block->steps.a) SBI(axis_bits, X_HEAD); @@ -2441,6 +2497,15 @@ void Stepper::init() { Z4_DIR_INIT(); #endif #endif + #if HAS_I_DIR + I_DIR_INIT(); + #endif + #if HAS_J_DIR + J_DIR_INIT(); + #endif + #if HAS_K_DIR + K_DIR_INIT(); + #endif #if HAS_E0_DIR E0_DIR_INIT(); #endif @@ -2499,6 +2564,18 @@ void Stepper::init() { if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH); #endif #endif + #if HAS_I_ENABLE + I_ENABLE_INIT(); + if (!I_ENABLE_ON) I_ENABLE_WRITE(HIGH); + #endif + #if HAS_J_ENABLE + J_ENABLE_INIT(); + if (!J_ENABLE_ON) J_ENABLE_WRITE(HIGH); + #endif + #if HAS_K_ENABLE + K_ENABLE_INIT(); + if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH); + #endif #if HAS_E0_ENABLE E0_ENABLE_INIT(); if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH); @@ -2575,6 +2652,15 @@ void Stepper::init() { #endif AXIS_INIT(Z, Z); #endif + #if HAS_I_STEP + AXIS_INIT(I, I); + #endif + #if HAS_J_STEP + AXIS_INIT(J, J); + #endif + #if HAS_K_STEP + AXIS_INIT(K, K); + #endif #if E_STEPPERS && HAS_E0_STEP E_AXIS_INIT(0); @@ -2612,7 +2698,10 @@ void Stepper::init() { LINEAR_AXIS_GANG( | TERN0(INVERT_X_DIR, _BV(X_AXIS)), | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)), - | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)) + | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)), + | TERN0(INVERT_I_DIR, _BV(I_AXIS)), + | TERN0(INVERT_J_DIR, _BV(J_AXIS)), + | TERN0(INVERT_K_DIR, _BV(K_AXIS)) ) ); @@ -2625,32 +2714,32 @@ void Stepper::init() { /** * Set the stepper positions directly in steps * - * The input is based on the typical per-axis XYZ steps. + * The input is based on the typical per-axis XYZE steps. * For CORE machines XYZ needs to be translated to ABC. * * This allows get_axis_position_mm to correctly - * derive the current XYZ position later on. + * derive the current XYZE position later on. */ -void Stepper::_set_position( - LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) -) { - #if CORE_IS_XY - // corexy positioning - // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html - count_position.set(a + b, CORESIGN(a - b), c); - #elif CORE_IS_XZ - // corexz planning - count_position.set(a + c, b, CORESIGN(a - c)); - #elif CORE_IS_YZ - // coreyz planning - count_position.set(a, b + c, CORESIGN(b - c)); - #elif ENABLED(MARKFORGED_XY) - count_position.set(a - b, b, c); +void Stepper::_set_position(const abce_long_t &spos) { + #if EITHER(IS_CORE, MARKFORGED_XY) + #if CORE_IS_XY + // corexy positioning + // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html + count_position.set(spos.a + spos.b, CORESIGN(spos.a - spos.b), spos.c); + #elif CORE_IS_XZ + // corexz planning + count_position.set(spos.a + spos.c, spos.b, CORESIGN(spos.a - spos.c)); + #elif CORE_IS_YZ + // coreyz planning + count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c)); + #elif ENABLED(MARKFORGED_XY) + count_position.set(spos.a - spos.b, spos.b, spos.c); + #endif + TERN_(HAS_EXTRUDERS, count_position.e = spos.e); #else // default non-h-bot planning - count_position.set(LINEAR_AXIS_LIST(a, b, c)); + count_position = spos; #endif - TERN_(HAS_EXTRUDERS, count_position.e = e); } /** @@ -2673,13 +2762,10 @@ int32_t Stepper::position(const AxisEnum axis) { } // Set the current position in steps -//TODO: Test for LINEAR_AXES >= 4 -void Stepper::set_position( - LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) -) { +void Stepper::set_position(const xyze_long_t &spos) { planner.synchronize(); const bool was_enabled = suspend(); - _set_position(LOGICAL_AXIS_LIST(e, a, b, c)); + _set_position(spos); if (was_enabled) wake_up(); } @@ -2747,18 +2833,24 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } +#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) + #define USES_ABC 1 +#endif +#if ANY(USES_ABC, MARKFORGED_XY, IS_SCARA) + #define USES_AB 1 +#endif + void Stepper::report_a_position(const xyz_long_t &pos) { - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, 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 ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) - SERIAL_ECHOPAIR(" C:", pos.z); - #elif LINEAR_AXES >= 3 - SERIAL_ECHOPAIR_P(SP_Z_LBL, pos.z); - #endif - SERIAL_EOL(); + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + TERN(USES_AB, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, + TERN(USES_AB, PSTR("B:"), SP_Y_LBL), pos.y, + TERN(USES_ABC, PSTR("C:"), SP_Z_LBL), pos.z, + SP_I_LBL, pos.i, + SP_J_LBL, pos.j, + SP_K_LBL, pos.k + ) + ); } void Stepper::report_positions() { @@ -2866,9 +2958,7 @@ void Stepper::report_positions() { // No other ISR should ever interrupt this! void Stepper::do_babystep(const AxisEnum axis, const bool direction) { - #if DISABLED(INTEGRATED_BABYSTEPPING) - cli(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, cli()); switch (axis) { @@ -2912,35 +3002,90 @@ void Stepper::report_positions() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); DIR_WAIT_BEFORE(); - const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ()); + const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ()); X_DIR_WRITE(INVERT_X_DIR ^ z_direction); - Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); - Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(INVERT_I_DIR ^ z_direction); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(INVERT_J_DIR ^ z_direction); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(INVERT_K_DIR ^ z_direction); + #endif DIR_WAIT_AFTER(); _SAVE_START(); X_STEP_WRITE(!INVERT_X_STEP_PIN); - Y_STEP_WRITE(!INVERT_Y_STEP_PIN); - Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(!INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(!INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(!INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(!INVERT_K_STEP_PIN); + #endif _PULSE_WAIT(); X_STEP_WRITE(INVERT_X_STEP_PIN); - Y_STEP_WRITE(INVERT_Y_STEP_PIN); - Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(INVERT_K_STEP_PIN); + #endif // Restore direction bits EXTRA_DIR_WAIT_BEFORE(); X_DIR_WRITE(old_dir.x); - Y_DIR_WRITE(old_dir.y); - Z_DIR_WRITE(old_dir.z); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(old_dir.y); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(old_dir.z); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(old_dir.i); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(old_dir.j); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(old_dir.k); + #endif EXTRA_DIR_WAIT_AFTER(); @@ -2948,12 +3093,20 @@ void Stepper::report_positions() { } break; + #if LINEAR_AXES >= 4 + case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break; + #endif + default: break; } - #if DISABLED(INTEGRATED_BABYSTEPPING) - sei(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, sei()); } #endif // BABYSTEPPING @@ -3288,6 +3441,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS1_PIN, ms1); break; #endif + #if HAS_I_MICROSTEPS + case 11: WRITE(I_MS1_PIN, ms1); break + #endif + #if HAS_J_MICROSTEPS + case 12: WRITE(J_MS1_PIN, ms1); break + #endif + #if HAS_K_MICROSTEPS + case 13: WRITE(K_MS1_PIN, ms1); break + #endif } if (ms2 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3350,6 +3512,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS2_PIN, ms2); break; #endif + #if HAS_I_M_PINS + case 11: WRITE(I_MS2_PIN, ms2); break + #endif + #if HAS_J_M_PINS + case 12: WRITE(J_MS2_PIN, ms2); break + #endif + #if HAS_K_M_PINS + case 13: WRITE(K_MS2_PIN, ms2); break + #endif } if (ms3 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3468,6 +3639,24 @@ void Stepper::report_positions() { PIN_CHAR(Z_MS3); #endif #endif + #if HAS_I_MS_PINS + MS_LINE(I); + #if PIN_EXISTS(I_MS3) + PIN_CHAR(I_MS3); + #endif + #endif + #if HAS_J_MS_PINS + MS_LINE(J); + #if PIN_EXISTS(J_MS3) + PIN_CHAR(J_MS3); + #endif + #endif + #if HAS_K_MS_PINS + MS_LINE(K); + #if PIN_EXISTS(K_MS3) + PIN_CHAR(K_MS3); + #endif + #endif #if HAS_E0_MS_PINS MS_LINE(E0); #if PIN_EXISTS(E0_MS3) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 67ca6fa433..236ba5ee98 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -133,27 +133,6 @@ #endif -// Add time for each stepper -#if HAS_X_STEP - #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_X_STEPPER_CYCLES 0UL -#endif -#if HAS_Y_STEP - #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_START_Y_STEPPER_CYCLES 0UL - #define ISR_Y_STEPPER_CYCLES 0UL -#endif -#if HAS_Z_STEP - #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_Z_STEPPER_CYCLES 0UL -#endif - -// E is always interpolated, even for mixing extruders -#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES - // If linear advance is disabled, the loop also handles them #if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER) #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) @@ -161,8 +140,31 @@ #define ISR_MIXING_STEPPER_CYCLES 0UL #endif +// Add time for each stepper +#if HAS_X_STEP + #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_Y_STEP + #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_Z_STEP + #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_I_STEP + #define ISR_I_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_J_STEP + #define ISR_J_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_K_STEP + #define ISR_K_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_EXTRUDERS + #define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES // E is always interpolated, even for mixing extruders +#endif + // And the total minimum loop time, not including the base -#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES) +#define MIN_ISR_LOOP_CYCLES (ISR_MIXING_STEPPER_CYCLES LOGICAL_AXIS_GANG(+ ISR_E_STEPPER_CYCLES, + ISR_X_STEPPER_CYCLES, + ISR_Y_STEPPER_CYCLES, + ISR_Z_STEPPER_CYCLES, + ISR_I_STEPPER_CYCLES, + ISR_J_STEPPER_CYCLES, + ISR_K_STEPPER_CYCLES)) // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate #define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N)) @@ -433,12 +435,7 @@ class Stepper { static int32_t position(const AxisEnum axis); // Set the current position in steps - static void set_position( - LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) - ); - static inline void set_position(const xyze_long_t &abce) { - set_position(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)); - } + static void set_position(const xyze_long_t &spos); static void set_axis_position(const AxisEnum a, const int32_t &v); // Report the positions of the steppers, in steps @@ -534,12 +531,7 @@ class Stepper { private: // Set the current position in steps - static void _set_position( - LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c) - ); - FORCE_INLINE static void _set_position(const abce_long_t &spos) { - _set_position(LOGICAL_AXIS_LIST(spos.e, spos.a, spos.b, spos.c)); - } + static void _set_position(const abce_long_t &spos); FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) { uint32_t timer; diff --git a/Marlin/src/module/stepper/L64xx.cpp b/Marlin/src/module/stepper/L64xx.cpp index 004e17a3fd..27816fb4f7 100644 --- a/Marlin/src/module/stepper/L64xx.cpp +++ b/Marlin/src/module/stepper/L64xx.cpp @@ -55,6 +55,15 @@ #if AXIS_IS_L64XX(Z4) L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN); #endif +#if AXIS_IS_L64XX(I) + L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(J) + L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(K) + L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN); +#endif #if AXIS_IS_L64XX(E0) L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN); #endif @@ -199,6 +208,15 @@ void L64XX_Marlin::init_to_defaults() { #if AXIS_IS_L64XX(Z4) L6470_INIT_CHIP(Z4); #endif + #if AXIS_IS_L64XX(I) + L6470_INIT_CHIP(I); + #endif + #if AXIS_IS_L64XX(J) + L6470_INIT_CHIP(J); + #endif + #if AXIS_IS_L64XX(K) + L6470_INIT_CHIP(K); + #endif #if AXIS_IS_L64XX(E0) L6470_INIT_CHIP(E0); #endif diff --git a/Marlin/src/module/stepper/L64xx.h b/Marlin/src/module/stepper/L64xx.h index 9c8b0b1bdd..9f7e6623b1 100644 --- a/Marlin/src/module/stepper/L64xx.h +++ b/Marlin/src/module/stepper/L64xx.h @@ -206,6 +206,66 @@ #define DISABLE_STEPPER_Z4() stepperZ4.free() #endif +// I Stepper +#if AXIS_IS_L64XX(I) + extern L64XX_CLASS(I) stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free()) + #define I_ENABLE_READ() (stepperI.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_I(L6474) + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) L6474_DIR_WRITE(I, STATE) + #define I_DIR_READ() READ(I_DIR_PIN) + #else + #define I_DIR_INIT() NOOP + #define I_DIR_WRITE(STATE) L64XX_DIR_WRITE(I, STATE) + #define I_DIR_READ() (stepper##I.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_I(L6470) + #define DISABLE_STEPPER_I() stepperI.free() + #endif + #endif +#endif + +// J Stepper +#if AXIS_IS_L64XX(J) + extern L64XX_CLASS(J) stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free()) + #define J_ENABLE_READ() (stepperJ.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_J(L6474) + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) L6474_DIR_WRITE(J, STATE) + #define J_DIR_READ() READ(J_DIR_PIN) + #else + #define J_DIR_INIT() NOOP + #define J_DIR_WRITE(STATE) L64XX_DIR_WRITE(J, STATE) + #define J_DIR_READ() (stepper##J.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_J(L6470) + #define DISABLE_STEPPER_J() stepperJ.free() + #endif + #endif +#endif + +// K Stepper +#if AXIS_IS_L64XX(K) + extern L64XX_CLASS(K) stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free()) + #define K_ENABLE_READ() (stepperK.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_K(L6474) + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) L6474_DIR_WRITE(K, STATE) + #define K_DIR_READ() READ(K_DIR_PIN) + #else + #define K_DIR_INIT() NOOP + #define K_DIR_WRITE(STATE) L64XX_DIR_WRITE(K, STATE) + #define K_DIR_READ() (stepper##K.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_K(L6470) + #define DISABLE_STEPPER_K() stepperK.free() + #endif + #endif +#endif + // E0 Stepper #if AXIS_IS_L64XX(E0) extern L64XX_CLASS(E0) stepperE0; diff --git a/Marlin/src/module/stepper/TMC26X.cpp b/Marlin/src/module/stepper/TMC26X.cpp index 926f1a4e08..26f91bfeb9 100644 --- a/Marlin/src/module/stepper/TMC26X.cpp +++ b/Marlin/src/module/stepper/TMC26X.cpp @@ -60,6 +60,15 @@ #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_DEFINE(Z4); #endif +#if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_DEFINE(I); +#endif +#if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_DEFINE(J); +#endif +#if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_DEFINE(K); +#endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_DEFINE(E0); #endif @@ -115,6 +124,15 @@ void tmc26x_init_to_defaults() { #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_INIT(Z4); #endif + #if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_INIT(I); + #endif + #if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_INIT(J); + #endif + #if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_INIT(K); + #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_INIT(E0); #endif diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index 547eb6521f..988bebe0f2 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -99,6 +99,30 @@ void tmc26x_init_to_defaults(); #define Z4_ENABLE_READ() stepperZ4.isEnabled() #endif +// I Stepper +#if HAS_I_ENABLE && AXIS_DRIVER_TYPE_I(TMC26X) + extern TMC26XStepper stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) stepperI.setEnabled(STATE) + #define I_ENABLE_READ() stepperI.isEnabled() +#endif + +// J Stepper +#if HAS_J_ENABLE && AXIS_DRIVER_TYPE_J(TMC26X) + extern TMC26XStepper stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) stepperJ.setEnabled(STATE) + #define J_ENABLE_READ() stepperJ.isEnabled() +#endif + +// K Stepper +#if HAS_K_ENABLE && AXIS_DRIVER_TYPE_K(TMC26X) + extern TMC26XStepper stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) stepperK.setEnabled(STATE) + #define K_ENABLE_READ() stepperK.isEnabled() +#endif + // E0 Stepper #if AXIS_DRIVER_TYPE_E0(TMC26X) extern TMC26XStepper stepperE0; diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 6297d83366..e44496d022 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -37,9 +37,7 @@ void restore_stepper_drivers() { } void reset_stepper_drivers() { - #if HAS_DRIVER(TMC26X) - tmc26x_init_to_defaults(); - #endif + TERN_(HAS_TMC26X, tmc26x_init_to_defaults()); TERN_(HAS_L64XX, L64xxManager.init_to_defaults()); TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers()); } diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 6f9fd24ce8..4770fd4dc1 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -36,7 +36,7 @@ #include "L64xx.h" #endif -#if HAS_DRIVER(TMC26X) +#if HAS_TMC26X #include "TMC26X.h" #endif @@ -65,38 +65,42 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define X_STEP_READ() bool(READ(X_STEP_PIN)) // Y Stepper -#ifndef Y_ENABLE_INIT - #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) - #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) - #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) +#if HAS_Y_AXIS + #ifndef Y_ENABLE_INIT + #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) + #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) + #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) + #endif + #ifndef Y_DIR_INIT + #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) + #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) + #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) + #endif + #define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) + #ifndef Y_STEP_WRITE + #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) + #endif + #define Y_STEP_READ() bool(READ(Y_STEP_PIN)) #endif -#ifndef Y_DIR_INIT - #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) - #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) - #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) -#endif -#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) -#ifndef Y_STEP_WRITE - #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) -#endif -#define Y_STEP_READ() bool(READ(Y_STEP_PIN)) // Z Stepper -#ifndef Z_ENABLE_INIT - #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) - #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) - #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) +#if HAS_Z_AXIS + #ifndef Z_ENABLE_INIT + #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) + #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) + #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) + #endif + #ifndef Z_DIR_INIT + #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) + #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) + #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) + #endif + #define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) + #ifndef Z_STEP_WRITE + #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) + #endif + #define Z_STEP_READ() bool(READ(Z_STEP_PIN)) #endif -#ifndef Z_DIR_INIT - #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) - #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) - #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) -#endif -#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) -#ifndef Z_STEP_WRITE - #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) -#endif -#define Z_STEP_READ() bool(READ(Z_STEP_PIN)) // X2 Stepper #if HAS_X2_ENABLE @@ -201,6 +205,63 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z4_DIR_WRITE(STATE) NOOP #endif +// I Stepper +#if LINEAR_AXES >= 4 + #ifndef I_ENABLE_INIT + #define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN) + #define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE) + #define I_ENABLE_READ() bool(READ(I_ENABLE_PIN)) + #endif + #ifndef I_DIR_INIT + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) WRITE(I_DIR_PIN,STATE) + #define I_DIR_READ() bool(READ(I_DIR_PIN)) + #endif + #define I_STEP_INIT() SET_OUTPUT(I_STEP_PIN) + #ifndef I_STEP_WRITE + #define I_STEP_WRITE(STATE) WRITE(I_STEP_PIN,STATE) + #endif + #define I_STEP_READ() bool(READ(I_STEP_PIN)) +#endif + +// J Stepper +#if LINEAR_AXES >= 5 + #ifndef J_ENABLE_INIT + #define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN) + #define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE) + #define J_ENABLE_READ() bool(READ(J_ENABLE_PIN)) + #endif + #ifndef J_DIR_INIT + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) WRITE(J_DIR_PIN,STATE) + #define J_DIR_READ() bool(READ(J_DIR_PIN)) + #endif + #define J_STEP_INIT() SET_OUTPUT(J_STEP_PIN) + #ifndef J_STEP_WRITE + #define J_STEP_WRITE(STATE) WRITE(J_STEP_PIN,STATE) + #endif + #define J_STEP_READ() bool(READ(J_STEP_PIN)) +#endif + +// K Stepper +#if LINEAR_AXES >= 6 + #ifndef K_ENABLE_INIT + #define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN) + #define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE) + #define K_ENABLE_READ() bool(READ(K_ENABLE_PIN)) + #endif + #ifndef K_DIR_INIT + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) WRITE(K_DIR_PIN,STATE) + #define K_DIR_READ() bool(READ(K_DIR_PIN)) + #endif + #define K_STEP_INIT() SET_OUTPUT(K_STEP_PIN) + #ifndef K_STEP_WRITE + #define K_STEP_WRITE(STATE) WRITE(K_STEP_PIN,STATE) + #endif + #define K_STEP_READ() bool(READ(K_STEP_PIN)) +#endif + // E0 Stepper #ifndef E0_ENABLE_INIT #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN) @@ -720,6 +781,51 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif #endif +#ifndef ENABLE_STEPPER_I + #if HAS_I_ENABLE + #define ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON) + #else + #define ENABLE_STEPPER_I() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_I + #if HAS_I_ENABLE + #define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON) + #else + #define DISABLE_STEPPER_I() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_J + #if HAS_J_ENABLE + #define ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON) + #else + #define ENABLE_STEPPER_J() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_J + #if HAS_J_ENABLE + #define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON) + #else + #define DISABLE_STEPPER_J() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_K + #if HAS_K_ENABLE + #define ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON) + #else + #define ENABLE_STEPPER_K() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_K + #if HAS_K_ENABLE + #define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON) + #else + #define DISABLE_STEPPER_K() NOOP + #endif +#endif + #ifndef ENABLE_STEPPER_E0 #if HAS_E0_ENABLE #define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON) @@ -857,10 +963,22 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); } #define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); } -#define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } -#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } -#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } -#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } + +#if HAS_Y_AXIS + #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } + #define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } +#else + #define ENABLE_AXIS_Y() NOOP + #define DISABLE_AXIS_Y() NOOP +#endif + +#if HAS_Z_AXIS + #define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } + #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } +#else + #define ENABLE_AXIS_Z() NOOP + #define DISABLE_AXIS_Z() NOOP +#endif #ifdef Z_IDLE_HEIGHT #define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0) @@ -868,6 +986,28 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z_RESET() #endif +#if LINEAR_AXES >= 4 + #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } + #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); } +#else + #define ENABLE_AXIS_I() NOOP + #define DISABLE_AXIS_I() NOOP +#endif +#if LINEAR_AXES >= 5 + #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } + #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); } +#else + #define ENABLE_AXIS_J() NOOP + #define DISABLE_AXIS_J() NOOP +#endif +#if LINEAR_AXES >= 6 + #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } + #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); } +#else + #define ENABLE_AXIS_K() NOOP + #define DISABLE_AXIS_K() NOOP +#endif + // // Extruder steppers enable / disable macros // diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index dab60e42a2..dbde6a5a04 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -36,7 +36,7 @@ #include enum StealthIndex : uint8_t { - LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z) + LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K) }; #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) @@ -97,6 +97,15 @@ enum StealthIndex : uint8_t { #if AXIS_HAS_SPI(Z4) TMC_SPI_DEFINE(Z4, Z); #endif +#if AXIS_HAS_SPI(I) + TMC_SPI_DEFINE(I, I); +#endif +#if AXIS_HAS_SPI(J) + TMC_SPI_DEFINE(J, J); +#endif +#if AXIS_HAS_SPI(K) + TMC_SPI_DEFINE(K, K); +#endif #if AXIS_HAS_SPI(E0) TMC_SPI_DEFINE_E(0); #endif @@ -329,6 +338,34 @@ enum StealthIndex : uint8_t { #define Z4_HAS_SW_SERIAL 1 #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, I, I); + #define I_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, I, I); + #define I_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, J, J); + #define J_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, J, J); + #define J_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, K, K); + #define K_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, K, K); + #define K_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 0); @@ -402,7 +439,9 @@ enum StealthIndex : uint8_t { #endif #endif - enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + #define _EN_ITEM(N) , E##N + enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; + #undef _EN_ITEM void tmc_serial_begin() { #if HAS_TMC_HW_SERIAL @@ -474,6 +513,27 @@ enum StealthIndex : uint8_t { stepperZ4.beginSerial(TMC_BAUD_RATE); #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + HW_SERIAL_BEGIN(I); + #else + stepperI.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + HW_SERIAL_BEGIN(J); + #else + stepperJ.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + HW_SERIAL_BEGIN(K); + #else + stepperK.beginSerial(TMC_BAUD_RATE); + #endif + #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL HW_SERIAL_BEGIN(E0); @@ -740,6 +800,15 @@ void restore_trinamic_drivers() { #if AXIS_IS_TMC(Z4) stepperZ4.push(); #endif + #if AXIS_IS_TMC(I) + stepperI.push(); + #endif + #if AXIS_IS_TMC(J) + stepperJ.push(); + #endif + #if AXIS_IS_TMC(K) + stepperK.push(); + #endif #if AXIS_IS_TMC(E0) stepperE0.push(); #endif @@ -771,7 +840,10 @@ void reset_trinamic_drivers() { ENABLED(STEALTHCHOP_E), ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_XY), - ENABLED(STEALTHCHOP_Z) + ENABLED(STEALTHCHOP_Z), + ENABLED(STEALTHCHOP_I), + ENABLED(STEALTHCHOP_J), + ENABLED(STEALTHCHOP_K) ); #if AXIS_IS_TMC(X) @@ -798,6 +870,15 @@ void reset_trinamic_drivers() { #if AXIS_IS_TMC(Z4) TMC_INIT(Z4, STEALTH_AXIS_Z); #endif + #if AXIS_IS_TMC(I) + TMC_INIT(I, STEALTH_AXIS_I); + #endif + #if AXIS_IS_TMC(J) + TMC_INIT(J, STEALTH_AXIS_J); + #endif + #if AXIS_IS_TMC(K) + TMC_INIT(K, STEALTH_AXIS_K); + #endif #if AXIS_IS_TMC(E0) TMC_INIT(E0, STEALTH_AXIS_E); #endif @@ -848,6 +929,24 @@ void reset_trinamic_drivers() { stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY)); #endif #endif + #if I_SENSORLESS + stepperI.homing_threshold(I_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(I) + stepperI.homing_threshold(CAT(TERN(I_SENSORLESS, I, I), _STALL_SENSITIVITY)); + #endif + #endif + #if J_SENSORLESS + stepperJ.homing_threshold(J_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(J) + stepperJ.homing_threshold(CAT(TERN(J_SENSORLESS, J, J), _STALL_SENSITIVITY)); + #endif + #endif + #if K_SENSORLESS + stepperK.homing_threshold(K_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(K) + stepperK.homing_threshold(CAT(TERN(K_SENSORLESS, K, K), _STALL_SENSITIVITY)); + #endif + #endif #endif // USE SENSORLESS #ifdef TMC_ADV diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 9f7445e4fd..766f8fced2 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -46,6 +46,10 @@ #define TMC_Y_LABEL 'Y', '0' #define TMC_Z_LABEL 'Z', '0' +#define TMC_I_LABEL 'I', '0' +#define TMC_J_LABEL 'J', '0' +#define TMC_K_LABEL 'K', '0' + #define TMC_X2_LABEL 'X', '2' #define TMC_Y2_LABEL 'Y', '2' #define TMC_Z2_LABEL 'Z', '2' @@ -79,13 +83,22 @@ typedef struct { #ifndef CHOPPER_TIMING_X #define CHOPPER_TIMING_X CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_Y +#if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y) #define CHOPPER_TIMING_Y CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_Z +#if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z) #define CHOPPER_TIMING_Z CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_E +#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I) + #define CHOPPER_TIMING_I CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J) + #define CHOPPER_TIMING_J CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K) + #define CHOPPER_TIMING_K CHOPPER_TIMING +#endif +#if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E) #define CHOPPER_TIMING_E CHOPPER_TIMING #endif @@ -225,6 +238,48 @@ void reset_trinamic_drivers(); #endif #endif +// I Stepper +#if AXIS_IS_TMC(I) + extern TMC_CLASS(I, I) stepperI; + static constexpr chopper_timing_t chopper_timing_I = CHOPPER_TIMING_I; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing.toff : 0) + #define I_ENABLE_READ() stepperI.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(I) + #define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0) + #endif +#endif + +// J Stepper +#if AXIS_IS_TMC(J) + extern TMC_CLASS(J, J) stepperJ; + static constexpr chopper_timing_t chopper_timing_J = CHOPPER_TIMING_J; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing.toff : 0) + #define J_ENABLE_READ() stepperJ.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(J) + #define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0) + #endif +#endif + +// K Stepper +#if AXIS_IS_TMC(K) + extern TMC_CLASS(K, K) stepperK; + static constexpr chopper_timing_t chopper_timing_K = CHOPPER_TIMING_K; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing.toff : 0) + #define K_ENABLE_READ() stepperK.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(K) + #define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0) + #endif +#endif + // E0 Stepper #if AXIS_IS_TMC(E0) extern TMC_CLASS_E(0) stepperE0; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 3abab802ab..5b478caa1a 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -49,7 +49,9 @@ bool toolchange_extruder_ready[EXTRUDERS]; #endif -#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) +#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) \ + || defined(EVENT_GCODE_TOOLCHANGE_T0) || defined(EVENT_GCODE_TOOLCHANGE_T1) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) \ + || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) #include "../gcode/gcode.h" #endif @@ -1311,10 +1313,22 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { TERN_(HAS_FANMUX, fanmux_switch(active_extruder)); - #ifdef EVENT_GCODE_AFTER_TOOLCHANGE - if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); - #endif + if (!no_move) { + #ifdef EVENT_GCODE_TOOLCHANGE_T0 + if (new_tool == 0) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0)); + #endif + + #ifdef EVENT_GCODE_TOOLCHANGE_T1 + if (new_tool == 1) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1)); + #endif + + #ifdef EVENT_GCODE_AFTER_TOOLCHANGE + if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); + #endif + } SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder); diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 8eee4f18fb..1ab7188b70 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -1319,6 +1319,105 @@ #if PIN_EXISTS(Z_MIN_PROBE) REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN) #endif +#if PIN_EXISTS(I_ATT) + REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN) +#endif +#if PIN_EXISTS(I_CS) + REPORT_NAME_DIGITAL(__LINE__, I_CS_PIN) +#endif +#if PIN_EXISTS(I_DIR) + REPORT_NAME_DIGITAL(__LINE__, I_DIR_PIN) +#endif +#if PIN_EXISTS(I_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, I_ENABLE_PIN) +#endif +#if PIN_EXISTS(I_MAX) + REPORT_NAME_DIGITAL(__LINE__, I_MAX_PIN) +#endif +#if PIN_EXISTS(I_MIN) + REPORT_NAME_DIGITAL(__LINE__, I_MIN_PIN) +#endif +#if PIN_EXISTS(I_MS1) + REPORT_NAME_DIGITAL(__LINE__, I_MS1_PIN) +#endif +#if PIN_EXISTS(I_MS2) + REPORT_NAME_DIGITAL(__LINE__, I_MS2_PIN) +#endif +#if PIN_EXISTS(I_MS3) + REPORT_NAME_DIGITAL(__LINE__, I_MS3_PIN) +#endif +#if PIN_EXISTS(I_STEP) + REPORT_NAME_DIGITAL(__LINE__, I_STEP_PIN) +#endif +#if PIN_EXISTS(I_STOP) + REPORT_NAME_DIGITAL(__LINE__, I_STOP_PIN) +#endif +#if PIN_EXISTS(J_ATT) + REPORT_NAME_DIGITAL(__LINE__, J_ATT_PIN) +#endif +#if PIN_EXISTS(J_CS) + REPORT_NAME_DIGITAL(__LINE__, J_CS_PIN) +#endif +#if PIN_EXISTS(J_DIR) + REPORT_NAME_DIGITAL(__LINE__, J_DIR_PIN) +#endif +#if PIN_EXISTS(J_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, J_ENABLE_PIN) +#endif +#if PIN_EXISTS(J_MAX) + REPORT_NAME_DIGITAL(__LINE__, J_MAX_PIN) +#endif +#if PIN_EXISTS(J_MIN) + REPORT_NAME_DIGITAL(__LINE__, J_MIN_PIN) +#endif +#if PIN_EXISTS(J_MS1) + REPORT_NAME_DIGITAL(__LINE__, J_MS1_PIN) +#endif +#if PIN_EXISTS(J_MS2) + REPORT_NAME_DIGITAL(__LINE__, J_MS2_PIN) +#endif +#if PIN_EXISTS(J_MS3) + REPORT_NAME_DIGITAL(__LINE__, J_MS3_PIN) +#endif +#if PIN_EXISTS(J_STEP) + REPORT_NAME_DIGITAL(__LINE__, J_STEP_PIN) +#endif +#if PIN_EXISTS(J_STOP) + REPORT_NAME_DIGITAL(__LINE__, J_STOP_PIN) +#endif +#if PIN_EXISTS(K_ATT) + REPORT_NAME_DIGITAL(__LINE__, K_ATT_PIN) +#endif +#if PIN_EXISTS(K_CS) + REPORT_NAME_DIGITAL(__LINE__, K_CS_PIN) +#endif +#if PIN_EXISTS(K_DIR) + REPORT_NAME_DIGITAL(__LINE__, K_DIR_PIN) +#endif +#if PIN_EXISTS(K_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, K_ENABLE_PIN) +#endif +#if PIN_EXISTS(K_MAX) + REPORT_NAME_DIGITAL(__LINE__, K_MAX_PIN) +#endif +#if PIN_EXISTS(K_MIN) + REPORT_NAME_DIGITAL(__LINE__, K_MIN_PIN) +#endif +#if PIN_EXISTS(K_MS1) + REPORT_NAME_DIGITAL(__LINE__, K_MS1_PIN) +#endif +#if PIN_EXISTS(K_MS2) + REPORT_NAME_DIGITAL(__LINE__, K_MS2_PIN) +#endif +#if PIN_EXISTS(K_MS3) + REPORT_NAME_DIGITAL(__LINE__, K_MS3_PIN) +#endif +#if PIN_EXISTS(K_STEP) + REPORT_NAME_DIGITAL(__LINE__, K_STEP_PIN) +#endif +#if PIN_EXISTS(K_STOP) + REPORT_NAME_DIGITAL(__LINE__, K_STOP_PIN) +#endif #if PIN_EXISTS(ZRIB_V20_D6) REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN) #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 8cc19678f1..31031c9589 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -402,40 +402,89 @@ #define X_STOP_PIN X_MAX_PIN #endif -#ifdef Y_STOP_PIN - #if Y_HOME_TO_MIN - #define Y_MIN_PIN Y_STOP_PIN - #ifndef Y_MAX_PIN - #define Y_MAX_PIN -1 +#if HAS_Y_AXIS + #ifdef Y_STOP_PIN + #if Y_HOME_TO_MIN + #define Y_MIN_PIN Y_STOP_PIN + #ifndef Y_MAX_PIN + #define Y_MAX_PIN -1 + #endif + #else + #define Y_MAX_PIN Y_STOP_PIN + #ifndef Y_MIN_PIN + #define Y_MIN_PIN -1 + #endif #endif + #elif Y_HOME_TO_MIN + #define Y_STOP_PIN Y_MIN_PIN #else - #define Y_MAX_PIN Y_STOP_PIN - #ifndef Y_MIN_PIN - #define Y_MIN_PIN -1 - #endif + #define Y_STOP_PIN Y_MAX_PIN #endif -#elif Y_HOME_TO_MIN - #define Y_STOP_PIN Y_MIN_PIN -#else - #define Y_STOP_PIN Y_MAX_PIN #endif -#ifdef Z_STOP_PIN - #if Z_HOME_TO_MIN - #define Z_MIN_PIN Z_STOP_PIN - #ifndef Z_MAX_PIN - #define Z_MAX_PIN -1 +#if HAS_Z_AXIS + #ifdef Z_STOP_PIN + #if Z_HOME_TO_MIN + #define Z_MIN_PIN Z_STOP_PIN + #ifndef Z_MAX_PIN + #define Z_MAX_PIN -1 + #endif + #else + #define Z_MAX_PIN Z_STOP_PIN + #ifndef Z_MIN_PIN + #define Z_MIN_PIN -1 + #endif #endif + #elif Z_HOME_TO_MIN + #define Z_STOP_PIN Z_MIN_PIN #else - #define Z_MAX_PIN Z_STOP_PIN - #ifndef Z_MIN_PIN - #define Z_MIN_PIN -1 + #define Z_STOP_PIN Z_MAX_PIN + #endif +#endif + +#if LINEAR_AXES >= 4 + #ifdef I_STOP_PIN + #if I_HOME_TO_MIN + #define I_MIN_PIN I_STOP_PIN + #define I_MAX_PIN -1 + #else + #define I_MIN_PIN -1 + #define I_MAX_PIN I_STOP_PIN #endif #endif -#elif Z_HOME_TO_MIN - #define Z_STOP_PIN Z_MIN_PIN #else - #define Z_STOP_PIN Z_MAX_PIN + #undef I_MIN_PIN + #undef I_MAX_PIN +#endif + +#if LINEAR_AXES >= 5 + #ifdef J_STOP_PIN + #if J_HOME_TO_MIN + #define J_MIN_PIN J_STOP_PIN + #define J_MAX_PIN -1 + #else + #define J_MIN_PIN -1 + #define J_MAX_PIN J_STOP_PIN + #endif + #endif +#else + #undef J_MIN_PIN + #undef J_MAX_PIN +#endif + +#if LINEAR_AXES >= 6 + #ifdef K_STOP_PIN + #if K_HOME_TO_MIN + #define K_MIN_PIN K_STOP_PIN + #define K_MAX_PIN -1 + #else + #define K_MIN_PIN -1 + #define K_MAX_PIN K_STOP_PIN + #endif + #endif +#else + #undef K_MIN_PIN + #undef K_MAX_PIN #endif // Filament Sensor first pin alias @@ -863,6 +912,19 @@ #undef Z_MAX_PIN #define Z_MAX_PIN -1 #endif +#if DISABLED(USE_IMAX_PLUG) + #undef I_MAX_PIN + #define I_MAX_PIN -1 +#endif +#if DISABLED(USE_JMAX_PLUG) + #undef J_MAX_PIN + #define J_MAX_PIN -1 +#endif +#if DISABLED(USE_KMAX_PLUG) + #undef K_MAX_PIN + #define K_MAX_PIN -1 +#endif + #if DISABLED(USE_XMIN_PLUG) #undef X_MIN_PIN #define X_MIN_PIN -1 @@ -906,6 +968,19 @@ #undef Z4_MAX_PIN #endif +#if DISABLED(USE_IMIN_PLUG) + #undef I_MIN_PIN + #define I_MIN_PIN -1 +#endif +#if DISABLED(USE_JMIN_PLUG) + #undef J_MIN_PIN + #define J_MIN_PIN -1 +#endif +#if DISABLED(USE_KMIN_PLUG) + #undef K_MIN_PIN + #define K_MIN_PIN -1 +#endif + // // Default DOGLCD SPI delays // diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 21ba87e8f6..de0f65c596 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -63,81 +63,220 @@ #define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS -#if PIN_EXISTS(Y_MIN) - #define _Y_MIN Y_MIN_PIN, +#if HAS_Y_AXIS + + #if PIN_EXISTS(Y_MIN) + #define _Y_MIN Y_MIN_PIN, + #else + #define _Y_MIN + #endif + #if PIN_EXISTS(Y_MAX) + #define _Y_MAX Y_MAX_PIN, + #else + #define _Y_MAX + #endif + #if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) + #define _Y_CS Y_CS_PIN, + #else + #define _Y_CS + #endif + #if PIN_EXISTS(Y_MS1) + #define _Y_MS1 Y_MS1_PIN, + #else + #define _Y_MS1 + #endif + #if PIN_EXISTS(Y_MS2) + #define _Y_MS2 Y_MS2_PIN, + #else + #define _Y_MS2 + #endif + #if PIN_EXISTS(Y_MS3) + #define _Y_MS3 Y_MS3_PIN, + #else + #define _Y_MS3 + #endif + #if PIN_EXISTS(Y_ENABLE) + #define _Y_ENABLE_PIN Y_ENABLE_PIN, + #else + #define _Y_ENABLE_PIN + #endif + + #define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS + #else - #define _Y_MIN -#endif -#if PIN_EXISTS(Y_MAX) - #define _Y_MAX Y_MAX_PIN, -#else - #define _Y_MAX -#endif -#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) - #define _Y_CS Y_CS_PIN, -#else - #define _Y_CS -#endif -#if PIN_EXISTS(Y_MS1) - #define _Y_MS1 Y_MS1_PIN, -#else - #define _Y_MS1 -#endif -#if PIN_EXISTS(Y_MS2) - #define _Y_MS2 Y_MS2_PIN, -#else - #define _Y_MS2 -#endif -#if PIN_EXISTS(Y_MS3) - #define _Y_MS3 Y_MS3_PIN, -#else - #define _Y_MS3 -#endif -#if PIN_EXISTS(Y_ENABLE) - #define _Y_ENABLE_PIN Y_ENABLE_PIN, -#else - #define _Y_ENABLE_PIN + + #define _Y_PINS + #endif -#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS +#if HAS_Z_AXIS + + #if PIN_EXISTS(Z_MIN) + #define _Z_MIN Z_MIN_PIN, + #else + #define _Z_MIN + #endif + #if PIN_EXISTS(Z_MAX) + #define _Z_MAX Z_MAX_PIN, + #else + #define _Z_MAX + #endif + #if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) + #define _Z_CS Z_CS_PIN, + #else + #define _Z_CS + #endif + #if PIN_EXISTS(Z_MS1) + #define _Z_MS1 Z_MS1_PIN, + #else + #define _Z_MS1 + #endif + #if PIN_EXISTS(Z_MS2) + #define _Z_MS2 Z_MS2_PIN, + #else + #define _Z_MS2 + #endif + #if PIN_EXISTS(Z_MS3) + #define _Z_MS3 Z_MS3_PIN, + #else + #define _Z_MS3 + #endif + #if PIN_EXISTS(Z_ENABLE) + #define _Z_ENABLE_PIN Z_ENABLE_PIN, + #else + #define _Z_ENABLE_PIN + #endif + + #define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS -#if PIN_EXISTS(Z_MIN) - #define _Z_MIN Z_MIN_PIN, #else - #define _Z_MIN -#endif -#if PIN_EXISTS(Z_MAX) - #define _Z_MAX Z_MAX_PIN, -#else - #define _Z_MAX -#endif -#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) - #define _Z_CS Z_CS_PIN, -#else - #define _Z_CS -#endif -#if PIN_EXISTS(Z_MS1) - #define _Z_MS1 Z_MS1_PIN, -#else - #define _Z_MS1 -#endif -#if PIN_EXISTS(Z_MS2) - #define _Z_MS2 Z_MS2_PIN, -#else - #define _Z_MS2 -#endif -#if PIN_EXISTS(Z_MS3) - #define _Z_MS3 Z_MS3_PIN, -#else - #define _Z_MS3 -#endif -#if PIN_EXISTS(Z_ENABLE) - #define _Z_ENABLE_PIN Z_ENABLE_PIN, -#else - #define _Z_ENABLE_PIN + + #define _Z_PINS + #endif -#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS +#if LINEAR_AXES >= 4 + + #if PIN_EXISTS(I_MIN) + #define _I_MIN I_MIN_PIN, + #else + #define _I_MIN + #endif + #if PIN_EXISTS(I_MAX) + #define _I_MAX I_MAX_PIN, + #else + #define _I_MAX + #endif + #if PIN_EXISTS(I_CS) + #define _I_CS I_CS_PIN, + #else + #define _I_CS + #endif + #if PIN_EXISTS(I_MS1) + #define _I_MS1 I_MS1_PIN, + #else + #define _I_MS1 + #endif + #if PIN_EXISTS(I_MS2) + #define _I_MS2 I_MS2_PIN, + #else + #define _I_MS2 + #endif + #if PIN_EXISTS(I_MS3) + #define _I_MS3 I_MS3_PIN, + #else + #define _I_MS3 + #endif + + #define _I_PINS I_STEP_PIN, I_DIR_PIN, I_ENABLE_PIN, _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS + +#else + + #define _I_PINS + +#endif + +#if LINEAR_AXES >= 5 + + #if PIN_EXISTS(J_MIN) + #define _J_MIN J_MIN_PIN, + #else + #define _J_MIN + #endif + #if PIN_EXISTS(J_MAX) + #define _J_MAX J_MAX_PIN, + #else + #define _J_MAX + #endif + #if PIN_EXISTS(J_CS) + #define _J_CS J_CS_PIN, + #else + #define _J_CS + #endif + #if PIN_EXISTS(J_MS1) + #define _J_MS1 J_MS1_PIN, + #else + #define _J_MS1 + #endif + #if PIN_EXISTS(J_MS2) + #define _J_MS2 J_MS2_PIN, + #else + #define _J_MS2 + #endif + #if PIN_EXISTS(J_MS3) + #define _J_MS3 J_MS3_PIN, + #else + #define _J_MS3 + #endif + + #define _J_PINS J_STEP_PIN, J_DIR_PIN, J_ENABLE_PIN, _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS + +#else + + #define _J_PINS + +#endif + +#if LINEAR_AXES >= 6 + + #if PIN_EXISTS(K_MIN) + #define _K_MIN K_MIN_PIN, + #else + #define _K_MIN + #endif + #if PIN_EXISTS(K_MAX) + #define _K_MAX K_MAX_PIN, + #else + #define _K_MAX + #endif + #if PIN_EXISTS(K_CS) + #define _K_CS K_CS_PIN, + #else + #define _K_CS + #endif + #if PIN_EXISTS(K_MS1) + #define _K_MS1 K_MS1_PIN, + #else + #define _K_MS1 + #endif + #if PIN_EXISTS(K_MS2) + #define _K_MS2 K_MS2_PIN, + #else + #define _K_MS2 + #endif + #if PIN_EXISTS(K_MS3) + #define _K_MS3 K_MS3_PIN, + #else + #define _K_MS3 + #endif + + #define _K_PINS K_STEP_PIN, K_DIR_PIN, K_ENABLE_PIN, _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS + +#else + + #define _K_PINS + +#endif // // Extruder Chip Select, Digital Micro-steps @@ -714,7 +853,8 @@ #endif #define SENSITIVE_PINS { \ - _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ + _X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \ + _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \ _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \ _PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \ diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 3890b08147..dc3df482b5 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -59,6 +59,7 @@ // extern +PGMSTR(M21_STR, "M21"); PGMSTR(M23_STR, "M23 %s"); PGMSTR(M24_STR, "M24"); From daab75b7eab9003e14547de9a07201da8b60869e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 5 Jun 2021 17:08:10 -0500 Subject: [PATCH 0216/2168] =?UTF-8?q?=F0=9F=94=A7=20FOAMCUTTER=5FXYUV=20mo?= =?UTF-8?q?ved=20to=20custom=20config?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 8 -------- 1 file changed, 8 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 27307eb3be..cb7740a294 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -66,14 +66,6 @@ // //=========================================================================== -//=========================================================================== -//=========================== FOAMCUTTER_XYUV ============================== -//=========================================================================== -// For a hot wire cutter with parallel horizontal axes X, I where the hights -// of the two wire ends are controlled by parallel axes Y, J. -// -//#define FOAMCUTTER_XYUV - // @section info // Author info of this build printed to the host during boot and M115 From 493e6c2cbaaa85c5f7d8b5fa176a19713b56c70d Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 6 Jun 2021 12:16:40 +1200 Subject: [PATCH 0217/2168] =?UTF-8?q?=F0=9F=94=A7=20Check=20G29=5FRETRY=5F?= =?UTF-8?q?AND=5FRECOVER=20requirements=20(#21921)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ee6fae0976..fe802ccf16 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1631,12 +1631,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif -#if ENABLED(G29_RETRY_AND_RECOVER) - #if ENABLED(AUTO_BED_LEVELING_UBL) - #error "G29_RETRY_AND_RECOVER is not compatible with UBL." - #elif ENABLED(MESH_BED_LEVELING) - #error "G29_RETRY_AND_RECOVER is not compatible with MESH_BED_LEVELING." - #endif +#if ENABLED(G29_RETRY_AND_RECOVER) && NONE(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) + #error "G29_RETRY_AND_RECOVER requires AUTO_BED_LEVELING_3POINT, LINEAR, or BILINEAR." #endif /** From b4114553c81dea6a863fdd994946cd40f7c10d85 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 6 Jun 2021 01:27:16 +0000 Subject: [PATCH 0218/2168] [cron] Bump distribution date (2021-06-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 722c63e117..9415a53c19 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 "2021-06-05" + #define STRING_DISTRIBUTION_DATE "2021-06-06" #endif /** From ce5dece3b57ad2fe36347530a6de79a3848736f4 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 6 Jun 2021 02:59:19 -0300 Subject: [PATCH 0219/2168] =?UTF-8?q?=E2=9A=B0=EF=B8=8F=20Remove=20obsolet?= =?UTF-8?q?e=20CUSTOM=5FSPI=5FPINS=20(#22058)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL_SPI.cpp | 8 ++-- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 3 ++ .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 13 ++--- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 1 - .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 11 ++--- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 2 - .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 1 - .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 1 - .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 34 ++++++-------- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 47 ++++++++----------- 10 files changed, 49 insertions(+), 72 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 80347e115d..bd36562de9 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -163,11 +163,9 @@ static SPISettings spiConfig; } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - #if ENABLED(CUSTOM_SPI_PINS) - SPI.setMISO(SD_MISO_PIN); - SPI.setMOSI(SD_MOSI_PIN); - SPI.setSCLK(SD_SCK_PIN); - #endif + SPI.setMISO(SD_MISO_PIN); + SPI.setMOSI(SD_MOSI_PIN); + SPI.setSCLK(SD_SCK_PIN); SPI.begin(); } diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 35224ebdd0..27aa84e44f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -276,6 +276,9 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 #elif SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN PA15 #define SD_SS_PIN PA10 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index bb356485cb..5850f11ef0 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -280,11 +280,8 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card -#define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI for SD on STM32 (for now) -#if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS ONBOARD_SD_CS_PIN - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 -#endif +#define ENABLE_SPI1 +#define SDSS ONBOARD_SD_CS_PIN +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 6369fcd31b..b482065666 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -186,7 +186,6 @@ // TODO: This is the only way to set SPI for SD on STM32 (for now) #define ENABLE_SPI2 -#define CUSTOM_SPI_PINS #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 9fb13c84fe..408048bfe2 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -205,13 +205,10 @@ #define EXP2_10_PIN PA6 // HAL SPI1 pins -#define CUSTOM_SPI_PINS -#if ENABLED(CUSTOM_SPI_PINS) - #define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK - #define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL - #define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO - #define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI -#endif +#define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK +#define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL +#define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO +#define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI #define SDSS EXP2_07_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 8f19b1915d..850b23db66 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -357,8 +357,6 @@ #elif SD_CONNECTION_IS(ONBOARD) - // Instruct the STM32 HAL to override the default SPI pins from the variant.h file - #define CUSTOM_SPI_PINS #define SDSS PA4 #define SD_SS_PIN SDSS #define SD_SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index cce21fbe8f..2cf1ee1447 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -356,7 +356,6 @@ #define SD_DETECT_PIN PC14 #elif SD_CONNECTION_IS(LCD) - #define CUSTOM_SPI_PINS #define SDSS PA4 #define SD_SS_PIN SDSS #define SD_SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index c46e0f03f0..d465bb23c7 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -348,7 +348,6 @@ #elif SD_CONNECTION_IS(LCD) - #define CUSTOM_SPI_PINS #define SDSS PA4 #define SD_SS_PIN SDSS #define SD_SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 726e9a6586..1146582a5b 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -217,37 +217,31 @@ // // detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) - #define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI3 for SD on STM32 (by now) - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI3 - #define SD_SS_PIN -1 - #define SDSS PC9 - #define SD_SCK_PIN PC10 - #define SD_MISO_PIN PC11 - #define SD_MOSI_PIN PC12 - #define SD_DETECT_PIN PD12 - #endif + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PD12 #endif // // LCD SD // #if SD_CONNECTION_IS(LCD) - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 - #endif + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 #endif // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 1000326dad..2b0df002d3 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -31,7 +31,7 @@ #define BOARD_INFO_NAME "MKS Robin PRO V2" // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation @@ -50,7 +50,7 @@ // // Note: MKS Robin board is using SPI2 interface. // -//#define SPI_MODULE 2 +//#define SPI_MODULE 2 // // Servos @@ -203,7 +203,7 @@ //#define LED_PIN PB2 #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif //#define USE_NEW_SPI_API 1 @@ -214,21 +214,17 @@ // // detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled #if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - - #if USE_NEW_SPI_API - #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) - #else - #define ENABLE_SPI3 - #define SD_SS_PIN -1 - #define SDSS PC9 - #define SD_SCK_PIN PC10 - #define SD_MISO_PIN PC11 - #define SD_MOSI_PIN PC12 - #endif - #define SD_DETECT_PIN PD12 + #if USE_NEW_SPI_API + #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) + #else + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 #endif + #define SD_DETECT_PIN PD12 #endif /* @@ -236,22 +232,19 @@ // LCD SD // #if SDCARD_CONNECTION == LCD - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 - #endif + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 #endif */ // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) From ba4fa4983411d03eae791b70d8ec3e26f0781785 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Sun, 6 Jun 2021 08:30:39 +0200 Subject: [PATCH 0220/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Followup=20to=20?= =?UTF-8?q?Six=20Linear=20Axes=20(#22056)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 4 +- Marlin/src/core/macros.h | 12 ++-- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/module/endstops.h | 2 +- Marlin/src/module/motion.cpp | 79 +++++++++++++++++++------- Marlin/src/module/motion.h | 2 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/stepper/trinamic.cpp | 30 +++++----- Marlin/src/pins/pins_postprocess.h | 67 ++++++++++++++-------- Marlin/src/pins/sensitive_pins.h | 6 +- 10 files changed, 132 insertions(+), 80 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e0c54dfbec..efde7cde19 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -734,7 +734,7 @@ * the position of the toolhead relative to the workspace. */ -//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing +//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (mm) Backoff from endstops before sensorless homing #define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) @@ -2253,7 +2253,7 @@ * Extra G-code to run while executing tool-change commands. Can be used to use an additional * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer. */ - //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 I0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 /** diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index dc6147adb0..295eee9bcf 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -36,15 +36,15 @@ #define _XMIN_ 100 #define _YMIN_ 200 #define _ZMIN_ 300 -#define _IMIN_ 400 -#define _JMIN_ 500 -#define _KMIN_ 600 +#define _IMIN_ 500 +#define _JMIN_ 600 +#define _KMIN_ 700 #define _XMAX_ 101 #define _YMAX_ 201 #define _ZMAX_ 301 -#define _IMAX_ 401 -#define _JMAX_ 501 -#define _KMAX_ 601 +#define _IMAX_ 501 +#define _JMAX_ 601 +#define _KMAX_ 701 #define _XDIAG_ 102 #define _YDIAG_ 202 #define _ZDIAG_ 302 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fe802ccf16..d5f763ce9d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -570,8 +570,8 @@ #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." #endif -constexpr float sbm[] = AXIS_RELATIVE_MODES; -static_assert(COUNT(sbm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements."); +constexpr float arm[] = AXIS_RELATIVE_MODES; +static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements."); /** * Probe temp compensation requirements diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 01f33099e9..d983d69871 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -223,7 +223,7 @@ class Endstops { typedef struct { union { bool any; - struct { bool x:1, y:1, z:1; }; + struct { bool LINEAR_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1); }; }; } tmc_spi_homing_t; static tmc_spi_homing_t tmc_spi_homing; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 1d40d3a253..d465a00356 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -588,27 +588,27 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } #endif -#if LINEAR_AXES == 4 +#if LINEAR_AXES >= 4 void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); } void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, i, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k), + fr_mm_s + ); } #endif #if LINEAR_AXES >= 5 - void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); - } - void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, i, raw.j, fr_mm_s); - } void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s); } void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, j, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k), + fr_mm_s + ); } #endif @@ -617,7 +617,10 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s); } void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, raw.j, k, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k), + fr_mm_s + ); } #endif @@ -822,7 +825,7 @@ void restore_feedrate_and_scaling() { #endif } #endif - #if LINEAR_AXES >= 4 // TODO (DerAndere): Find out why this was missing / removed + #if LINEAR_AXES >= 4 if (axis_was_homed(I_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I) NOLESS(target.i, soft_endstop.min.i); @@ -1295,7 +1298,7 @@ void prepare_line_to_destination() { bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { if ((axis_bits = axes_should_home(axis_bits))) { - PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); // TODO: (DerAndere) Set this up for extra axes + PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[strlen_P(home_first)+1]; sprintf_P(msg, home_first, LINEAR_AXIS_LIST( @@ -1390,8 +1393,21 @@ void prepare_line_to_destination() { #if ENABLED(SPI_ENDSTOPS) switch (axis) { 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; + #if HAS_Y_AXIS + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = true; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = true; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break; + #endif default: break; } #endif @@ -1454,11 +1470,21 @@ void prepare_line_to_destination() { #if ENABLED(SPI_ENDSTOPS) switch (axis) { 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; - case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; - case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; - case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; + #if HAS_Y_AXIS + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; + #endif default: break; } #endif @@ -1734,11 +1760,11 @@ void prepare_line_to_destination() { #endif // - // Back away to prevent an early X/Y sensorless trigger + // Back away to prevent an early sensorless trigger // #if DISABLED(DELTA) && defined(SENSORLESS_BACKOFF_MM) - const xy_float_t backoff = SENSORLESS_BACKOFF_MM; - if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS)) && backoff[axis]) { + const xyz_float_t backoff = SENSORLESS_BACKOFF_MM; + if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS) || TERN0(Z_SENSORLESS, axis == Z_AXIS) || TERN0(I_SENSORLESS, axis == I_AXIS) || TERN0(J_SENSORLESS, axis == J_AXIS) || TERN0(K_SENSORLESS, axis == K_AXIS)) && backoff[axis]) { const float backoff_length = -ABS(backoff[axis]) * axis_home_dir; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Sensorless backoff: ", backoff_length, "mm"); do_homing_move(axis, backoff_length, homing_feedrate(axis)); @@ -1777,6 +1803,15 @@ void prepare_line_to_destination() { case X_AXIS: es = X_ENDSTOP; break; case Y_AXIS: es = Y_ENDSTOP; break; case Z_AXIS: es = Z_ENDSTOP; break; + #if LINEAR_AXES >= 4 + case I_AXIS: es = I_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: es = J_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: es = K_ENDSTOP; break; + #endif } if (TEST(endstops.state(), es)) { SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 9095290cc7..d099246f17 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -180,7 +180,7 @@ inline float home_bump_mm(const AxisEnum axis) { TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); break; #endif - #if LINEAR_AXES >= 4 // TODO (DerAndere): Test for LINEAR_AXES >= 4 + #if LINEAR_AXES >= 4 case I_AXIS: TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i); TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index eb0d204cb0..49b2d60b20 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1451,7 +1451,7 @@ void Planner::check_axes_activity() { float high = 0.0; for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; - if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, block->steps.i, || block->steps.j, || block->steps.k)) { + if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k)) { const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; NOLESS(high, se); } @@ -2852,7 +2852,7 @@ bool Planner::buffer_segment(const abce_pos_t &abce int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])), int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])), int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])), - int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), // FIXME (DerAndere): Multiplication by 4.0 is a work-around for issue with wrong internal steps per mm + int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])), int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])) ) @@ -2893,7 +2893,7 @@ bool Planner::buffer_segment(const abce_pos_t &abce #endif #if LINEAR_AXES >= 4 SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i); - SERIAL_ECHOPAIR(" (", position.i, "->", target.i); // FIXME (DerAndere): Introduce work-around for issue with wrong internal steps per mm and feedrate for I_AXIS + SERIAL_ECHOPAIR(" (", position.i, "->", target.i); SERIAL_CHAR(')'); #endif #if LINEAR_AXES >= 5 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index dbde6a5a04..a5d7e5ad6b 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -766,11 +766,7 @@ enum StealthIndex : uint8_t { pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } #endif // TMC5160 @@ -971,11 +967,12 @@ void reset_trinamic_drivers() { // Using a fixed-length character array for the port name allows this to be constexpr compatible. struct SanityHwSerialDetails { const char port[20]; uint32_t address; }; #define TMC_HW_DETAIL_ARGS(A) TERN(A##_HAS_HW_SERIAL, STRINGIFY(A##_HARDWARE_SERIAL), ""), TERN0(A##_HAS_HW_SERIAL, A##_SLAVE_ADDRESS) - #define TMC_HW_DETAIL(A) {TMC_HW_DETAIL_ARGS(A)} + #define TMC_HW_DETAIL(A) { TMC_HW_DETAIL_ARGS(A) } constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = { TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2), TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2), TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4), + TMC_HW_DETAIL(I), TMC_HW_DETAIL(J), TMC_HW_DETAIL(K), TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7) }; @@ -995,10 +992,11 @@ void reset_trinamic_drivers() { #define TMC_HWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_HARDWARE_SERIAL" #define SA_NO_TMC_HW_C(A) static_assert(1 >= count_tmc_hw_serial_matches(TMC_HW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_hw_details)), TMC_HWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_HW_C(X);SA_NO_TMC_HW_C(X2); - SA_NO_TMC_HW_C(Y);SA_NO_TMC_HW_C(Y2); - SA_NO_TMC_HW_C(Z);SA_NO_TMC_HW_C(Z2);SA_NO_TMC_HW_C(Z3);SA_NO_TMC_HW_C(Z4); - SA_NO_TMC_HW_C(E0);SA_NO_TMC_HW_C(E1);SA_NO_TMC_HW_C(E2);SA_NO_TMC_HW_C(E3);SA_NO_TMC_HW_C(E4);SA_NO_TMC_HW_C(E5);SA_NO_TMC_HW_C(E6);SA_NO_TMC_HW_C(E7); + SA_NO_TMC_HW_C(X); SA_NO_TMC_HW_C(X2); + SA_NO_TMC_HW_C(Y); SA_NO_TMC_HW_C(Y2); + SA_NO_TMC_HW_C(Z); SA_NO_TMC_HW_C(Z2); SA_NO_TMC_HW_C(Z3); SA_NO_TMC_HW_C(Z4); + SA_NO_TMC_HW_C(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K); + SA_NO_TMC_HW_C(E0); SA_NO_TMC_HW_C(E1); SA_NO_TMC_HW_C(E2); SA_NO_TMC_HW_C(E3); SA_NO_TMC_HW_C(E4); SA_NO_TMC_HW_C(E5); SA_NO_TMC_HW_C(E6); SA_NO_TMC_HW_C(E7); #endif #if ANY_AXIS_HAS(SW_SERIAL) @@ -1009,7 +1007,8 @@ void reset_trinamic_drivers() { TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2), TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2), TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4), - TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) + TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K), + TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) }; constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; } @@ -1023,10 +1022,11 @@ void reset_trinamic_drivers() { #define TMC_SWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_SERIAL_RX_PIN or " STRINGIFY(A) "_SERIAL_TX_PIN" #define SA_NO_TMC_SW_C(A) static_assert(1 >= count_tmc_sw_serial_matches(TMC_SW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_sw_details)), TMC_SWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_SW_C(X);SA_NO_TMC_SW_C(X2); - SA_NO_TMC_SW_C(Y);SA_NO_TMC_SW_C(Y2); - SA_NO_TMC_SW_C(Z);SA_NO_TMC_SW_C(Z2);SA_NO_TMC_SW_C(Z3);SA_NO_TMC_SW_C(Z4); - SA_NO_TMC_SW_C(E0);SA_NO_TMC_SW_C(E1);SA_NO_TMC_SW_C(E2);SA_NO_TMC_SW_C(E3);SA_NO_TMC_SW_C(E4);SA_NO_TMC_SW_C(E5);SA_NO_TMC_SW_C(E6);SA_NO_TMC_SW_C(E7); + SA_NO_TMC_SW_C(X); SA_NO_TMC_SW_C(X2); + SA_NO_TMC_SW_C(Y); SA_NO_TMC_SW_C(Y2); + SA_NO_TMC_SW_C(Z); SA_NO_TMC_SW_C(Z2); SA_NO_TMC_SW_C(Z3); SA_NO_TMC_SW_C(Z4); + SA_NO_TMC_SW_C(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K); + SA_NO_TMC_SW_C(E0); SA_NO_TMC_SW_C(E1); SA_NO_TMC_SW_C(E2); SA_NO_TMC_SW_C(E3); SA_NO_TMC_SW_C(E4); SA_NO_TMC_SW_C(E5); SA_NO_TMC_SW_C(E6); SA_NO_TMC_SW_C(E7); #endif #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 31031c9589..33b78a4d11 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -212,6 +212,15 @@ #if !AXIS_HAS_SPI(Z) #undef Z_CS_PIN #endif +#if !AXIS_HAS_SPI(I) + #undef I_CS_PIN +#endif +#if !AXIS_HAS_SPI(J) + #undef J_CS_PIN +#endif +#if !AXIS_HAS_SPI(K) + #undef K_CS_PIN +#endif #if E_STEPPERS && !AXIS_HAS_SPI(E0) #undef E0_CS_PIN #endif @@ -246,6 +255,15 @@ #ifndef Z_CS_PIN #define Z_CS_PIN -1 #endif +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif #ifndef E0_CS_PIN #define E0_CS_PIN -1 #endif @@ -900,43 +918,55 @@ #undef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN -1 #endif +#if DISABLED(USE_XMIN_PLUG) + #undef X_MIN_PIN + #define X_MIN_PIN -1 +#endif #if DISABLED(USE_XMAX_PLUG) #undef X_MAX_PIN #define X_MAX_PIN -1 #endif +#if DISABLED(USE_YMIN_PLUG) + #undef Y_MIN_PIN + #define Y_MIN_PIN -1 +#endif #if DISABLED(USE_YMAX_PLUG) #undef Y_MAX_PIN #define Y_MAX_PIN -1 #endif +#if DISABLED(USE_ZMIN_PLUG) + #undef Z_MIN_PIN + #define Z_MIN_PIN -1 +#endif #if DISABLED(USE_ZMAX_PLUG) #undef Z_MAX_PIN #define Z_MAX_PIN -1 #endif +#if DISABLED(USE_IMIN_PLUG) + #undef I_MIN_PIN + #define I_MIN_PIN -1 +#endif #if DISABLED(USE_IMAX_PLUG) #undef I_MAX_PIN #define I_MAX_PIN -1 #endif +#if DISABLED(USE_JMIN_PLUG) + #undef J_MIN_PIN + #define J_MIN_PIN -1 +#endif #if DISABLED(USE_JMAX_PLUG) #undef J_MAX_PIN #define J_MAX_PIN -1 #endif +#if DISABLED(USE_KMIN_PLUG) + #undef K_MIN_PIN + #define K_MIN_PIN -1 +#endif #if DISABLED(USE_KMAX_PLUG) #undef K_MAX_PIN #define K_MAX_PIN -1 #endif -#if DISABLED(USE_XMIN_PLUG) - #undef X_MIN_PIN - #define X_MIN_PIN -1 -#endif -#if DISABLED(USE_YMIN_PLUG) - #undef Y_MIN_PIN - #define Y_MIN_PIN -1 -#endif -#if DISABLED(USE_ZMIN_PLUG) - #undef Z_MIN_PIN - #define Z_MIN_PIN -1 -#endif #if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX #undef X2_MIN_PIN #endif @@ -968,19 +998,6 @@ #undef Z4_MAX_PIN #endif -#if DISABLED(USE_IMIN_PLUG) - #undef I_MIN_PIN - #define I_MIN_PIN -1 -#endif -#if DISABLED(USE_JMIN_PLUG) - #undef J_MIN_PIN - #define J_MIN_PIN -1 -#endif -#if DISABLED(USE_KMIN_PLUG) - #undef K_MIN_PIN - #define K_MIN_PIN -1 -#endif - // // Default DOGLCD SPI delays // diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index de0f65c596..e304901940 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -167,7 +167,7 @@ #else #define _I_MAX #endif - #if PIN_EXISTS(I_CS) + #if PIN_EXISTS(I_CS) && AXIS_HAS_SPI(I) #define _I_CS I_CS_PIN, #else #define _I_CS @@ -208,7 +208,7 @@ #else #define _J_MAX #endif - #if PIN_EXISTS(J_CS) + #if PIN_EXISTS(J_CS) && AXIS_HAS_SPI(J) #define _J_CS J_CS_PIN, #else #define _J_CS @@ -249,7 +249,7 @@ #else #define _K_MAX #endif - #if PIN_EXISTS(K_CS) + #if PIN_EXISTS(K_CS) && AXIS_HAS_SPI(K) #define _K_CS K_CS_PIN, #else #define _K_CS From 21739f41c2e26c50ac2e9e110aeff05bfe2c81c0 Mon Sep 17 00:00:00 2001 From: George Fu Date: Sun, 6 Jun 2021 14:37:52 +0800 Subject: [PATCH 0221/2168] =?UTF-8?q?=F0=9F=93=8C=20Update=20FYSETC=20E4?= =?UTF-8?q?=20to=20espressif32@2.1.0=20(#22049)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/esp32.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/esp32.ini b/ini/esp32.ini index 1aee88f692..fcfa829608 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -24,6 +24,6 @@ monitor_speed = 250000 #board_build.flash_mode = qio [env:FYSETC_E4] -platform = espressif32@1.11.2 +platform = espressif32@2.1.0 extends = env:esp32 board_build.partitions = default_16MB.csv From bc6d8f99b23bbf613b81d7a4d562f113fc32c2e2 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 6 Jun 2021 19:50:14 +1200 Subject: [PATCH 0222/2168] =?UTF-8?q?=F0=9F=93=A6=EF=B8=8F=20Malyan=20M200?= =?UTF-8?q?=20with=20HAL/STM32=20(#22052)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- ini/stm32f1-maple.ini | 2 +- ini/stm32f1.ini | 11 +++++++++++ 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b0463d4498..514665d826 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -466,7 +466,7 @@ #elif MB(STM32F103RE) #include "stm32f1/pins_STM32F1R.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(MALYAN_M200) - #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan + #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan env:STM32F103CB_malyan_maple #elif MB(STM3R_MINI) #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 4daf04263a..349016145c 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -330,7 +330,7 @@ build_flags = ${common_stm32f1.build_flags} # # Malyan M200 (STM32F103CB) # -[env:STM32F103CB_malyan] +[env:STM32F103CB_malyan_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_malyanM200 diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 2e197ccb4d..150ddba01e 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -282,3 +282,14 @@ build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py + +# +# Malyan M200 (STM32F103CB) +# +[env:STM32F103CB_malyan] +platform = ${common_stm32.platform} +extends = common_stm32 +board = malyanm200_f103cb +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED +src_filter = ${common.default_src_filter} + From e7e60a50d81b728cf954ec8cb05d849e61911fa5 Mon Sep 17 00:00:00 2001 From: 7FM <41307817+7FM@users.noreply.github.com> Date: Sun, 6 Jun 2021 09:56:24 +0200 Subject: [PATCH 0223/2168] =?UTF-8?q?=F0=9F=91=BD=EF=B8=8F=20Include=20=20in=20STM32=20(for=20now)=20(#22054)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/eeprom_flash.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 5862090f1b..3d06b172bd 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -28,6 +28,10 @@ #include "../shared/eeprom_api.h" +// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 +// Use EEPROM.h for compatibility, for now. +#include + /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that * even have multiple "banks" of flash. From 0e40d47c727797230ff426cdd7cfbb759b9a986a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 6 Jun 2021 03:49:23 -0500 Subject: [PATCH 0224/2168] =?UTF-8?q?=F0=9F=91=B7=20Add=20caching=20to=20C?= =?UTF-8?q?I=20workflow?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index fd945b0f2a..5429f3eb95 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -109,8 +109,25 @@ jobs: steps: + - name: Check out the PR + uses: actions/checkout@v2 + + - name: Cache pip + uses: actions/cache@v2 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + + - name: Cache PlatformIO + uses: actions/cache@v2 + with: + path: ~/.platformio + key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} + - name: Select Python 3.7 - uses: actions/setup-python@v1 + uses: actions/setup-python@v2 with: python-version: '3.7' # Version range or exact version of a Python version to use, using semvers version range syntax. architecture: 'x64' # optional x64 or x86. Defaults to x64 if not specified @@ -120,9 +137,6 @@ jobs: pip install -U https://github.com/platformio/platformio-core/archive/develop.zip platformio update - - name: Check out the PR - uses: actions/checkout@v2 - - name: Run ${{ matrix.test-platform }} Tests run: | make tests-single-ci TEST_TARGET=${{ matrix.test-platform }} From 3c522fff31f7e1d4127ab09bb27345b098186cd5 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 6 Jun 2021 21:21:14 +1200 Subject: [PATCH 0225/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fallback=20ID=20for=20?= =?UTF-8?q?MKS=20TS35=20V2.0=20(#22031)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 12 ++++++-- Marlin/src/HAL/STM32F1/tft/tft_spi.cpp | 12 ++++++-- Marlin/src/inc/Conditionals_LCD.h | 31 ++++++++++---------- Marlin/src/lcd/tft_io/tft_ids.h | 35 +++++++++++++++++++++++ Marlin/src/lcd/tft_io/tft_io.cpp | 39 +++++++++++++++++++------- Marlin/src/lcd/tft_io/tft_io.h | 35 ++++++----------------- 6 files changed, 109 insertions(+), 55 deletions(-) create mode 100644 Marlin/src/lcd/tft_io/tft_ids.h diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 32af67d158..6bfce81f1a 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -125,12 +125,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { WRITE(TFT_CS_PIN, LOW); } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 1095389946..5edf96fe56 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -90,12 +90,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { TFT_CS_L; } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 07c0439e28..445cc3c067 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1166,29 +1166,38 @@ * - TFT_COLOR * - GRAPHICAL_TFT_UPSCALE */ -#if ENABLED(MKS_TS35_V2_0) // Most common: ST7796 +#if ENABLED(MKS_TS35_V2_0) // ST7796 + #define TFT_DEFAULT_DRIVER ST7796 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) #define TFT_RES_480x320 #define TFT_INTERFACE_SPI -#elif ENABLED(MKS_ROBIN_TFT24) // Most common: ST7789 +#elif ENABLED(ANET_ET5_TFT35) // ST7796 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_RES_480x320 + #define TFT_INTERFACE_FSMC +#elif ENABLED(ANET_ET4_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT28) // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT24) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT32) // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT35) // Most common: ILI9488 +#elif ENABLED(MKS_ROBIN_TFT32) // ST7789 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) + #define TFT_RES_320x240 + #define TFT_INTERFACE_FSMC +#elif ENABLED(MKS_ROBIN_TFT35) // ILI9488 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC #elif ENABLED(MKS_ROBIN_TFT43) - #define TFT_DEFAULT_ORIENTATION 0 #define TFT_DRIVER SSD1963 + #define TFT_DEFAULT_ORIENTATION 0 #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC #elif ENABLED(MKS_ROBIN_TFT_V1_1R) // ILI9328 or R61505 @@ -1196,22 +1205,14 @@ #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC #elif EITHER(TFT_TRONXY_X5SA, ANYCUBIC_TFT35) // ILI9488 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_DRIVER ILI9488 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC #elif ENABLED(LONGER_LK_TFT28) #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(ANET_ET4_TFT28) // ST7789 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif ENABLED(ANET_ET5_TFT35) // ST7796 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) - #define TFT_RES_480x320 - #define TFT_INTERFACE_FSMC #elif ENABLED(BIQU_BX_TFT70) // RGB #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) #define TFT_RES_1024x600 diff --git a/Marlin/src/lcd/tft_io/tft_ids.h b/Marlin/src/lcd/tft_io/tft_ids.h new file mode 100644 index 0000000000..c4f6127c68 --- /dev/null +++ b/Marlin/src/lcd/tft_io/tft_ids.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define LTDC_RGB 0xABAB +#define SSD1963 0x5761 +#define ST7735 0x89F0 +#define ST7789 0x8552 +#define ST7796 0x7796 +#define R61505 0x1505 +#define ILI9328 0x9328 +#define ILI9341 0x9341 +#define ILI9488 0x9488 +#define ILI9488_ID1 0x8066 // Some ILI9488 have 0x8066 in the 0x04 +#define LERDGE_ST7796 0xFFFE +#define AUTO 0xFFFF diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index fa81d95a4d..c06e86b281 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -20,18 +20,37 @@ * */ -#include "tft_io.h" +#include "../../inc/MarlinConfigPre.h" #if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT -#include "st7735.h" -#include "st7789v.h" -#include "st7796s.h" -#include "r65105.h" -#include "ili9328.h" -#include "ili9341.h" -#include "ili9488.h" -#include "ssd1963.h" +#include "tft_io.h" +#include "tft_ids.h" + +#if TFT_DRIVER == ST7735 || TFT_DRIVER == AUTO + #include "st7735.h" +#endif +#if TFT_DRIVER == ST7789 || TFT_DRIVER == AUTO + #include "st7789v.h" +#endif +#if TFT_DRIVER == ST7796 || TFT_DRIVER == AUTO + #include "st7796s.h" +#endif +#if TFT_DRIVER == R61505 || TFT_DRIVER == AUTO + #include "r65105.h" +#endif +#if TFT_DRIVER == ILI9328 || TFT_DRIVER == AUTO + #include "ili9328.h" +#endif +#if TFT_DRIVER == ILI9341 || TFT_DRIVER == AUTO + #include "ili9341.h" +#endif +#if TFT_DRIVER == ILI9488 || TFT_DRIVER == ILI9488_ID1 || TFT_DRIVER == AUTO + #include "ili9488.h" +#endif +#if TFT_DRIVER == SSD1963 || TFT_DRIVER == AUTO + #include "ssd1963.h" +#endif #define DEBUG_OUT ENABLED(DEBUG_GRAPHICAL_TFT) #include "../../core/debug_out.h" @@ -236,4 +255,4 @@ void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { io.DataTransferEnd(); } -#endif // HAS_SPI_TFT || HAS_FSMC_TFT +#endif // HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 846b45e8e0..0e4322f0d7 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -23,8 +23,6 @@ #include "../../inc/MarlinConfig.h" -#if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT - #if HAS_SPI_TFT #include HAL_PATH(../../HAL, tft/tft_spi.h) #elif HAS_FSMC_TFT @@ -35,9 +33,9 @@ #error "TFT IO only supports SPI, FSMC or LTDC interface" #endif -#define TFT_EXCHANGE_XY (1UL << 1) -#define TFT_INVERT_X (1UL << 2) -#define TFT_INVERT_Y (1UL << 3) +#define TFT_EXCHANGE_XY _BV32(1) +#define TFT_INVERT_X _BV32(2) +#define TFT_INVERT_Y _BV32(3) #define TFT_NO_ROTATION (0x00) #define TFT_ROTATE_90 (TFT_EXCHANGE_XY | TFT_INVERT_X) @@ -65,8 +63,8 @@ // TFT_ORIENTATION is the "sum" of TFT_DEFAULT_ORIENTATION plus user TFT_ROTATION #define TFT_ORIENTATION ((TFT_DEFAULT_ORIENTATION) ^ (TFT_ROTATION)) -#define TFT_COLOR_RGB (1UL << 3) -#define TFT_COLOR_BGR (1UL << 4) +#define TFT_COLOR_RGB _BV32(3) +#define TFT_COLOR_BGR _BV32(4) // Each TFT Driver is responsible for its default color mode. // #ifndef TFT_COLOR @@ -93,27 +91,14 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif -#define LTDC_RGB 0xABAB -#define SSD1963 0x5761 -#define ST7735 0x89F0 -#define ST7789 0x8552 -#define ST7796 0x7796 -#define R61505 0x1505 -#define ILI9328 0x9328 -#define ILI9341 0x9341 -#define ILI9488 0x9488 -#define ILI9488_ID1 0x8066 //Some ILI9488 have 0x8066 in the 0x04 -#define LERDGE_ST7796 0xFFFE -#define AUTO 0xFFFF - #ifndef TFT_DRIVER #define TFT_DRIVER AUTO #endif -#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x -#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) -#define ESC_END 0xFFFF, 0x7FFF -#define ESC_FFFF 0xFFFF, 0xFFFF +#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x +#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) +#define ESC_END 0xFFFF, 0x7FFF +#define ESC_FFFF 0xFFFF, 0xFFFF class TFT_IO { public: @@ -143,5 +128,3 @@ public: protected: static uint32_t lcd_id; }; - -#endif // HAS_SPI_TFT || HAS_FSMC_TFT From fa94fc5f355fcd9130a895659b7ac12eba64338c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 7 Jun 2021 01:29:19 +0000 Subject: [PATCH 0226/2168] [cron] Bump distribution date (2021-06-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9415a53c19..c531cf8c65 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 "2021-06-06" + #define STRING_DISTRIBUTION_DATE "2021-06-07" #endif /** From e31c26748197bdeb8ad7aa01ae34299d9d7136f3 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Mon, 7 Jun 2021 06:23:23 +0200 Subject: [PATCH 0227/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Six=20Linear=20A?= =?UTF-8?q?xes=20followup=20(Hybrid=20Threshold=20init)=20(#22068)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index aae0f97361..0a88d63e8c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1175,7 +1175,7 @@ void MarlinSettings::postprocess() { const tmc_hybrid_threshold_t tmc_hybrid_threshold = { LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3), .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3 - REPEAT(EXTRUDERS, _EN_ITEM) + REPEAT(E_STEPPERS, _EN_ITEM) }; #undef _EN_ITEM #endif From 209c44b8031c1d22bc4616b1ecd8243ddcc0a4ad Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sun, 6 Jun 2021 22:26:42 -0600 Subject: [PATCH 0228/2168] =?UTF-8?q?=F0=9F=8E=A8=20Reorganize=20FTDI=20To?= =?UTF-8?q?uch=20UI=20variants=20(#22066)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../advanced_settings.cpp} | 2 +- .../advanced_settings.h} | 0 .../confirm_home_e.cpp} | 2 +- .../confirm_home_e.h} | 0 .../confirm_home_xyz.cpp} | 2 +- .../confirm_home_xyz.h} | 0 .../main_menu.cpp} | 2 +- .../main_menu.h} | 0 .../printing_dialog_box.cpp} | 2 +- .../printing_dialog_box.h} | 0 .../status_screen.cpp} | 6 +- .../status_screen.h} | 0 .../tune_menu.cpp} | 2 +- .../tune_menu.h} | 0 .../ui_landscape.h} | 0 .../ui_portrait.h} | 0 .../advanced_settings_menu.cpp} | 8 +- .../advanced_settings_menu.h} | 6 +- .../{screens => cocoa_press}/cocoa_press_ui.h | 0 .../load_chocolate.cpp} | 14 +- .../load_chocolate.h} | 6 +- .../main_menu.cpp} | 8 +- .../main_menu.h} | 6 +- .../move_e_screen.cpp} | 10 +- .../move_e_screen.h} | 6 +- .../move_xyz_screen.cpp} | 10 +- .../move_xyz_screen.h} | 6 +- .../preheat_menu.cpp} | 8 +- .../preheat_menu.h} | 6 +- .../preheat_screen.cpp} | 14 +- .../preheat_screen.h} | 6 +- .../status_screen.cpp} | 8 +- .../status_screen.h} | 6 +- .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 2 +- .../{screens => generic}/about_screen.cpp | 2 +- .../{screens => generic}/about_screen.h | 0 .../advanced_settings_menu.cpp | 2 +- .../advanced_settings_menu.h | 0 .../{screens => generic}/alert_dialog_box.cpp | 4 +- .../{screens => generic}/alert_dialog_box.h | 0 .../backlash_compensation_screen.cpp | 2 +- .../backlash_compensation_screen.h | 0 .../base_numeric_adjustment_screen.cpp | 4 +- .../base_numeric_adjustment_screen.h | 0 .../{screens => generic}/base_screen.cpp | 2 +- .../{screens => generic}/base_screen.h | 0 .../{screens => generic}/bed_mesh_base.cpp | 2 +- .../{screens => generic}/bed_mesh_base.h | 0 .../bed_mesh_edit_screen.cpp | 4 +- .../bed_mesh_edit_screen.h | 0 .../bed_mesh_view_screen.cpp | 4 +- .../bed_mesh_view_screen.h | 0 .../{screens => generic}/boot_screen.cpp | 2 +- .../{screens => generic}/boot_screen.h | 0 .../case_light_screen.cpp | 2 +- .../{screens => generic}/case_light_screen.h | 0 .../change_filament_screen.cpp | 4 +- .../change_filament_screen.h | 0 .../confirm_abort_print_dialog_box.cpp | 2 +- .../confirm_abort_print_dialog_box.h | 0 .../confirm_auto_calibration_dialog_box.cpp | 2 +- .../confirm_auto_calibration_dialog_box.h | 0 .../confirm_erase_flash_dialog_box.cpp | 2 +- .../confirm_erase_flash_dialog_box.h | 0 .../confirm_start_print_dialog_box.cpp | 4 +- .../confirm_start_print_dialog_box.h | 0 .../confirm_user_request_alert_box.cpp | 4 +- .../confirm_user_request_alert_box.h | 0 .../custom_user_menus.cpp | 2 +- .../{screens => generic}/custom_user_menus.h | 0 .../default_acceleration_screen.cpp | 2 +- .../default_acceleration_screen.h | 0 .../{screens => generic}/developer_menu.cpp | 2 +- .../{screens => generic}/developer_menu.h | 0 .../dialog_box_base_class.cpp | 2 +- .../dialog_box_base_class.h | 0 .../display_tuning_screen.cpp | 2 +- .../display_tuning_screen.h | 0 .../endstop_state_screen.cpp | 2 +- .../endstop_state_screen.h | 0 .../feedrate_percent_screen.cpp | 2 +- .../feedrate_percent_screen.h | 0 .../{screens => generic}/filament_menu.cpp | 2 +- .../{screens => generic}/filament_menu.h | 0 .../filament_runout_screen.cpp | 2 +- .../filament_runout_screen.h | 0 .../{screens => generic}/files_screen.cpp | 4 +- .../{screens => generic}/files_screen.h | 0 .../flow_percent_screen.cpp | 2 +- .../flow_percent_screen.h | 0 .../interface_settings_screen.cpp | 4 +- .../interface_settings_screen.h | 0 .../interface_sounds_screen.cpp | 4 +- .../interface_sounds_screen.h | 0 .../{screens => generic}/jerk_screen.cpp | 2 +- .../{screens => generic}/jerk_screen.h | 0 .../junction_deviation_screen.cpp | 2 +- .../junction_deviation_screen.h | 0 .../{screens => generic}/kill_screen.cpp | 2 +- .../{screens => generic}/kill_screen.h | 0 .../{screens => generic}/language_menu.cpp | 2 +- .../{screens => generic}/language_menu.h | 0 .../{screens => generic}/leveling_menu.cpp | 2 +- .../{screens => generic}/leveling_menu.h | 0 .../linear_advance_screen.cpp | 2 +- .../linear_advance_screen.h | 0 .../{screens => generic}/lock_screen.cpp | 4 +- .../{screens => generic}/lock_screen.h | 0 .../{screens => generic}/main_menu.cpp | 2 +- .../{screens => generic}/main_menu.h | 0 .../max_acceleration_screen.cpp | 2 +- .../max_acceleration_screen.h | 0 .../max_velocity_screen.cpp | 2 +- .../max_velocity_screen.h | 0 .../media_player_screen.cpp | 2 +- .../media_player_screen.h | 0 .../{screens => generic}/move_axis_screen.cpp | 4 +- .../{screens => generic}/move_axis_screen.h | 0 .../nozzle_offsets_screen.cpp | 2 +- .../nozzle_offsets_screen.h | 0 .../nudge_nozzle_screen.cpp | 4 +- .../nudge_nozzle_screen.h | 0 .../restore_failsafe_dialog_box.cpp | 2 +- .../restore_failsafe_dialog_box.h | 0 .../save_settings_dialog_box.cpp | 2 +- .../save_settings_dialog_box.h | 0 .../spinner_dialog_box.cpp | 4 +- .../{screens => generic}/spinner_dialog_box.h | 0 .../statistics_screen.cpp | 2 +- .../{screens => generic}/statistics_screen.h | 0 .../{screens => generic}/status_screen.cpp | 4 +- .../{screens => generic}/status_screen.h | 0 .../stepper_bump_sensitivity_screen.cpp | 2 +- .../stepper_bump_sensitivity_screen.h | 0 .../stepper_current_screen.cpp | 2 +- .../stepper_current_screen.h | 0 .../{screens => generic}/steps_screen.cpp | 2 +- .../{screens => generic}/steps_screen.h | 0 .../stress_test_screen.cpp | 4 +- .../{screens => generic}/stress_test_screen.h | 0 .../{screens => generic}/string_format.cpp | 2 +- .../{screens => generic}/string_format.h | 0 .../temperature_screen.cpp | 2 +- .../{screens => generic}/temperature_screen.h | 0 .../touch_calibration_screen.cpp | 2 +- .../touch_calibration_screen.h | 0 .../touch_registers_screen.cpp | 2 +- .../touch_registers_screen.h | 0 .../{screens => generic}/tune_menu.cpp | 2 +- .../{screens => generic}/tune_menu.h | 0 .../widget_demo_screen.cpp | 2 +- .../{screens => generic}/widget_demo_screen.h | 0 .../{screens => generic}/z_offset_screen.cpp | 4 +- .../{screens => generic}/z_offset_screen.h | 0 .../{screens => }/screen_data.h | 6 +- .../{screens => }/screens.cpp | 19 ++- .../ftdi_eve_touch_ui/{screens => }/screens.h | 148 +++++++++--------- .../screens/cocoa_press_unload_cartridge.cpp | 100 ------------ .../screens/cocoa_press_unload_cartridge.h | 34 ---- 159 files changed, 237 insertions(+), 372 deletions(-) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_advanced_settings.cpp => bioprinter/advanced_settings.cpp} (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_advanced_settings.h => bioprinter/advanced_settings.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_confirm_home_e.cpp => bioprinter/confirm_home_e.cpp} (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_confirm_home_e.h => bioprinter/confirm_home_e.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_confirm_home_xyz.cpp => bioprinter/confirm_home_xyz.cpp} (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_confirm_home_xyz.h => bioprinter/confirm_home_xyz.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_main_menu.cpp => bioprinter/main_menu.cpp} (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_main_menu.h => bioprinter/main_menu.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_printing_dialog_box.cpp => bioprinter/printing_dialog_box.cpp} (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_printing_dialog_box.h => bioprinter/printing_dialog_box.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_status_screen.cpp => bioprinter/status_screen.cpp} (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_status_screen.h => bioprinter/status_screen.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_tune_menu.cpp => bioprinter/tune_menu.cpp} (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_tune_menu.h => bioprinter/tune_menu.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_printer_ui_landscape.h => bioprinter/ui_landscape.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/bio_printer_ui_portrait.h => bioprinter/ui_portrait.h} (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_advanced_settings_menu.cpp => cocoa_press/advanced_settings_menu.cpp} (96%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_advanced_settings_menu.h => cocoa_press/advanced_settings_menu.h} (91%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => cocoa_press}/cocoa_press_ui.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_load_chocolate.cpp => cocoa_press/load_chocolate.cpp} (96%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_load_chocolate.h => cocoa_press/load_chocolate.h} (93%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_main_menu.cpp => cocoa_press/main_menu.cpp} (97%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_main_menu.h => cocoa_press/main_menu.h} (94%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_move_e_screen.cpp => cocoa_press/move_e_screen.cpp} (94%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_move_e_screen.h => cocoa_press/move_e_screen.h} (93%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_move_xyz_screen.cpp => cocoa_press/move_xyz_screen.cpp} (93%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_move_xyz_screen.h => cocoa_press/move_xyz_screen.h} (93%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_preheat_menu.cpp => cocoa_press/preheat_menu.cpp} (97%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_preheat_menu.h => cocoa_press/preheat_menu.h} (92%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_preheat_screen.cpp => cocoa_press/preheat_screen.cpp} (96%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_preheat_screen.h => cocoa_press/preheat_screen.h} (94%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_status_screen.cpp => cocoa_press/status_screen.cpp} (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens/cocoa_press_status_screen.h => cocoa_press/status_screen.h} (95%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/about_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/about_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/advanced_settings_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/advanced_settings_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/alert_dialog_box.cpp (97%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/alert_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/backlash_compensation_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/backlash_compensation_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/base_numeric_adjustment_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/base_numeric_adjustment_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/base_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/base_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_base.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_base.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_edit_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_edit_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_view_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/bed_mesh_view_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/boot_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/boot_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/case_light_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/case_light_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/change_filament_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/change_filament_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_abort_print_dialog_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_abort_print_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_auto_calibration_dialog_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_auto_calibration_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_erase_flash_dialog_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_erase_flash_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_start_print_dialog_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_start_print_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_user_request_alert_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/confirm_user_request_alert_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/custom_user_menus.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/custom_user_menus.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/default_acceleration_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/default_acceleration_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/developer_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/developer_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/dialog_box_base_class.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/dialog_box_base_class.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/display_tuning_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/display_tuning_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/endstop_state_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/endstop_state_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/feedrate_percent_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/feedrate_percent_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/filament_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/filament_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/filament_runout_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/filament_runout_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/files_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/files_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/flow_percent_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/flow_percent_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/interface_settings_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/interface_settings_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/interface_sounds_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/interface_sounds_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/jerk_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/jerk_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/junction_deviation_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/junction_deviation_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/kill_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/kill_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/language_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/language_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/leveling_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/leveling_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/linear_advance_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/linear_advance_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/lock_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/lock_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/main_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/main_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/max_acceleration_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/max_acceleration_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/max_velocity_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/max_velocity_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/media_player_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/media_player_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/move_axis_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/move_axis_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/nozzle_offsets_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/nozzle_offsets_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/nudge_nozzle_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/nudge_nozzle_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/restore_failsafe_dialog_box.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/restore_failsafe_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/save_settings_dialog_box.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/save_settings_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/spinner_dialog_box.cpp (97%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/spinner_dialog_box.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/statistics_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/statistics_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/status_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/status_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stepper_bump_sensitivity_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stepper_bump_sensitivity_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stepper_current_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stepper_current_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/steps_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/steps_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stress_test_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/stress_test_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/string_format.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/string_format.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/temperature_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/temperature_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/touch_calibration_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/touch_calibration_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/touch_registers_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/touch_registers_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/tune_menu.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/tune_menu.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/widget_demo_screen.cpp (99%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/widget_demo_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/z_offset_screen.cpp (98%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => generic}/z_offset_screen.h (100%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => }/screen_data.h (94%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => }/screens.cpp (90%) rename Marlin/src/lcd/extui/ftdi_eve_touch_ui/{screens => }/screens.h (62%) delete mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp delete mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp index 16b2891e27..fd478c95a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp index 3b55551375..dedda6d215 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_CONFIRM_HOME_E diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp index f1abd2e76a..bff1808d0d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_CONFIRM_HOME_XYZ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index 6897ceb914..ae5e7d8ab1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index 10ed6eb14a..86c700f235 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_PRINTING_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp index c66e4d94d8..6fa4d761f6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -22,14 +22,14 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_STATUS_SCREEN #if ENABLED(TOUCH_UI_PORTRAIT) - #include "bio_printer_ui_portrait.h" + #include "ui_portrait.h" #else - #include "bio_printer_ui_landscape.h" + #include "ui_landscape.h" #endif #define GRID_COLS 2 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp index 806f7bd1af..31021c31c0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_TUNE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp index 7bd149bd46..d984dbe120 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp @@ -1,5 +1,5 @@ /***************************************** - * cocoa_press_advance_settings_menu.cpp * + * cocoa_press/advance_settings_menu.cpp * *****************************************/ /**************************************************************************** @@ -21,9 +21,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_ADVANCED_SETTINGS_MENU +#ifdef COCOA_ADVANCED_SETTINGS_MENU using namespace FTDI; using namespace ExtUI; @@ -92,4 +92,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } -#endif // FTDI_COCOA_ADVANCED_SETTINGS_MENU +#endif // COCOA_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h similarity index 91% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h index 08c0745321..02f65572a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h @@ -1,5 +1,5 @@ /*************************************** - * cocoa_press_advance_settings_menu.h * + * cocoa_press/advance_settings_menu.h * ***************************************/ /**************************************************************************** @@ -22,8 +22,8 @@ #pragma once -#define FTDI_COCOA_ADVANCED_SETTINGS_MENU -#define FTDI_COCOA_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu +#define COCOA_ADVANCED_SETTINGS_MENU +#define COCOA_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp index ac49df0916..8c15cae60f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp @@ -1,6 +1,6 @@ -/************************************ - * cocoa_press_unload_cartridge.cpp * - ************************************/ +/********************************** + * cocoa_press/load_chocolate.cpp * + **********************************/ /**************************************************************************** * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_LOAD_CHOCOLATE_SCREEN +#ifdef COCOA_LOAD_CHOCOLATE_SCREEN #include "cocoa_press_ui.h" @@ -215,4 +215,4 @@ void LoadChocolateScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_LOAD_CHOCOLATE_SCREEN +#endif // COCOA_LOAD_CHOCOLATE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h index 819464495b..4a582f0212 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h @@ -1,5 +1,5 @@ /******************************** - * cocoa_press_load_chocolate.h * + * cocoa_press/load_chocolate.h * ********************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_LOAD_CHOCOLATE_SCREEN -#define FTDI_COCOA_LOAD_CHOCOLATE_SCREEN_CLASS LoadChocolateScreen +#define COCOA_LOAD_CHOCOLATE_SCREEN +#define COCOA_LOAD_CHOCOLATE_SCREEN_CLASS LoadChocolateScreen struct LoadChocolateScreenData { uint8_t repeat_tag; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index 7708b38eca..28dad42b13 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -1,5 +1,5 @@ /***************************** - * cocoa_press_main_menu.cpp * + * cocoa_press/main_menu.cpp * *****************************/ /**************************************************************************** @@ -22,9 +22,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_MAIN_MENU +#ifdef COCOA_MAIN_MENU using namespace FTDI; using namespace Theme; @@ -97,4 +97,4 @@ bool MainMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // FTDI_COCOA_MAIN_MENU +#endif // COCOA_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h index 7c2bb5039a..460bb4b81a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h @@ -1,5 +1,5 @@ /*************************** - * cocoa_press_main_menu.h * + * cocoa_press/main_menu.h * ***************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MAIN_MENU -#define FTDI_COCOA_MAIN_MENU_CLASS MainMenu +#define COCOA_MAIN_MENU +#define COCOA_MAIN_MENU_CLASS MainMenu class MainMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp index 2621ef64fe..f7dbc466c7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_move_e_screen.cpp * + * cocoa_press/move_e_screen.cpp * *********************************/ /**************************************************************************** @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_MOVE_E_SCREEN +#ifdef COCOA_MOVE_E_SCREEN using namespace FTDI; using namespace ExtUI; @@ -60,4 +60,4 @@ void MoveEScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_MOVE_E_SCREEN +#endif // COCOA_MOVE_E_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h index e86a91a529..0cede6f0c5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h @@ -1,5 +1,5 @@ /******************************* - * cocoa_press_move_e_screen.h * + * cocoa_press/move_e_screen.h * *******************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MOVE_E_SCREEN -#define FTDI_COCOA_MOVE_E_SCREEN_CLASS MoveEScreen +#define COCOA_MOVE_E_SCREEN +#define COCOA_MOVE_E_SCREEN_CLASS MoveEScreen class MoveEScreen : public BaseMoveAxisScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp index c9442c9322..8e80bd53a9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp @@ -1,5 +1,5 @@ /*********************************** - * cocoa_press_move_xyz_screen.cpp * + * cocoa_press/move_xyz_screen.cpp * ***********************************/ /**************************************************************************** @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_MOVE_XYZ_SCREEN +#ifdef COCOA_MOVE_XYZ_SCREEN using namespace FTDI; using namespace ExtUI; @@ -49,4 +49,4 @@ void MoveXYZScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_MOVE_XYZ_SCREEN +#endif // COCOA_MOVE_XYZ_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h index 9cbec113e6..015f5b30e4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_move_xyz_screen.h * + * cocoa_press/move_xyz_screen.h * *********************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MOVE_XYZ_SCREEN -#define FTDI_COCOA_MOVE_XYZ_SCREEN_CLASS MoveXYZScreen +#define COCOA_MOVE_XYZ_SCREEN +#define COCOA_MOVE_XYZ_SCREEN_CLASS MoveXYZScreen class MoveXYZScreen : public BaseMoveAxisScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp index 92d1522360..56e90ceb4d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -1,5 +1,5 @@ /******************************** - * cocoa_press_preheat_menu.cpp * + * cocoa_press/preheat_menu.cpp * ********************************/ /**************************************************************************** @@ -20,9 +20,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_PREHEAT_MENU +#ifdef COCOA_PREHEAT_MENU using namespace FTDI; using namespace ExtUI; @@ -113,4 +113,4 @@ bool PreheatMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // FTDI_COCOA_PREHEAT_MENU +#endif // COCOA_PREHEAT_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h similarity index 92% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h index a109e42111..46bded7df4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h @@ -1,5 +1,5 @@ /****************************** - * cocoa_press_preheat_menu.h * + * cocoa_press/preheat_menu.h * ******************************/ /**************************************************************************** @@ -21,8 +21,8 @@ #pragma once -#define FTDI_COCOA_PREHEAT_MENU -#define FTDI_COCOA_PREHEAT_MENU_CLASS PreheatMenu +#define COCOA_PREHEAT_MENU +#define COCOA_PREHEAT_MENU_CLASS PreheatMenu class PreheatMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index a8a172b3da..3bcc64fd93 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -1,6 +1,6 @@ -/**************************** - * preheat_timer_screen.cpp * - ****************************/ +/*************************************** + * cocoapress/preheat_timer_screen.cpp * + ***************************************/ /**************************************************************************** * Written By Marcio Teixeira 2019 - Cocoa Press * @@ -20,10 +20,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_PREHEAT_SCREEN +#ifdef COCOA_PREHEAT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -168,4 +168,4 @@ void PreheatTimerScreen::onIdle() { BaseScreen::onIdle(); } -#endif // FTDI_COCOA_PREHEAT_SCREEN +#endif // COCOA_PREHEAT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h index e91340a3aa..9b8e2620dc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h @@ -1,5 +1,5 @@ /********************************* - * cocoapress_preheat_screen.cpp * + * cocoapress/preheat_screen.cpp * *********************************/ /**************************************************************************** @@ -21,8 +21,8 @@ #pragma once -#define FTDI_COCOA_PREHEAT_SCREEN -#define FTDI_COCOA_PREHEAT_SCREEN_CLASS PreheatTimerScreen +#define COCOA_PREHEAT_SCREEN +#define COCOA_PREHEAT_SCREEN_CLASS PreheatTimerScreen struct PreheatTimerScreenData { uint32_t start_ms; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index a0c8914589..38fdc2bb26 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_status_screen.cpp * + * cocoa_press/status_screen.cpp * *********************************/ /**************************************************************************** @@ -22,9 +22,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_STATUS_SCREEN +#ifdef COCOA_STATUS_SCREEN #include "cocoa_press_ui.h" @@ -294,4 +294,4 @@ void StatusScreen::onIdle() { } } -#endif // FTDI_COCOA_STATUS_SCREEN +#endif // COCOA_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h similarity index 95% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h index b22bceac14..1cddfa0896 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h @@ -1,5 +1,5 @@ /******************************* - * cocoa_press_status_screen.h * + * cocoa_press/status_screen.h * *******************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_STATUS_SCREEN -#define FTDI_COCOA_STATUS_SCREEN_CLASS StatusScreen +#define COCOA_STATUS_SCREEN +#define COCOA_STATUS_SCREEN_CLASS StatusScreen class StatusScreen : public BaseScreen, public CachedScreen { private: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index 08faaa3b6a..e15f61be00 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -28,7 +28,7 @@ #if ENABLED(TOUCH_UI_FTDI_EVE) -#include "screens/screens.h" +#include "screens.h" namespace ExtUI { using namespace Theme; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 1d8db12ef9..8d8c543046 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_ABOUT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index b9255c11b9..58a7112d01 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp index bbe922ad5d..ccdfa89419 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_ALERT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp index 11fb72b5a8..c3fcb25f43 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BACKLASH_COMP_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index 747e632d8f..90199783fd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BASE_NUMERIC_ADJ_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp index 139a3100cf..3981a37042 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BASE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp index 83b0825802..14f2196453 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BED_MESH_BASE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 31c6ab8fcb..e06fb52773 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -20,8 +20,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BED_MESH_EDIT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 1a00e10ca9..f5cf1cbb34 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -20,8 +20,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BED_MESH_VIEW_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp index c8c7cdb5a5..d2a2269295 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp @@ -22,7 +22,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BOOT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp index 04327128ab..8fbb400a68 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CASE_LIGHT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index e9fa8a66d4..a3cb91af5d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_CHANGE_FILAMENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp index 46b27062bf..02e48efa01 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CONFIRM_ABORT_PRINT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_abort_print_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp index 65b5140ccb..748cc1d7ef 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CONFIRM_AUTO_CALIBRATION_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp index 13d61005e8..b4ddebea5e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_erase_flash_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp index 86e7e33035..47aac62860 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_CONFIRM_START_PRINT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp index d514015058..4aabbaab59 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_CONFIRM_USER_REQUEST_ALERT_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp index d5d1abdf9d..5f8ff92922 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -21,7 +21,7 @@ */ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CUSTOM_USER_MENUS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/custom_user_menus.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp index 6178228d09..07473d66a1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_DEFAULT_ACCELERATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/default_acceleration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/default_acceleration_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp index 0bbce08a2b..34c754d535 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_DEVELOPER_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/developer_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index feaebb77be..0d604751f1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_DIALOG_BOX_BASE_CLASS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/dialog_box_base_class.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp index 62a329e907..504ebde169 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_DISPLAY_TUNING_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/display_tuning_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/display_tuning_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index e79e88b6b0..d12cb32e20 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_ENDSTOP_STATE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp index 8b3984aa01..80eb295f64 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_FEEDRATE_PERCENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/feedrate_percent_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/feedrate_percent_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp index cf63a1a124..bd5fa96e8d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_FILAMENT_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp index 069686b541..37ab70f7ac 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_FILAMENT_RUNOUT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/filament_runout_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp index f9057ae88e..c34a3d3055 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_FILES_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/files_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp index 5280092ced..be350bd9a7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_FLOW_PERCENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/flow_percent_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/flow_percent_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp index 56f0fbdc3c..05c6956e42 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_INTERFACE_SETTINGS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_settings_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp index 4e47653899..3ba035f19b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_INTERFACE_SOUNDS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/interface_sounds_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp index d74879fd41..4331cb7089 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_JERK_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/jerk_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/jerk_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp index 4b9f5512bb..98e4816790 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_JUNCTION_DEVIATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/junction_deviation_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/junction_deviation_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp index fe58cad93c..bb44a87176 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_KILL_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/kill_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/kill_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp index 77c0d02756..ce6045018b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_LANGUAGE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/language_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 1309ab5c09..93f9c4c228 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_LEVELING_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/leveling_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp index e70d6933cc..e3b59eef5c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_LINEAR_ADVANCE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/linear_advance_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/linear_advance_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp index f89ad5c44c..4e44f26d91 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_LOCK_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/lock_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index 53d6306175..f7a0d6683a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -22,7 +22,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp index d4d14d6331..be3a244380 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_MAX_ACCELERATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_acceleration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp index 4de3e33360..bca533c94f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_MAX_VELOCITY_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/max_velocity_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp index 38e8b0b5c7..061c8555df 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" /** * The MediaPlayerScreen allows an AVI to be played. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/media_player_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index 9406572c33..3bfe1784fc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_MOVE_AXIS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp index a444a07cfc..288d06ea8e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_NOZZLE_OFFSETS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nozzle_offsets_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp index 96ad833b14..c1611100a9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_NUDGE_NOZZLE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/nudge_nozzle_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp index 8dce1a259c..2dfd64fa5b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_RESTORE_FAILSAFE_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp index a475a9863c..176630d11e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_SAVE_SETTINGS_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/save_settings_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 7483261e3c..489beabe6b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_SPINNER_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp index 2d62d5349b..2153a1e1ad 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_STATISTICS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index f61136e396..9ef481d39b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp index 701fb78062..ddbe648c32 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_STEPPER_BUMP_SENSITIVITY_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_bump_sensitivity_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp index 4b63b1f3e4..ddd273aa47 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_STEPPER_CURRENT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stepper_current_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stepper_current_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp index ec812b776b..c73c49493e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_STEPS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/steps_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/steps_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp index 916315a243..09f2088240 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_STRESS_TEST_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/stress_test_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp index ac423c2d07..09f0bb6089 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp @@ -23,7 +23,7 @@ #if ENABLED(TOUCH_UI_FTDI_EVE) -#include "screens.h" +#include "../screens.h" #define ROUND(val) uint16_t((val)+0.5) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/string_format.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp index b1d00aa521..ee53a82bee 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_TEMPERATURE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/temperature_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp index 37f0c5d33a..c7c21368df 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_TOUCH_CALIBRATION_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_calibration_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_calibration_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp index 01c7169a3e..5475d67a80 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_TOUCH_REGISTERS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/touch_registers_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/touch_registers_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index 5403b4004e..b4afae9f17 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_TUNE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/tune_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp index 451b7e786e..d02397abf9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_WIDGET_DEMO_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/widget_demo_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/widget_demo_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp index 8a21efcbac..58cab48049 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_Z_OFFSET_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/z_offset_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h index 17e445fe4d..057054a6af 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h @@ -22,7 +22,7 @@ #pragma once -#include "../ftdi_eve_lib/ftdi_eve_lib.h" +#include "ftdi_eve_lib/ftdi_eve_lib.h" // To save RAM, store state information related to a particular screen // in a union. The values should be initialized in the onEntry method. @@ -58,12 +58,12 @@ union screen_data_t { DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_VIEW_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_EDIT_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) - DECL_DATA_IF_INCLUDED(FTDI_COCOA_PREHEAT_SCREEN) - DECL_DATA_IF_INCLUDED(FTDI_COCOA_LOAD_CHOCOLATE_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_NUDGE_NOZZLE_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_Z_OFFSET_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_BASE_NUMERIC_ADJ_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_ALERT_DIALOG_BOX) + DECL_DATA_IF_INCLUDED(COCOA_PREHEAT_SCREEN) + DECL_DATA_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) }; extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp similarity index 90% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp index c3e015d75c..e1900ac793 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -20,7 +20,7 @@ * location: . * ****************************************************************************/ -#include "../config.h" +#include "config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "screens.h" @@ -100,15 +100,6 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(FTDI_BIO_PRINTING_DIALOG_BOX) DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_XYZ) DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_E) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_STATUS_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MAIN_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_ADVANCED_SETTINGS_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_PREHEAT_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_PREHEAT_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_LOAD_CHOCOLATE_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MOVE_XYZ_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MOVE_E_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_DEVELOPER_MENU) DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX) DECL_SCREEN_IF_INCLUDED(FTDI_WIDGET_DEMO_SCREEN) @@ -116,6 +107,14 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_MEDIA_PLAYER_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_DISPLAY_TUNING_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_STATUS_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MAIN_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_ADVANCED_SETTINGS_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_XYZ_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_E_SCREEN) }; SCREEN_TABLE_POST diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h similarity index 62% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h index 316896c360..f5e2160d10 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -22,14 +22,14 @@ #pragma once -#include "../compat.h" +#include "compat.h" #if ENABLED(TOUCH_UI_FTDI_EVE) -#include "../ftdi_eve_lib/ftdi_eve_lib.h" -#include "../language/language.h" -#include "../theme/theme.h" -#include "string_format.h" +#include "ftdi_eve_lib/ftdi_eve_lib.h" +#include "language/language.h" +#include "theme/theme.h" +#include "generic/string_format.h" #ifndef BED_LEVELING_COMMANDS #define BED_LEVELING_COMMANDS "G29" @@ -132,9 +132,9 @@ enum { /************************* MENU SCREEN DECLARATIONS *************************/ -#include "base_screen.h" -#include "base_numeric_adjustment_screen.h" -#include "dialog_box_base_class.h" +#include "generic/base_screen.h" +#include "generic/base_numeric_adjustment_screen.h" +#include "generic/dialog_box_base_class.h" #if ENABLED(TOUCH_UI_LULZBOT_BIO) #include "bio_status_screen.h" @@ -146,128 +146,128 @@ enum { #include "bio_confirm_home_e.h" #elif ENABLED(TOUCH_UI_COCOA_PRESS) - #include "cocoa_press_status_screen.h" - #include "cocoa_press_main_menu.h" - #include "cocoa_press_advanced_settings_menu.h" - #include "cocoa_press_preheat_menu.h" - #include "cocoa_press_preheat_screen.h" - #include "cocoa_press_load_chocolate.h" - #include "move_axis_screen.h" - #include "flow_percent_screen.h" - #include "cocoa_press_move_xyz_screen.h" - #include "cocoa_press_move_e_screen.h" - #include "tune_menu.h" + #include "generic/move_axis_screen.h" + #include "generic/flow_percent_screen.h" + #include "generic/tune_menu.h" + #include "cocoa_press/status_screen.h" + #include "cocoa_press/main_menu.h" + #include "cocoa_press/advanced_settings_menu.h" + #include "cocoa_press/preheat_menu.h" + #include "cocoa_press/preheat_screen.h" + #include "cocoa_press/load_chocolate.h" + #include "cocoa_press/move_xyz_screen.h" + #include "cocoa_press/move_e_screen.h" #else - #include "status_screen.h" - #include "main_menu.h" - #include "advanced_settings_menu.h" - #include "tune_menu.h" + #include "generic/status_screen.h" + #include "generic/main_menu.h" + #include "generic/advanced_settings_menu.h" + #include "generic/tune_menu.h" #endif -#include "boot_screen.h" -#include "about_screen.h" -#include "kill_screen.h" -#include "alert_dialog_box.h" -#include "spinner_dialog_box.h" -#include "restore_failsafe_dialog_box.h" -#include "save_settings_dialog_box.h" -#include "confirm_start_print_dialog_box.h" -#include "confirm_abort_print_dialog_box.h" -#include "confirm_user_request_alert_box.h" -#include "touch_calibration_screen.h" -#include "touch_registers_screen.h" -#include "change_filament_screen.h" -#include "move_axis_screen.h" -#include "steps_screen.h" -#include "feedrate_percent_screen.h" -#include "max_velocity_screen.h" -#include "max_acceleration_screen.h" -#include "default_acceleration_screen.h" -#include "temperature_screen.h" -#include "interface_sounds_screen.h" -#include "interface_settings_screen.h" -#include "lock_screen.h" -#include "endstop_state_screen.h" -#include "display_tuning_screen.h" -#include "media_player_screen.h" +#include "generic/boot_screen.h" +#include "generic/about_screen.h" +#include "generic/kill_screen.h" +#include "generic/alert_dialog_box.h" +#include "generic/spinner_dialog_box.h" +#include "generic/restore_failsafe_dialog_box.h" +#include "generic/save_settings_dialog_box.h" +#include "generic/confirm_start_print_dialog_box.h" +#include "generic/confirm_abort_print_dialog_box.h" +#include "generic/confirm_user_request_alert_box.h" +#include "generic/touch_calibration_screen.h" +#include "generic/touch_registers_screen.h" +#include "generic/change_filament_screen.h" +#include "generic/move_axis_screen.h" +#include "generic/steps_screen.h" +#include "generic/feedrate_percent_screen.h" +#include "generic/max_velocity_screen.h" +#include "generic/max_acceleration_screen.h" +#include "generic/default_acceleration_screen.h" +#include "generic/temperature_screen.h" +#include "generic/interface_sounds_screen.h" +#include "generic/interface_settings_screen.h" +#include "generic/lock_screen.h" +#include "generic/endstop_state_screen.h" +#include "generic/display_tuning_screen.h" +#include "generic/media_player_screen.h" #if ENABLED(PRINTCOUNTER) - #include "statistics_screen.h" + #include "generic/statistics_screen.h" #endif #if HAS_TRINAMIC_CONFIG - #include "stepper_current_screen.h" - #include "stepper_bump_sensitivity_screen.h" + #include "generic/stepper_current_screen.h" + #include "generic/stepper_bump_sensitivity_screen.h" #endif #if HAS_MULTI_HOTEND - #include "nozzle_offsets_screen.h" + #include "generic/nozzle_offsets_screen.h" #endif #if HAS_LEVELING - #include "leveling_menu.h" + #include "generic/leveling_menu.h" #if HAS_BED_PROBE - #include "z_offset_screen.h" + #include "generic/z_offset_screen.h" #endif #if HAS_MESH - #include "bed_mesh_base.h" - #include "bed_mesh_view_screen.h" - #include "bed_mesh_edit_screen.h" + #include "generic/bed_mesh_base.h" + #include "generic/bed_mesh_view_screen.h" + #include "generic/bed_mesh_edit_screen.h" #endif #endif #if ENABLED(CALIBRATION_GCODE) - #include "confirm_auto_calibration_dialog_box.h" + #include "generic/confirm_auto_calibration_dialog_box.h" #endif #if ENABLED(BABYSTEPPING) - #include "nudge_nozzle_screen.h" + #include "generic/nudge_nozzle_screen.h" #endif #if ENABLED(BACKLASH_GCODE) - #include "backlash_compensation_screen.h" + #include "generic/backlash_compensation_screen.h" #endif #if HAS_JUNCTION_DEVIATION - #include "junction_deviation_screen.h" + #include "generic/junction_deviation_screen.h" #else - #include "jerk_screen.h" + #include "generic/jerk_screen.h" #endif #if ENABLED(CASE_LIGHT_ENABLE) - #include "case_light_screen.h" + #include "generic/case_light_screen.h" #endif #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) - #include "filament_menu.h" + #include "generic/filament_menu.h" #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) - #include "filament_runout_screen.h" + #include "generic/filament_runout_screen.h" #endif #if ENABLED(LIN_ADVANCE) - #include "linear_advance_screen.h" + #include "generic/linear_advance_screen.h" #endif #if ENABLED(SDSUPPORT) - #include "files_screen.h" + #include "generic/files_screen.h" #endif #if ENABLED(CUSTOM_MENU_MAIN) - #include "custom_user_menus.h" + #include "generic/custom_user_menus.h" #endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) - #include "developer_menu.h" - #include "confirm_erase_flash_dialog_box.h" - #include "widget_demo_screen.h" - #include "stress_test_screen.h" + #include "generic/developer_menu.h" + #include "generic/confirm_erase_flash_dialog_box.h" + #include "generic/widget_demo_screen.h" + #include "generic/stress_test_screen.h" #endif #if NUM_LANGUAGES > 1 - #include "language_menu.h" + #include "generic/language_menu.h" #endif #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp deleted file mode 100644 index 3428c38bb1..0000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp +++ /dev/null @@ -1,100 +0,0 @@ -/************************************ - * cocoa_press_unload_cartridge.cpp * - ************************************/ - -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2020 - Cocoa Press * - * * - * 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. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" -#include "screens.h" -#include "screen_data.h" - -#ifdef FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN - -using namespace ExtUI; -using namespace FTDI; -using namespace Theme; - -#define GRID_COLS 2 -#define GRID_ROWS 6 - -#define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) -#define DESCRIPTION_POS BTN_POS(1,2), BTN_SIZE(2,3) -#define CARTRIDGE_OUT_BTN_POS BTN_POS(1,5), BTN_SIZE(1,1) -#define CARTRIDGE_IN_BTN_POS BTN_POS(2,5), BTN_SIZE(1,1) -#define BACK_BTN_POS BTN_POS(1,6), BTN_SIZE(2,1) - -void UnloadCartridgeScreen::onRedraw(draw_mode_t what) { - CommandProcessor cmd; - - if (what & BACKGROUND) { - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0) - .font(font_large) - .text(TITLE_POS, GET_TEXT_F(MSG_UNLOAD_CARTRIDGE)); - draw_text_box(cmd, DESCRIPTION_POS, F( - "Press and hold the buttons below to help " - "you unlock the cartridge. After unlocking, " - "press and hold the Cartridge Out button " - "until the cartridge is sticking out of the " - "extruder enough to grip and remove. After " - "removing the cartridge, continue holding the " - "Cartridge Out button until the plunger adapter is " - "visible at the bottom of the extruder." - ), - OPT_CENTERY, font_medium); - } - - if (what & FOREGROUND) { - cmd.font(font_medium) - .colors(normal_btn) - .tag(2).button(CARTRIDGE_OUT_BTN_POS, GET_TEXT_F(MSG_CARTRIDGE_OUT)) - .tag(3).button(CARTRIDGE_IN_BTN_POS, GET_TEXT_F(MSG_CARTRIDGE_IN)) - .colors(action_btn) - .tag(1).button(BACK_BTN_POS, GET_TEXT_F(MSG_BACK)); - } -} - -bool UnloadCartridgeScreen::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - } - return true; -} - -bool UnloadCartridgeScreen::onTouchHeld(uint8_t tag) { - if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate - constexpr float increment = 0.25; - MoveAxisScreen::setManualFeedrate(E0, increment); - #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); - #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); - switch (tag) { - case 2: UI_DECREMENT_AXIS(E0); break; - case 3: UI_INCREMENT_AXIS(E0); break; - default: return false; - } - #undef UI_DECREMENT_AXIS - #undef UI_INCREMENT_AXIS - return false; -} - -#endif // FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h deleted file mode 100644 index 95a9ee47ec..0000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h +++ /dev/null @@ -1,34 +0,0 @@ -/********************************** - * cocoa_press_unload_cartridge.h * - **********************************/ - -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2020 - Cocoa Press * - * * - * 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. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#pragma once - -#define FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN -#define FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN_CLASS UnloadCartridgeScreen - -class UnloadCartridgeScreen : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static bool onTouchHeld(uint8_t tag); -}; From 588a74fd9dc5e2f2a8432528699556a65b0136d1 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 8 Jun 2021 07:09:12 +1200 Subject: [PATCH 0229/2168] expose hidden BLTOUCH setting changes (#22069) --- Marlin/src/inc/Conditionals_LCD.h | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 445cc3c067..d66ceabc19 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -713,14 +713,24 @@ #ifndef Z_PROBE_SERVO_NR #define Z_PROBE_SERVO_NR 0 #endif - #undef DEACTIVATE_SERVOS_AFTER_MOVE + #ifdef DEACTIVATE_SERVOS_AFTER_MOVE + #warning "BLTOUCH requires DEACTIVATE_SERVOS_AFTER_MOVE to be to disabled. Undefining DEACTIVATE_SERVOS_AFTER_MOVE. Please update your Configuration.h file." + #undef DEACTIVATE_SERVOS_AFTER_MOVE + #endif // Always disable probe pin inverting for BLTouch - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #if Z_MIN_PROBE_ENDSTOP_INVERTING + #warning "BLTOUCH requires Z_MIN_PROBE_ENDSTOP_INVERTING set to false. Resetting Z_MIN_PROBE_ENDSTOP_INVERTING to false. Please update your Configuration.h file." + #undef Z_MIN_PROBE_ENDSTOP_INVERTING + #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #endif + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #undef Z_MIN_ENDSTOP_INVERTING - #define Z_MIN_ENDSTOP_INVERTING false + #if Z_MIN_ENDSTOP_INVERTING + #warning "BLTOUCH requires Z_MIN_ENDSTOP_INVERTING set to false. Resetting Z_MIN_ENDSTOP_INVERTING to false. Please update your Configuration.h file." + #undef Z_MIN_ENDSTOP_INVERTING + #define Z_MIN_ENDSTOP_INVERTING false + #endif #endif #endif From 002e1d49fe7e39ca82730876f0a384bb60ce4190 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Mon, 7 Jun 2021 14:15:09 -0500 Subject: [PATCH 0230/2168] Add Laser Based I2C Ammeter Feature (#21835) --- Marlin/Configuration_adv.h | 9 +++ Marlin/src/feature/ammeter.cpp | 49 ++++++++++++++ Marlin/src/feature/ammeter.h | 44 +++++++++++++ Marlin/src/feature/spindle_laser.cpp | 8 +++ Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 23 ++++++- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 42 +++++++++++- Marlin/src/lcd/dogm/status/ammeter.h | 71 +++++++++++++++++++++ Marlin/src/lcd/dogm/status/cooler.h | 64 +++++++++---------- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 25 ++++++++ Marlin/src/libs/numtostr.cpp | 9 +++ Marlin/src/libs/numtostr.h | 3 + ini/features.ini | 1 + 12 files changed, 314 insertions(+), 34 deletions(-) create mode 100644 Marlin/src/feature/ammeter.cpp create mode 100644 Marlin/src/feature/ammeter.h create mode 100644 Marlin/src/lcd/dogm/status/ammeter.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index efde7cde19..50bc85801f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3283,6 +3283,15 @@ //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin #endif + // + // Laser I2C Ammeter (High precision INA226 low/high side module) + // + //#define I2C_AMMETER + #if ENABLED(I2C_AMMETER) + #define I2C_AMMETER_IMAX .1 // Calibration value for the expected current range in Amps (use float e.g. 1.0) + #define I2C_AMMETER_SHUNT_RESISTOR .1 // Calibration shunt resistor value in ohms + #endif + //#define SPINDLE_SERVO // A servo converting an angle to spindle power #ifdef SPINDLE_SERVO #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control diff --git a/Marlin/src/feature/ammeter.cpp b/Marlin/src/feature/ammeter.cpp new file mode 100644 index 0000000000..01e1084474 --- /dev/null +++ b/Marlin/src/feature/ammeter.cpp @@ -0,0 +1,49 @@ + /** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../inc/MarlinConfig.h" + +#if ENABLED(I2C_AMMETER) + #include "ammeter.h" + + INA226 ina; + + Ammeter ammeter; + + float Ammeter::scale; + float Ammeter::current; + + void Ammeter::init() { + ina.begin(); + ina.configure(INA226_AVERAGES_16, INA226_BUS_CONV_TIME_1100US, INA226_SHUNT_CONV_TIME_1100US, INA226_MODE_SHUNT_BUS_CONT); + ina.calibrate(I2C_AMMETER_SHUNT_RESISTOR,I2C_AMMETER_IMAX); + } + + float Ammeter::read() { + scale = 1; + current = ina.readShuntCurrent(); + if (current <= .0001) current = 0; // Cleanup lsb bit amplification errors + if (current < .1) scale = 1000; + return current * scale; + } + +#endif //I2C_AMMETER diff --git a/Marlin/src/feature/ammeter.h b/Marlin/src/feature/ammeter.h new file mode 100644 index 0000000000..cc60a2d28a --- /dev/null +++ b/Marlin/src/feature/ammeter.h @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../inc/MarlinConfigPre.h" + +#include +#include + +#ifndef I2C_AMMETER_IMAX + #define I2C_AMMETER_IMAX .500 // Calibration range 500 Milli Amps +#endif + +class Ammeter { +private: + static float scale; + +public: + static float current; + static void init(); + static float read(); + +}; + +extern Ammeter ammeter; diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 100b7c4b26..58dc5ef101 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -34,6 +34,10 @@ #include "../module/servo.h" #endif +#if ENABLED(I2C_AMMETER) + #include "../feature/ammeter.h" +#endif + SpindleLaser cutter; uint8_t SpindleLaser::power; #if ENABLED(LASER_FEATURE) @@ -74,6 +78,10 @@ void SpindleLaser::init() { #if ENABLED(AIR_ASSIST) OUT_WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); // Init Air Assist OFF #endif + #if ENABLED(I2C_AMMETER) + ammeter.init(); // Init I2C Ammeter + #endif + } #if ENABLED(SPINDLE_LASER_PWM) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 50c80c9fa0..ab3d415c15 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -50,6 +50,10 @@ #include "../../feature/cooler.h" #endif +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + #if ENABLED(AUTO_BED_LEVELING_UBL) #include "../../feature/bedlevel/bedlevel.h" #endif @@ -588,12 +592,26 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { #if ENABLED(LASER_COOLANT_FLOW_METER) FORCE_INLINE void _draw_flowmeter_status() { - lcd_put_u8str("~ "); + lcd_put_u8str("~"); lcd_put_u8str(ftostr11ns(cooler.flowrate)); lcd_put_wchar('L'); } #endif +#if ENABLED(I2C_AMMETER) + FORCE_INLINE void _draw_ammeter_status() { + lcd_put_u8str(" "); + ammeter.read(); + if (ammeter.current <= .999) { + lcd_put_u8str(ftostr3ns(ammeter.current)); + lcd_put_u8str("mA"); + } else { + lcd_put_u8str(ftostr12ns(ammeter.current)); + lcd_put_wchar('A'); + } + } +#endif + FORCE_INLINE void _draw_bed_status(const bool blink) { _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); } @@ -835,6 +853,9 @@ void MarlinUI::draw_status_screen() { #if ENABLED(LASER_COOLANT_FLOW_METER) _draw_flowmeter_status(); #endif + #if ENABLED(I2C_AMMETER) + _draw_ammeter_status(); + #endif #endif // LCD_WIDTH >= 20 diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 61d22a28ec..db0b66777d 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -107,7 +107,18 @@ #define STATUS_FLOWMETER_BYTEWIDTH BW(STATUS_FLOWMETER_WIDTH) #endif - +// +// Laser Ammeter +// +#if !STATUS_AMMETER_WIDTH && ENABLED(I2C_AMMETER) + #include "status/ammeter.h" +#endif +#ifndef STATUS_AMMETER_WIDTH + #define STATUS_AMMETER_WIDTH 0 +#endif +#ifndef STATUS_AMMETER_BYTEWIDTH + #define STATUS_AMMETER_BYTEWIDTH BW(STATUS_AMMETER_WIDTH) +#endif // // Bed @@ -603,6 +614,32 @@ #endif #endif +#if ENABLED(I2C_AMMETER) + #if STATUS_AMMETER_WIDTH + + #ifndef STATUS_AMMETER_X + #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) + #endif + + #ifndef STATUS_AMMETER_HEIGHT + #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp1) / (STATUS_AMMETER_BYTEWIDTH)) + #endif + + #ifndef STATUS_AMMETER_Y + #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) + #endif + + #ifndef STATUS_AMMETER_TEXT_X + #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) + #endif + + static_assert( + sizeof(status_ammeter_bmp1) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), + "Status ammeter bitmap (status_ammeter_bmp1) dimensions don't match data." + ); + #endif +#endif + // // Bed Bitmap Properties // @@ -696,6 +733,9 @@ #if ENABLED(LASER_COOLANT_FLOW_METER) #define DO_DRAW_FLOWMETER 1 #endif +#if ENABLED(I2C_AMMETER) + #define DO_DRAW_AMMETER 1 +#endif #if HAS_TEMP_CHAMBER && STATUS_CHAMBER_WIDTH && HOTENDS <= 4 #define DO_DRAW_CHAMBER 1 diff --git a/Marlin/src/lcd/dogm/status/ammeter.h b/Marlin/src/lcd/dogm/status/ammeter.h new file mode 100644 index 0000000000..c98d1eb401 --- /dev/null +++ b/Marlin/src/lcd/dogm/status/ammeter.h @@ -0,0 +1,71 @@ +/** + * 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 + +// +// lcd/dogm/status/ammeter.h - Status Screen Laser Ammeter bitmaps +// +#if ENABLED(I2C_AMMETER) + + #define STATUS_AMMETER_WIDTH 20 + + const unsigned char status_ammeter_bmp_mA[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000110,B00100000, + B00010000,B00001001,B00100000, + B00100000,B00001001,B00010000, + B00100011,B01001111,B00010000, + B11100010,B10101001,B00011100, + B00100010,B10101001,B00010000, + B00100010,B10101001,B00010000, + B00010000,B00000000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000 + }; + +const unsigned char status_ammeter_bmp_A[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000000,B00100000, + B00010000,B00110000,B00100000, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B11100000,B01111000,B00011100, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B00010000,B01001000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000, +}; + +#endif diff --git a/Marlin/src/lcd/dogm/status/cooler.h b/Marlin/src/lcd/dogm/status/cooler.h index 6cf67a4b62..65c28ec28e 100644 --- a/Marlin/src/lcd/dogm/status/cooler.h +++ b/Marlin/src/lcd/dogm/status/cooler.h @@ -29,40 +29,40 @@ #define STATUS_COOLER_WIDTH 22 const unsigned char status_cooler_bmp2[] PROGMEM = { - B00000100,B00000010,B00000000, - B00000100,B10010010,B01000000, - B00010101,B00001010,B10000000, - B00001110,B00000111,B00000000, - B00111111,B10111111,B11000000, - B00001110,B00000111,B00000000, - B00010101,B00001010,B10000000, - B00100100,B00100010,B01000000, - B00000100,B00100000,B00000000, - B00000001,B00100100,B00000000, - B00000000,B10101000,B00000000, - B00000000,B01110000,B00000000, - B00000111,B11111111,B00000000, - B00000000,B01110000,B00000000, - B00000000,B10101000,B00000000, - B00000001,B00100100,B00000000 + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000011,B10000001,B11000000, + B00001111,B11101111,B11110000, + B00000011,B10000001,B11000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00011100,B00000000, + B00000001,B11111111,B11000000, + B00000000,B00011100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 }; const unsigned char status_cooler_bmp1[] PROGMEM = { - B00000100,B00000010,B00000000, - B00000100,B10010010,B01000000, - B00010101,B00001010,B10000000, - B00001010,B00000101,B00000000, - B00110001,B11011000,B11000000, - B00001010,B00000101,B00000000, - B00010101,B00001010,B10000000, - B00100100,B00100010,B01000000, - B00000100,B00100000,B00000000, - B00000001,B00100100,B00000000, - B00000000,B10101000,B00000000, - B00000000,B01010000,B00000000, - B00000111,B10001111,B00000000, - B00000000,B01010000,B00000000, - B00000000,B10101000,B00000000, - B00000001,B00100100,B00000000 + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000010,B10000001,B01000000, + B00001100,B01110110,B00110000, + B00000010,B10000001,B01000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00010100,B00000000, + B00000001,B11100011,B11000000, + B00000000,B00010100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 }; #endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index f05958e675..00e8af66e2 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -205,6 +205,14 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co } #endif +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_centered_current(const float current, const uint8_t tx, const uint8_t ty) { + const char *str = ftostr31ns(current); + 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]); + } +#endif + #if DO_DRAW_HOTENDS // Draw hotend bitmap with current and target temperatures @@ -404,6 +412,13 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co } #endif +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_ammeter_status() { + if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) + _draw_centered_current(ammeter.read(), STATUS_AMMETER_TEXT_X, 28); + } +#endif + // // Before homing, blink '123' <-> '???'. // Homed but unknown... '123' <-> ' '. @@ -677,6 +692,13 @@ void MarlinUI::draw_status_screen() { u8g.drawBitmapP(STATUS_FLOWMETER_X, flowmetery, STATUS_FLOWMETER_BYTEWIDTH, flowmeterh, blink && cooler.flowpulses ? status_flowmeter_bmp2 : status_flowmeter_bmp1); #endif + // Laser Ammeter + #if DO_DRAW_AMMETER + const uint8_t ammetery = STATUS_AMMETER_Y(status_ammeter_bmp_mA), + ammeterh = STATUS_AMMETER_HEIGHT(status_ammeter_bmp_mA); + if (PAGE_CONTAINS(ammetery, ammetery + ammeterh - 1)) + u8g.drawBitmapP(STATUS_AMMETER_X, ammetery, STATUS_AMMETER_BYTEWIDTH, ammeterh, (ammeter.current < .1) ? status_ammeter_bmp_mA : status_ammeter_bmp_A); + #endif // Heated Bed TERN_(DO_DRAW_BED, _draw_bed_status(blink)); @@ -690,6 +712,9 @@ void MarlinUI::draw_status_screen() { // Flowmeter TERN_(DO_DRAW_FLOWMETER, _draw_flowmeter_status()); + // Flowmeter + TERN_(DO_DRAW_AMMETER, _draw_ammeter_status()); + // Fan, if a bitmap was provided #if DO_DRAW_FAN if (PAGE_CONTAINS(STATUS_FAN_TEXT_Y - INFO_FONT_ASCENT, STATUS_FAN_TEXT_Y - 1)) { diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 1e1ac05710..a1e320844a 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -217,6 +217,15 @@ const char* ftostr41ns(const_float_t f) { return &conv[2]; } +// Convert unsigned float to string with 123 format +const char* ftostr3ns(const_float_t f) { + const long i = UINTFLOAT(f, 3); + conv[4] = DIGIMOD(i, 100); + conv[5] = DIGIMOD(i, 10); + conv[6] = DIGIMOD(i, 1); + return &conv[4]; +} + // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t f) { if (f <= -10 || f >= 100) return ftostr52(f); // -23.45 / 123.45 diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index b058f3cdf6..5ebf6e1b22 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -74,6 +74,9 @@ const char* ftostr31ns(const_float_t x); // Convert unsigned float to string with 123.4 format const char* ftostr41ns(const_float_t x); +// Convert unsigned float to string with 123 format +const char* ftostr3ns(const_float_t x); + // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t x); diff --git a/ini/features.ini b/ini/features.ini index f8f995c69f..15f6c2a138 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -30,6 +30,7 @@ HAS_L64XX = Arduino-L6470@0.8.0 NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 +I2C_AMMETER = peterus/INA226Lib@1.1.2 USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 From 420d5b0b412067f806da2ccfc989ae1b6bacc7df Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 8 Jun 2021 01:26:19 +0000 Subject: [PATCH 0231/2168] [cron] Bump distribution date (2021-06-08) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c531cf8c65..04a823e0c8 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 "2021-06-07" + #define STRING_DISTRIBUTION_DATE "2021-06-08" #endif /** From d320545066676338d4a0142268931bb66eedfccc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 8 Jun 2021 07:51:28 -0500 Subject: [PATCH 0232/2168] =?UTF-8?q?=F0=9F=8E=A8=20Laser=20Ammeter=20foll?= =?UTF-8?q?owup=20(#22079)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #21835 --- Marlin/Configuration_adv.h | 21 ++++---- Marlin/src/HAL/STM32/eeprom_flash.cpp | 2 +- Marlin/src/feature/ammeter.cpp | 43 ++++++++------- Marlin/src/feature/ammeter.h | 13 ++--- Marlin/src/feature/spindle_laser.cpp | 3 +- Marlin/src/inc/Conditionals_LCD.h | 4 ++ Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 31 ++++------- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 60 ++++++++++----------- Marlin/src/lcd/dogm/status/ammeter.h | 11 ++-- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 4 +- Marlin/src/libs/numtostr.cpp | 9 ---- Marlin/src/libs/numtostr.h | 3 -- buildroot/tests/mega2560 | 2 +- 13 files changed, 90 insertions(+), 116 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 50bc85801f..5bd3c51603 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3283,15 +3283,6 @@ //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin #endif - // - // Laser I2C Ammeter (High precision INA226 low/high side module) - // - //#define I2C_AMMETER - #if ENABLED(I2C_AMMETER) - #define I2C_AMMETER_IMAX .1 // Calibration value for the expected current range in Amps (use float e.g. 1.0) - #define I2C_AMMETER_SHUNT_RESISTOR .1 // Calibration shunt resistor value in ohms - #endif - //#define SPINDLE_SERVO // A servo converting an angle to spindle power #ifdef SPINDLE_SERVO #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control @@ -3424,8 +3415,18 @@ #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop #endif + + // + // Laser I2C Ammeter (High precision INA226 low/high side module) + // + //#define I2C_AMMETER + #if ENABLED(I2C_AMMETER) + #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range + #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value + #endif + #endif -#endif +#endif // SPINDLE_FEATURE || LASER_FEATURE /** * Synchronous Laser Control with M106/M107 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 3d06b172bd..dfeae9e9e5 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -30,7 +30,7 @@ // Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 // Use EEPROM.h for compatibility, for now. -#include +#include /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that diff --git a/Marlin/src/feature/ammeter.cpp b/Marlin/src/feature/ammeter.cpp index 01e1084474..71b84f1121 100644 --- a/Marlin/src/feature/ammeter.cpp +++ b/Marlin/src/feature/ammeter.cpp @@ -1,4 +1,4 @@ - /** +/** * Marlin 3D Printer Firmware * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * @@ -23,27 +23,32 @@ #include "../inc/MarlinConfig.h" #if ENABLED(I2C_AMMETER) - #include "ammeter.h" - INA226 ina; +#include "ammeter.h" - Ammeter ammeter; +#ifndef I2C_AMMETER_IMAX + #define I2C_AMMETER_IMAX 0.500 // Calibration range 500 Milliamps +#endif - float Ammeter::scale; - float Ammeter::current; +INA226 ina; - void Ammeter::init() { - ina.begin(); - ina.configure(INA226_AVERAGES_16, INA226_BUS_CONV_TIME_1100US, INA226_SHUNT_CONV_TIME_1100US, INA226_MODE_SHUNT_BUS_CONT); - ina.calibrate(I2C_AMMETER_SHUNT_RESISTOR,I2C_AMMETER_IMAX); - } +Ammeter ammeter; - float Ammeter::read() { - scale = 1; - current = ina.readShuntCurrent(); - if (current <= .0001) current = 0; // Cleanup lsb bit amplification errors - if (current < .1) scale = 1000; - return current * scale; - } +float Ammeter::scale; +float Ammeter::current; -#endif //I2C_AMMETER +void Ammeter::init() { + ina.begin(); + ina.configure(INA226_AVERAGES_16, INA226_BUS_CONV_TIME_1100US, INA226_SHUNT_CONV_TIME_1100US, INA226_MODE_SHUNT_BUS_CONT); + ina.calibrate(I2C_AMMETER_SHUNT_RESISTOR, I2C_AMMETER_IMAX); +} + +float Ammeter::read() { + scale = 1; + current = ina.readShuntCurrent(); + if (current <= 0.0001f) current = 0; // Clean up least-significant-bit amplification errors + if (current < 0.1f) scale = 1000; + return current * scale; +} + +#endif // I2C_AMMETER diff --git a/Marlin/src/feature/ammeter.h b/Marlin/src/feature/ammeter.h index cc60a2d28a..86f09bb9a1 100644 --- a/Marlin/src/feature/ammeter.h +++ b/Marlin/src/feature/ammeter.h @@ -26,19 +26,14 @@ #include #include -#ifndef I2C_AMMETER_IMAX - #define I2C_AMMETER_IMAX .500 // Calibration range 500 Milli Amps -#endif - class Ammeter { private: - static float scale; + static float scale; public: - static float current; - static void init(); - static float read(); - + static float current; + static void init(); + static float read(); }; extern Ammeter ammeter; diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 58dc5ef101..539fafeb34 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -79,9 +79,8 @@ void SpindleLaser::init() { OUT_WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); // Init Air Assist OFF #endif #if ENABLED(I2C_AMMETER) - ammeter.init(); // Init I2C Ammeter + ammeter.init(); // Init I2C Ammeter #endif - } #if ENABLED(SPINDLE_LASER_PWM) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index d66ceabc19..9e87589ca8 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -405,6 +405,10 @@ #endif +#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) + #define DETECT_I2C_LCD_DEVICE 1 +#endif + #ifndef STD_ENCODER_PULSES_PER_STEP #if ENABLED(TOUCH_SCREEN) #define STD_ENCODER_PULSES_PER_STEP 2 diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index ab3d415c15..0c87c3dc3f 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -68,11 +68,7 @@ #elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) - LCD_CLASS lcd(LCD_I2C_ADDRESS - #ifdef DETECT_DEVICE - , 1 - #endif - ); + LCD_CLASS lcd(LCD_I2C_ADDRESS OPTARG(DETECT_I2C_LCD_DEVICE, 1)); #elif ENABLED(LCD_I2C_TYPE_PCA8574) @@ -380,11 +376,7 @@ void MarlinUI::init_lcd() { } bool MarlinUI::detected() { - return (true - #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE) - && lcd.LcdDetected() == 1 - #endif - ); + return TERN1(DETECT_I2C_LCD_DEVICE, lcd.LcdDetected() == 1); } #if HAS_SLOW_BUTTONS @@ -602,10 +594,11 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { FORCE_INLINE void _draw_ammeter_status() { lcd_put_u8str(" "); ammeter.read(); - if (ammeter.current <= .999) { - lcd_put_u8str(ftostr3ns(ammeter.current)); + if (ammeter.current <= 0.999f) { + lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); lcd_put_u8str("mA"); - } else { + } + else { lcd_put_u8str(ftostr12ns(ammeter.current)); lcd_put_wchar('A'); } @@ -847,15 +840,9 @@ void MarlinUI::draw_status_screen() { #endif #endif - #if HAS_COOLER - _draw_cooler_status('*', blink); - #endif - #if ENABLED(LASER_COOLANT_FLOW_METER) - _draw_flowmeter_status(); - #endif - #if ENABLED(I2C_AMMETER) - _draw_ammeter_status(); - #endif + TERN_(HAS_COOLER, _draw_cooler_status('*', blink)); + TERN_(LASER_COOLANT_FLOW_METER, _draw_flowmeter_status()); + TERN_(I2C_AMMETER, _draw_ammeter_status()); #endif // LCD_WIDTH >= 20 diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index db0b66777d..6aa2bab0da 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -110,14 +110,13 @@ // // Laser Ammeter // -#if !STATUS_AMMETER_WIDTH && ENABLED(I2C_AMMETER) - #include "status/ammeter.h" -#endif -#ifndef STATUS_AMMETER_WIDTH - #define STATUS_AMMETER_WIDTH 0 -#endif -#ifndef STATUS_AMMETER_BYTEWIDTH - #define STATUS_AMMETER_BYTEWIDTH BW(STATUS_AMMETER_WIDTH) +#if ENABLED(I2C_AMMETER) + #if !STATUS_AMMETER_WIDTH + #include "status/ammeter.h" + #endif + #ifndef STATUS_AMMETER_WIDTH + #define STATUS_AMMETER_WIDTH 0 + #endif #endif // @@ -614,30 +613,29 @@ #endif #endif -#if ENABLED(I2C_AMMETER) - #if STATUS_AMMETER_WIDTH - - #ifndef STATUS_AMMETER_X - #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) - #endif - - #ifndef STATUS_AMMETER_HEIGHT - #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp1) / (STATUS_AMMETER_BYTEWIDTH)) - #endif - - #ifndef STATUS_AMMETER_Y - #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) - #endif - - #ifndef STATUS_AMMETER_TEXT_X - #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) - #endif - - static_assert( - sizeof(status_ammeter_bmp1) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), - "Status ammeter bitmap (status_ammeter_bmp1) dimensions don't match data." - ); +// +// I2C Laser Ammeter +// +#if ENABLED(I2C_AMMETER) && STATUS_AMMETER_WIDTH + #ifndef STATUS_AMMETER_BYTEWIDTH + #define STATUS_AMMETER_BYTEWIDTH BW(STATUS_AMMETER_WIDTH) #endif + #ifndef STATUS_AMMETER_X + #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) + #endif + #ifndef STATUS_AMMETER_HEIGHT + #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp1) / (STATUS_AMMETER_BYTEWIDTH)) + #endif + #ifndef STATUS_AMMETER_Y + #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) + #endif + #ifndef STATUS_AMMETER_TEXT_X + #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) + #endif + static_assert( + sizeof(status_ammeter_bmp1) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), + "Status ammeter bitmap (status_ammeter_bmp1) dimensions don't match data." + ); #endif // diff --git a/Marlin/src/lcd/dogm/status/ammeter.h b/Marlin/src/lcd/dogm/status/ammeter.h index c98d1eb401..d99ea6949a 100644 --- a/Marlin/src/lcd/dogm/status/ammeter.h +++ b/Marlin/src/lcd/dogm/status/ammeter.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -24,11 +24,10 @@ // // lcd/dogm/status/ammeter.h - Status Screen Laser Ammeter bitmaps // -#if ENABLED(I2C_AMMETER) - #define STATUS_AMMETER_WIDTH 20 +#define STATUS_AMMETER_WIDTH 20 - const unsigned char status_ammeter_bmp_mA[] PROGMEM = { +const unsigned char status_ammeter_bmp_mA[] PROGMEM = { B00000000,B11111100,B00000000, B00000011,B00000011,B00000000, B00000100,B00000000,B10000000, @@ -46,7 +45,7 @@ B00000100,B00000000,B10000000, B00000011,B00000011,B00000000, B00000000,B11111100,B00000000 - }; +}; const unsigned char status_ammeter_bmp_A[] PROGMEM = { B00000000,B11111100,B00000000, @@ -67,5 +66,3 @@ const unsigned char status_ammeter_bmp_A[] PROGMEM = { B00000011,B00000011,B00000000, B00000000,B11111100,B00000000, }; - -#endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 00e8af66e2..8309c3a00e 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -207,7 +207,7 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #if DO_DRAW_AMMETER FORCE_INLINE void _draw_centered_current(const float current, const uint8_t tx, const uint8_t ty) { - const char *str = ftostr31ns(current); + const char *str = ftostr31ns(current); 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]); } @@ -697,7 +697,7 @@ void MarlinUI::draw_status_screen() { const uint8_t ammetery = STATUS_AMMETER_Y(status_ammeter_bmp_mA), ammeterh = STATUS_AMMETER_HEIGHT(status_ammeter_bmp_mA); if (PAGE_CONTAINS(ammetery, ammetery + ammeterh - 1)) - u8g.drawBitmapP(STATUS_AMMETER_X, ammetery, STATUS_AMMETER_BYTEWIDTH, ammeterh, (ammeter.current < .1) ? status_ammeter_bmp_mA : status_ammeter_bmp_A); + u8g.drawBitmapP(STATUS_AMMETER_X, ammetery, STATUS_AMMETER_BYTEWIDTH, ammeterh, (ammeter.current < 0.1f) ? status_ammeter_bmp_mA : status_ammeter_bmp_A); #endif // Heated Bed diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index a1e320844a..1e1ac05710 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -217,15 +217,6 @@ const char* ftostr41ns(const_float_t f) { return &conv[2]; } -// Convert unsigned float to string with 123 format -const char* ftostr3ns(const_float_t f) { - const long i = UINTFLOAT(f, 3); - conv[4] = DIGIMOD(i, 100); - conv[5] = DIGIMOD(i, 10); - conv[6] = DIGIMOD(i, 1); - return &conv[4]; -} - // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t f) { if (f <= -10 || f >= 100) return ftostr52(f); // -23.45 / 123.45 diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index 5ebf6e1b22..b058f3cdf6 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -74,9 +74,6 @@ const char* ftostr31ns(const_float_t x); // Convert unsigned float to string with 123.4 format const char* ftostr41ns(const_float_t x); -// Convert unsigned float to string with 123 format -const char* ftostr3ns(const_float_t x); - // Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t x); diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index ecf82267f4..3ddb68fe88 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -193,7 +193,7 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_C MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER I2C_AMMETER exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" From 70b80fcd16722ecbd8ada54c0fb867041cb5f1fd Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 9 Jun 2021 10:43:39 +1200 Subject: [PATCH 0233/2168] =?UTF-8?q?=F0=9F=8E=A8=20IJK=20auto-allocation?= =?UTF-8?q?=20(#22075)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins_postprocess.h | 212 +++++++++++++++++++++++++++++ 1 file changed, 212 insertions(+) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 33b78a4d11..bd52e30454 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -809,6 +809,8 @@ #undef Z3_DIAG_PIN #endif #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) +#else + #define Z4_E_INDEX Z3_E_INDEX #endif #ifndef Z3_CS_PIN @@ -876,6 +878,9 @@ #endif #undef Z4_DIAG_PIN #endif + #define I_E_INDEX INCREMENT(Z4_E_INDEX) +#else + #define I_E_INDEX Z4_E_INDEX #endif #ifndef Z4_CS_PIN @@ -891,6 +896,213 @@ #define Z4_MS3_PIN -1 #endif +#if LINEAR_AXES >= 4 + #ifndef I_STEP_PIN + #define I_STEP_PIN _EPIN(I_E_INDEX, STEP) + #define I_DIR_PIN _EPIN(I_E_INDEX, DIR) + #define I_ENABLE_PIN _EPIN(I_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(I_STEP) + #error "No E stepper plug left for I!" + #endif + #endif + #if AXIS_HAS_SPI(I) + #ifndef I_CS_PIN + #define I_CS_PIN _EPIN(I_E_INDEX, CS) + #endif + #endif + #ifndef I_MS1_PIN + #define I_MS1_PIN _EPIN(I_E_INDEX, MS1) + #endif + #ifndef I_MS2_PIN + #define I_MS2_PIN _EPIN(I_E_INDEX, MS2) + #endif + #ifndef I_MS3_PIN + #define I_MS3_PIN _EPIN(I_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(I) + #ifndef I_SERIAL_TX_PIN + #define I_SERIAL_TX_PIN _EPIN(I_E_INDEX, SERIAL_TX) + #endif + #ifndef I_SERIAL_RX_PIN + #define I_SERIAL_RX_PIN _EPIN(I_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(I_USE_ENDSTOP) && defined(I_STALL_SENSITIVITY) && _PEXI(I_E_INDEX, DIAG) + #define I_DIAG_PIN _EPIN(I_E_INDEX, DIAG) + #if DIAG_REMAPPED(I, X_MIN) + #define I_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(I, Y_MIN) + #define I_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(I, Z_MIN) + #define I_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(I, X_MAX) + #define I_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(I, Y_MAX) + #define I_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define I_USE_ENDSTOP _ZMAX_ + #else + #define _I_USE_ENDSTOP(P) _E##P##_DIAG_ + #define I_USE_ENDSTOP _I_USE_ENDSTOP(I_E_INDEX) + #endif + #undef I_DIAG_PIN + #endif + #define J_E_INDEX INCREMENT(I_E_INDEX) +#else + #define J_E_INDEX I_E_INDEX +#endif + +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef I_MS1_PIN + #define I_MS1_PIN -1 +#endif +#ifndef I_MS2_PIN + #define I_MS2_PIN -1 +#endif +#ifndef I_MS3_PIN + #define I_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 5 + #ifndef J_STEP_PIN + #define J_STEP_PIN _EPIN(J_E_INDEX, STEP) + #define J_DIR_PIN _EPIN(J_E_INDEX, DIR) + #define J_ENABLE_PIN _EPIN(J_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(J_STEP) + #error "No E stepper plug left for J!" + #endif + #endif + #if AXIS_HAS_SPI(J) + #ifndef J_CS_PIN + #define J_CS_PIN _EPIN(J_E_INDEX, CS) + #endif + #endif + #ifndef J_MS1_PIN + #define J_MS1_PIN _EPIN(J_E_INDEX, MS1) + #endif + #ifndef J_MS2_PIN + #define J_MS2_PIN _EPIN(J_E_INDEX, MS2) + #endif + #ifndef J_MS3_PIN + #define J_MS3_PIN _EPIN(J_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(J) + #ifndef J_SERIAL_TX_PIN + #define J_SERIAL_TX_PIN _EPIN(J_E_INDEX, SERIAL_TX) + #endif + #ifndef J_SERIAL_RX_PIN + #define J_SERIAL_RX_PIN _EPIN(J_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(J_USE_ENDSTOP) && defined(J_STALL_SENSITIVITY) && _PEXI(J_E_INDEX, DIAG) + #define J_DIAG_PIN _EPIN(J_E_INDEX, DIAG) + #if DIAG_REMAPPED(J, X_MIN) + #define J_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(J, Y_MIN) + #define J_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(J, Z_MIN) + #define J_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(J, X_MAX) + #define J_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(J, Y_MAX) + #define J_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define J_USE_ENDSTOP _ZMAX_ + #else + #define _J_USE_ENDSTOP(P) _E##P##_DIAG_ + #define J_USE_ENDSTOP _J_USE_ENDSTOP(J_E_INDEX) + #endif + #undef J_DIAG_PIN + #endif + #define K_E_INDEX INCREMENT(J_E_INDEX) +#else + #define K_E_INDEX J_E_INDEX +#endif + +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef J_MS1_PIN + #define J_MS1_PIN -1 +#endif +#ifndef J_MS2_PIN + #define J_MS2_PIN -1 +#endif +#ifndef J_MS3_PIN + #define J_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 6 + #ifndef K_STEP_PIN + #define K_STEP_PIN _EPIN(K_E_INDEX, STEP) + #define K_DIR_PIN _EPIN(K_E_INDEX, DIR) + #define K_ENABLE_PIN _EPIN(K_E_INDEX, ENABLE) + #if K_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(K_STEP) + #error "No E stepper plug left for K!" + #endif + #endif + #if AXIS_HAS_SPI(K) + #ifndef K_CS_PIN + #define K_CS_PIN _EPIN(K_E_INDEX, CS) + #endif + #endif + #ifndef K_MS1_PIN + #define K_MS1_PIN _EPIN(K_E_INDEX, MS1) + #endif + #ifndef K_MS2_PIN + #define K_MS2_PIN _EPIN(K_E_INDEX, MS2) + #endif + #ifndef K_MS3_PIN + #define K_MS3_PIN _EPIN(K_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(K) + #ifndef K_SERIAL_TX_PIN + #define K_SERIAL_TX_PIN _EPIN(K_E_INDEX, SERIAL_TX) + #endif + #ifndef K_SERIAL_RX_PIN + #define K_SERIAL_RX_PIN _EPIN(K_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(K_USE_ENDSTOP) && defined(K_STALL_SENSITIVITY) && _PEXI(K_E_INDEX, DIAG) + #define K_DIAG_PIN _EPIN(K_E_INDEX, DIAG) + #if DIAG_REMAPPED(K, X_MIN) + #define K_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(K, Y_MIN) + #define K_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(K, Z_MIN) + #define K_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(K, X_MAX) + #define K_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(K, Y_MAX) + #define K_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(K, Z_MAX) + #define K_USE_ENDSTOP _ZMAX_ + #else + #define _K_USE_ENDSTOP(P) _E##P##_DIAG_ + #define K_USE_ENDSTOP _K_USE_ENDSTOP(K_E_INDEX) + #endif + #undef K_DIAG_PIN + #endif +#endif + +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif +#ifndef K_MS1_PIN + #define K_MS1_PIN -1 +#endif +#ifndef K_MS2_PIN + #define K_MS2_PIN -1 +#endif +#ifndef K_MS3_PIN + #define K_MS3_PIN -1 +#endif + // // Disable unused endstop / probe pins // From 7c5e3b9071f2ca108ae636dff72b9558479950e4 Mon Sep 17 00:00:00 2001 From: Kyle Repinski Date: Tue, 8 Jun 2021 18:56:16 -0500 Subject: [PATCH 0234/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20small/huge=20I2C?= =?UTF-8?q?=20EEPROM=20address=20(#22081)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/eeprom_if_i2c.cpp | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index 27f0233562..6b559e234b 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -61,11 +61,24 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE // Public functions // ------------------------ +#define SMALL_EEPROM (MARLIN_EEPROM_SIZE <= 2048) + +// Combine Address high bits into the device address on <=16Kbit (2K) and >512Kbit (64K) EEPROMs. +// Note: MARLIN_EEPROM_SIZE is specified in bytes, whereas EEPROM model numbers refer to bits. +// e.g., The "16" in BL24C16 indicates a 16Kbit (2KB) size. +static uint8_t _eeprom_calc_device_address(uint8_t * const pos) { + const unsigned eeprom_address = (unsigned)pos; + return (SMALL_EEPROM || MARLIN_EEPROM_SIZE > 65536) + ? uint8_t(eeprom_device_address | ((eeprom_address >> (SMALL_EEPROM ? 8 : 16)) & 0x07)) + : eeprom_device_address; +} + static void _eeprom_begin(uint8_t * const pos) { const unsigned eeprom_address = (unsigned)pos; - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // Address High - Wire.write(int(eeprom_address & 0xFF)); // Address Low + Wire.beginTransmission(_eeprom_calc_device_address(pos)); + if (!SMALL_EEPROM) + Wire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed + Wire.write(uint8_t(eeprom_address & 0xFF)); // Address Low } void eeprom_write_byte(uint8_t *pos, uint8_t value) { @@ -81,7 +94,7 @@ void eeprom_write_byte(uint8_t *pos, uint8_t value) { uint8_t eeprom_read_byte(uint8_t *pos) { _eeprom_begin(pos); Wire.endTransmission(); - Wire.requestFrom(eeprom_device_address, (byte)1); + Wire.requestFrom(_eeprom_calc_device_address(pos), (byte)1); return Wire.available() ? Wire.read() : 0xFF; } From 77496c8235dab5182312652b4dc0b6d0f182cf30 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 8 Jun 2021 19:55:27 -0500 Subject: [PATCH 0235/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Optimize=20Sensi?= =?UTF-8?q?tive=20Pins=20array=20(except=20STM32)=20(#22080)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/LINUX/include/pinmapping.cpp | 37 ----------- Marlin/src/HAL/LINUX/include/pinmapping.h | 28 ++++---- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_adv.h | 3 + Marlin/src/MarlinCore.cpp | 9 ++- Marlin/src/pins/sensitive_pins.h | 72 +++++++++++++++------ 7 files changed, 83 insertions(+), 70 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index e24b923ef0..a5896a0e97 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -186,7 +186,7 @@ inline void HAL_adc_init() { #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define HAL_SENSITIVE_PINS 0, 1 +#define HAL_SENSITIVE_PINS 0, 1, #ifdef __AVR_AT90USB1286__ #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp index 870ab3a96e..5823668cd5 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp +++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp @@ -25,43 +25,6 @@ #include "../../../gcode/parser.h" -uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; - -// Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p) { - return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); -} - -// Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin) { - return pin; -} - -// Test whether the pin is valid -bool VALID_PIN(const pin_t p) { - return WITHIN(p, 0, NUM_DIGITAL_PINS); -} - -// Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { - return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); -} - -// Test whether the pin is PWM -bool PWM_PIN(const pin_t p) { - return false; -} - -// Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p) { - return false; -} - -// Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind) { - return ind; -} - int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { return parser.intval(code, dval); } diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h index 98f4b812e8..3751ae0027 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.h +++ b/Marlin/src/HAL/LINUX/include/pinmapping.h @@ -34,26 +34,32 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16; #define HAL_SENSITIVE_PINS +constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; + // Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p); - -// Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin); - -// Test whether the pin is valid -bool VALID_PIN(const pin_t p); +constexpr pin_t analogInputToDigitalPin(const int8_t p) { + return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); +} // Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p); +constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { + return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); +} + +// Return the index of a pin number +constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; } + +// Test whether the pin is valid +constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); } // Test whether the pin is PWM -bool PWM_PIN(const pin_t p); +constexpr bool PWM_PIN(const pin_t p) { return false; } // Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p); +constexpr bool INTERRUPT_PIN(const pin_t p) { return false; } // Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind); +constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; } // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 85e8933920..3f9cd2dfbd 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -198,7 +198,7 @@ constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card -#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09 +#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, #define HAL_IDLETASK 1 void HAL_idletask(); diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index d71a5c61b9..451c94f25d 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -30,3 +30,6 @@ #undef F_CPU #define F_CPU BOARD_F_CPU #endif + +// The Sensitive Pins array is not optimizable +#define RUNTIME_ONLY_ANALOG_TO_DIGITAL diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 18bee54009..40e6d77c74 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -282,8 +282,15 @@ bool wait_for_heatup = true; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wnarrowing" +#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; +#else + template + constexpr pin_t OnlyPins<-2, D...>::table[sizeof...(D)]; + #define sensitive_pins OnlyPins::table +#endif + bool pin_is_protected(const pin_t pin) { - static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; LOOP_L_N(i, COUNT(sensitive_pins)) { pin_t sensitive_pin; memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t)); diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index e304901940..9102bbab7b 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -187,8 +187,13 @@ #else #define _I_MS3 #endif + #if PIN_EXISTS(I_ENABLE) + #define _I_ENABLE_PIN I_ENABLE_PIN, + #else + #define _I_ENABLE_PIN + #endif - #define _I_PINS I_STEP_PIN, I_DIR_PIN, I_ENABLE_PIN, _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS + #define _I_PINS I_STEP_PIN, I_DIR_PIN, _I_ENABLE_PIN _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS #else @@ -228,8 +233,13 @@ #else #define _J_MS3 #endif + #if PIN_EXISTS(J_ENABLE) + #define _J_ENABLE_PIN J_ENABLE_PIN, + #else + #define _J_ENABLE_PIN + #endif - #define _J_PINS J_STEP_PIN, J_DIR_PIN, J_ENABLE_PIN, _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS + #define _J_PINS J_STEP_PIN, J_DIR_PIN, _J_ENABLE_PIN _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS #else @@ -269,8 +279,13 @@ #else #define _K_MS3 #endif + #if PIN_EXISTS(K_ENABLE) + #define _K_ENABLE_PIN K_ENABLE_PIN, + #else + #define _K_ENABLE_PIN + #endif - #define _K_PINS K_STEP_PIN, K_DIR_PIN, K_ENABLE_PIN, _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS + #define _K_PINS K_STEP_PIN, K_DIR_PIN, _K_ENABLE_PIN _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS #else @@ -577,30 +592,32 @@ #define _H6_PINS #define _H7_PINS +#define DIO_PIN(P) TERN(TARGET_LPC1768, P, analogInputToDigitalPin(P)) + #if HAS_HOTEND #undef _H0_PINS - #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_0_PIN), + #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, DIO_PIN(TEMP_0_PIN), #if HAS_MULTI_HOTEND #undef _H1_PINS - #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_1_PIN), + #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, DIO_PIN(TEMP_1_PIN), #if HOTENDS > 2 #undef _H2_PINS - #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_2_PIN), + #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, DIO_PIN(TEMP_2_PIN), #if HOTENDS > 3 #undef _H3_PINS - #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_3_PIN), + #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, DIO_PIN(TEMP_3_PIN), #if HOTENDS > 4 #undef _H4_PINS - #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_4_PIN), + #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, DIO_PIN(TEMP_4_PIN), #if HOTENDS > 5 #undef _H5_PINS - #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_5_PIN), + #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, DIO_PIN(TEMP_5_PIN), #if HOTENDS > 6 #undef _H6_PINS - #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_6_PIN), + #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, DIO_PIN(TEMP_6_PIN), #if HOTENDS > 7 #undef _H7_PINS - #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_7_PIN), + #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, DIO_PIN(TEMP_7_PIN), #endif // HOTENDS > 7 #endif // HOTENDS > 6 #endif // HOTENDS > 5 @@ -809,13 +826,13 @@ #endif #if TEMP_SENSOR_BED && PINS_EXIST(TEMP_BED, HEATER_BED) - #define _BED_PINS HEATER_BED_PIN, analogInputToDigitalPin(TEMP_BED_PIN), + #define _BED_PINS HEATER_BED_PIN, DIO_PIN(TEMP_BED_PIN), #else #define _BED_PINS #endif #if TEMP_SENSOR_CHAMBER && PIN_EXISTS(TEMP_CHAMBER) - #define _CHAMBER_TEMP analogInputToDigitalPin(TEMP_CHAMBER_PIN), + #define _CHAMBER_TEMP DIO_PIN(TEMP_CHAMBER_PIN), #else #define _CHAMBER_TEMP #endif @@ -831,17 +848,15 @@ #endif #if TEMP_SENSOR_COOLER && PIN_EXISTS(TEMP_COOLER) - #define _COOLER_TEMP analogInputToDigitalPin(TEMP_COOLER_PIN), + #define _COOLER_TEMP DIO_PIN(TEMP_COOLER_PIN), #else #define _COOLER_TEMP #endif - #if TEMP_SENSOR_COOLER && PIN_EXISTS(COOLER) #define _COOLER COOLER_PIN, #else #define _COOLER #endif - #if TEMP_SENSOR_COOLER && PINS_EXIST(TEMP_COOLER, COOLER_AUTO_FAN) #define _COOLER_FAN COOLER_AUTO_FAN_PIN, #else @@ -852,11 +867,30 @@ #define HAL_SENSITIVE_PINS #endif -#define SENSITIVE_PINS { \ +#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + #define _SP_END +#else + #define _SP_END -2 + + // Move a regular pin in front to the end + template + struct OnlyPins : OnlyPins { }; + + // Remove a -1 from the front + template + struct OnlyPins<-1, D...> : OnlyPins { }; + + // Remove -2 from the front, emit the rest, cease propagation + template + struct OnlyPins<_SP_END, D...> { static constexpr pin_t table[sizeof...(D)] PROGMEM = { D... }; }; +#endif + +#define SENSITIVE_PINS \ _X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \ _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \ _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \ _PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \ - _BED_PINS _COOLER _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN HAL_SENSITIVE_PINS \ -} + _BED_PINS _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN \ + _COOLER_TEMP _COOLER _COOLER_FAN HAL_SENSITIVE_PINS \ + _SP_END From 403b3667444d934a0bbaa0e44f090f7f5593fe6e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 9 Jun 2021 01:05:08 +0000 Subject: [PATCH 0236/2168] [cron] Bump distribution date (2021-06-09) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 04a823e0c8..8a50c4d7b0 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 "2021-06-08" + #define STRING_DISTRIBUTION_DATE "2021-06-09" #endif /** From d27d86d5960feec322fb5c322e38e4b81ee41a72 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 10 Jun 2021 01:03:10 +0000 Subject: [PATCH 0237/2168] [cron] Bump distribution date (2021-06-10) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8a50c4d7b0..212b7e9246 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 "2021-06-09" + #define STRING_DISTRIBUTION_DATE "2021-06-10" #endif /** From 0e1e1591879077cdda868a28b095c427098fda07 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 10 Jun 2021 02:05:04 -0500 Subject: [PATCH 0238/2168] =?UTF-8?q?=F0=9F=8E=A8=20Adjust=20some=20condit?= =?UTF-8?q?ionals?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/bedlevel.h | 2 +- Marlin/src/feature/powerloss.h | 4 ++-- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 23 +++++++++++++---------- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/inc/Conditionals_LCD.h | 4 ++++ Marlin/src/lcd/menu/menu_probe_offset.cpp | 2 +- Marlin/src/lcd/menu/menu_tramming.cpp | 2 +- 9 files changed, 25 insertions(+), 18 deletions(-) diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index 9bab2fbd2f..63f032eee8 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfigPre.h" #if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) - #define G28_L0_ENSURES_LEVELING_OFF 1 + #define CAN_SET_LEVELING_AFTER_G28 1 #endif #if ENABLED(PROBE_MANUALLY) diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 0fa9172fcf..55180e5390 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -88,7 +88,7 @@ typedef struct { uint8_t fan_speed[FAN_COUNT]; #endif - #if ENABLED(HAS_LEVELING) + #if HAS_LEVELING float fade; #endif @@ -120,7 +120,7 @@ typedef struct { bool raised:1; // Raised before saved bool dryrun:1; // M111 S8 bool allow_cold_extrusion:1; // M302 P1 - #if ENABLED(HAS_LEVELING) + #if HAS_LEVELING bool leveling:1; // M420 S #endif #if DISABLED(NO_VOLUMETRICS) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 5760667bed..729bca93a6 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -246,7 +246,7 @@ G29_TYPE GcodeSuite::G29() { // Send 'N' to force homing before G29 (internal only) if (parser.seen_test('N')) - process_subcommands_now_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + process_subcommands_now_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); // Don't allow auto-leveling without homing first if (homing_needed_error()) G29_RETURN(false); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 07721330ba..055acc1ed4 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -87,7 +87,7 @@ void GcodeSuite::G29() { mbl.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2")); + queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2")); return; } state = MeshNext; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 2eca66c3b0..61e7ab4233 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -242,12 +242,16 @@ void GcodeSuite::G28() { SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state // Disable the leveling matrix before homing - #if HAS_LEVELING - const bool leveling_restore_state = parser.boolval('L', TERN(RESTORE_LEVELING_AFTER_G28, planner.leveling_active, ENABLED(ENABLE_LEVELING_AFTER_G28))); - IF_ENABLED(PROBE_MANUALLY, g29_in_progress = false); // Cancel the active G29 session - set_bed_leveling_enabled(false); + #if CAN_SET_LEVELING_AFTER_G28 + const bool leveling_restore_state = parser.boolval('L', TERN1(RESTORE_LEVELING_AFTER_G28, planner.leveling_active)); #endif + // Cancel any prior G29 session + TERN_(PROBE_MANUALLY, g29_in_progress = false); + + // Disable leveling before homing + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + // Reset to the XY plane TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); @@ -353,13 +357,14 @@ void GcodeSuite::G28() { const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; - if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { + if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); TERN_(BLTOUCH, bltouch.init()); } + // Diagonal move first if both are homing TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); // Home Y (before X) @@ -464,12 +469,10 @@ void GcodeSuite::G28() { // Clear endstop state for polled stallGuard endstops TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); - #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE) - // move to a height where we can use the full xy-area - do_blocking_move_to_z(delta_clip_start_height); - #endif + // Move to a height where we can use the full xy-area + TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_restore_state)); + TERN_(CAN_SET_LEVELING_AFTER_G28, if (leveling_restore_state) set_bed_leveling_enabled()); restore_feedrate_and_scaling(); diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index abd7f07916..89605ee25b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -392,7 +392,7 @@ public: static void process_subcommands_now(char * gcode); static inline void home_all_axes(const bool keep_leveling=false) { - process_subcommands_now_P(keep_leveling ? G28_STR : TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + process_subcommands_now_P(keep_leveling ? G28_STR : TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); } #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9e87589ca8..0eaa749126 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1027,6 +1027,10 @@ #endif #endif +#if DISABLED(DELTA) + #undef DELTA_HOME_TO_SAFE_ZONE +#endif + // This flag indicates some kind of jerk storage is needed #if EITHER(CLASSIC_JERK, IS_KINEMATIC) #define HAS_CLASSIC_JERK 1 diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 008db6a8b8..5ed217131a 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -42,7 +42,7 @@ // Global storage float z_offset_backup, calculated_z_offset, z_offset_ref; -#if ENABLED(HAS_LEVELING) +#if HAS_LEVELING bool leveling_was_active; #endif diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index da7afd86ef..7ccb320f31 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -92,7 +92,7 @@ void goto_tramming_wizard() { // Inject G28, wait for homing to complete, set_all_unhomed(); - queue.inject_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + queue.inject_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); ui.goto_screen([]{ _lcd_draw_homing(); From 54d526f6b613b408a3fd61f2d9f6ddbf9cb73e99 Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 10 Jun 2021 19:09:52 +1200 Subject: [PATCH 0239/2168] =?UTF-8?q?=F0=9F=94=A7=20Enforce=20BLTouch=20se?= =?UTF-8?q?ttings=20(#22086)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 11 +++-------- buildroot/tests/mega1280 | 4 +++- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 0eaa749126..ea83b5abbc 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -718,22 +718,17 @@ #define Z_PROBE_SERVO_NR 0 #endif #ifdef DEACTIVATE_SERVOS_AFTER_MOVE - #warning "BLTOUCH requires DEACTIVATE_SERVOS_AFTER_MOVE to be to disabled. Undefining DEACTIVATE_SERVOS_AFTER_MOVE. Please update your Configuration.h file." - #undef DEACTIVATE_SERVOS_AFTER_MOVE + #error "BLTOUCH requires DEACTIVATE_SERVOS_AFTER_MOVE to be to disabled. Please update your Configuration.h file." #endif // Always disable probe pin inverting for BLTouch #if Z_MIN_PROBE_ENDSTOP_INVERTING - #warning "BLTOUCH requires Z_MIN_PROBE_ENDSTOP_INVERTING set to false. Resetting Z_MIN_PROBE_ENDSTOP_INVERTING to false. Please update your Configuration.h file." - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #error "BLTOUCH requires Z_MIN_PROBE_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." #endif #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #if Z_MIN_ENDSTOP_INVERTING - #warning "BLTOUCH requires Z_MIN_ENDSTOP_INVERTING set to false. Resetting Z_MIN_ENDSTOP_INVERTING to false. Please update your Configuration.h file." - #undef Z_MIN_ENDSTOP_INVERTING - #define Z_MIN_ENDSTOP_INVERTING false + #error "BLTOUCH requires Z_MIN_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." #endif #endif #endif diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index 8b16b1dbc8..d8cefbaf81 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -47,7 +47,9 @@ exec_test $1 $2 "RAMPS | DELTA | RRD LCD | DELTA_AUTO_CALIBRATION | DELTA_CALIBR # # Delta Config (generic) + ABL bilinear + BLTOUCH use_example_configs delta/generic -opt_set LCD_LANGUAGE cz +opt_set LCD_LANGUAGE cz \ + Z_MIN_PROBE_ENDSTOP_INVERTING false \ + Z_MIN_ENDSTOP_INVERTING false opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR BLTOUCH exec_test $1 $2 "DELTA | RRD LCD | ABL Bilinear | BLTOUCH" "$3" From 9ca121bc5afe2b98532f17cb0c94e2ca85712e9c Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 10 Jun 2021 02:08:42 -0600 Subject: [PATCH 0240/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Six=20Linear=20A?= =?UTF-8?q?xes=20followup=20(typos)=20(#22094)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G425.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 56b1555fc4..c8efea858c 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -439,7 +439,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif - #if LINEAR_AXES >= 4 AXIS_CAN_CALIBRATE(I) + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) #if ENABLED(CALIBRATION_MEASURE_IMIN) SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); #endif @@ -447,7 +447,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 5 AXIS_CAN_CALIBRATE(J) + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) #if ENABLED(CALIBRATION_MEASURE_JMIN) SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); #endif @@ -455,7 +455,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 6 AXIS_CAN_CALIBRATE(K) + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) #if ENABLED(CALIBRATION_MEASURE_KMIN) SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); #endif From 6d2c7aa227a5868badc9ab748bbd799a95ed7740 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 10 Jun 2021 02:17:39 -0600 Subject: [PATCH 0241/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20and=20improve=20?= =?UTF-8?q?FTDI=20Eve=20Touch=20UI=20(#22093)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../archim2-flash/media_file_reader.cpp | 4 +--- .../ftdi_eve_lib/extended/text_box.cpp | 2 +- .../ftdi_eve_touch_ui/generic/about_screen.cpp | 8 ++++---- .../generic/bed_mesh_view_screen.cpp | 4 ++-- .../generic/z_offset_screen.cpp | 18 ++++++++++++------ .../generic/z_offset_screen.h | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 4 ++-- Marlin/src/lcd/extui/ui_api.cpp | 4 ++++ Marlin/src/lcd/extui/ui_api.h | 1 + 9 files changed, 28 insertions(+), 19 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp index ab60579700..ea8d403753 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp @@ -27,9 +27,7 @@ #if ENABLED(SDSUPPORT) bool MediaFileReader::open(const char *filename) { - card.init(SD_SPI_SPEED, SDSS); - volume.init(&card); - root.openRoot(&volume); + root = CardReader::getroot(); return file.open(&root, filename, O_READ); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 6d53d00bb8..9f73c7dfb8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -82,8 +82,8 @@ namespace FTDI { box_width = w; measure_text_box(fm, str, box_width, box_height); if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; - fm.load(--font); if (font == 26) break; + fm.load(--font); } const uint16_t dx = (options & OPT_RIGHTX) ? w : diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 8d8c543046..3d2c6a9e44 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -26,7 +26,7 @@ #ifdef FTDI_ABOUT_SCREEN #define GRID_COLS 4 -#define GRID_ROWS 7 +#define GRID_ROWS 8 using namespace FTDI; using namespace Theme; @@ -47,9 +47,9 @@ void AboutScreen::onRedraw(draw_mode_t) { #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) - #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2) - #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,3) + #define STATS_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,8), BTN_SIZE(2,1) #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h #define INSET_POS(pos) _INSET_POS(pos) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index f5cf1cbb34..75b15828a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -69,7 +69,7 @@ void BedMeshViewScreen::onEntry() { void BedMeshViewScreen::drawHighlightedPointValue() { CommandProcessor cmd; cmd.font(Theme::font_medium) - .colors(normal_btn) + .cmd(COLOR_RGB(bg_text_enabled)) .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) .font(font_small); @@ -161,7 +161,7 @@ void BedMeshViewScreen::doProbe() { void BedMeshViewScreen::doMeshValidation() { mydata.count = 0; GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("G28 O\nM117 Heating...\nG26 R X0 Y0")); + injectCommands_P(PSTR("M75\nG28 O\nM117 Heating...\nG26 R X0 Y0\nG27\nM77")); } void BedMeshViewScreen::show() { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp index 58cab48049..8d886c704a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -46,17 +46,22 @@ void ZOffsetScreen::onRedraw(draw_mode_t what) { w.heading( GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); w.color(z_axis).adjuster(4, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), getZOffset_mm()); w.increments(); - w.button( 2, GET_TEXT_F(MSG_PROBE_WIZARD)); + w.button(2, GET_TEXT_F(MSG_PROBE_WIZARD), !isPrinting()); } -void ZOffsetScreen::move(float inc) { +void ZOffsetScreen::move(float mm, int16_t steps) { // We can't store state after the call to the AlertBox, so // check whether the current position equal mydata.z in order // to know whether the user started the wizard. if (getAxisPosition_mm(Z) == mydata.z) { - mydata.z += inc; + // In the wizard + mydata.z += mm; setAxisPosition_mm(mydata.z, Z); } + else { + // Otherwise doing a manual adjustment, possibly during a print. + babystepAxis_steps(steps, Z); + } } void ZOffsetScreen::runWizard() { @@ -80,11 +85,12 @@ void ZOffsetScreen::runWizard() { } bool ZOffsetScreen::onTouchHeld(uint8_t tag) { - const float increment = getIncrement(); + const int16_t steps = mmToWholeSteps(getIncrement(), Z); + const float increment = mmFromWholeSteps(steps, Z); switch (tag) { case 2: runWizard(); break; - case 4: UI_DECREMENT(ZOffset_mm); move(-increment); break; - case 5: UI_INCREMENT(ZOffset_mm); move( increment); break; + case 4: UI_DECREMENT(ZOffset_mm); move(-increment, -steps); break; + case 5: UI_INCREMENT(ZOffset_mm); move( increment, steps); break; default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h index 159fd2383c..067687f315 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h @@ -31,7 +31,7 @@ struct ZOffsetScreenData : public BaseNumericAdjustmentScreenData { class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { private: - static void move(float inc); + static void move(float mm, int16_t steps); static void runWizard(); public: static void onEntry(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 9de9623e19..4ac44501d5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -70,7 +70,7 @@ namespace Language_en { PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; PROGMEM Language_Str MSG_LICENSE = u8"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.\n\nTo view a copy of the GNU General " + "of the License, or (at your option) any later version. To view a copy of the GNU General " "Public License, go to the following location: https://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; @@ -130,7 +130,7 @@ namespace Language_en { PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; PROGMEM Language_Str MSG_EEPROM_SAVED = u8"Settings saved!"; - PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings as defaults?"; + PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings for next power-on?"; PROGMEM Language_Str MSG_EEPROM_RESET_WARNING = u8"Are you sure? Customizations will be lost."; PROGMEM Language_Str MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index fff31f099b..b0def618fd 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -767,6 +767,10 @@ namespace ExtUI { return steps > 0 ? CEIL(steps) : FLOOR(steps); } + float mmFromWholeSteps(int16_t steps, const axis_t axis) { + return steps * planner.steps_to_mm[axis]; + } + #endif // BABYSTEPPING float getZOffset_mm() { diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 5603169626..9922fa6799 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -239,6 +239,7 @@ namespace ExtUI { #if ENABLED(BABYSTEPPING) int16_t mmToWholeSteps(const_float_t mm, const axis_t axis); + float mmFromWholeSteps(int16_t steps, const axis_t axis); bool babystepAxis_steps(const int16_t steps, const axis_t axis); void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles); From ded1b0c26f6e7b39ed8d88a78172d689a138e5cc Mon Sep 17 00:00:00 2001 From: Radek <46979052+radek8@users.noreply.github.com> Date: Thu, 10 Jun 2021 19:51:07 +0200 Subject: [PATCH 0242/2168] =?UTF-8?q?=F0=9F=94=A7=20EEPROM=20options=20for?= =?UTF-8?q?=20BTT=20SKR=201.4=20(#22092)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 14 ++++++++++++++ 1 file changed, 14 insertions(+) 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 0508c5b5a9..73b4d3e63d 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -31,6 +31,20 @@ #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 #endif +// +// EEPROM +// +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION +#endif + +#if ENABLED(I2C_EEPROM) + #define MARLIN_EEPROM_SIZE 0x8000 // 32Kb +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb +#endif + // // Servos // From eac0f6be3e25ec0f3acf746f55191b79a609c96b Mon Sep 17 00:00:00 2001 From: grauerfuchs <42082416+grauerfuchs@users.noreply.github.com> Date: Thu, 10 Jun 2021 17:04:18 -0400 Subject: [PATCH 0243/2168] =?UTF-8?q?=F0=9F=94=A8=20MightyBoard=20envs=20f?= =?UTF-8?q?or=20A.B.M.=20(#22100)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 514665d826..3b0f7d42ea 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -216,7 +216,7 @@ #elif MB(CNCONTROLS_15) #include "mega/pins_CNCONTROLS_15.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MIGHTYBOARD_REVE) - #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 + #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 env:MightyBoard1280 env:MightyBoard2560 #elif MB(CHEAPTRONIC) #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 #elif MB(CHEAPTRONIC_V2) From 8d54f9b847c5c20d340975e3f4f095820b1b6edd Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Thu, 10 Jun 2021 23:05:07 +0200 Subject: [PATCH 0244/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Hungarian=20l?= =?UTF-8?q?anguage=20(#22083)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_hu.h | 49 +++++++++++++++++++-------- 1 file changed, 35 insertions(+), 14 deletions(-) diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index b2c1d30f33..f29a7b76b9 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -26,11 +26,11 @@ * * LCD Menu Messages. See also https://marlinfw.org/docs/development/lcd_language.html * Hungarian translation by AntoszHUN. I am constantly improving and updating the translation. - * Translation last updated: 21/03/2021 - 21:00 + * Translation last updated: 23/05/2021 - 20:45 * * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html * A Magyar fordítást készítette: AntoszHUN. A fordítást folyamatosan javítom és frissítem. - * A Fordítás utolsó frissítése: 2021.03.21. - 21:00 + * A Fordítás utolsó frissítése: 2021.05.23. - 20:45 */ namespace Language_hu { @@ -76,6 +76,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés kész!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint csökkentés"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Elektromos segéd"); @@ -108,12 +111,15 @@ namespace Language_hu { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer telj."); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó telj."); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Lézer váltás"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Hütés váltás"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Levegö segéd"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Impulzus teszt ms"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Tüz impulzus"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Áramlási hiba"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Orsóváltás"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó előre"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vákuum váltás"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó elöre"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó hátra"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Adagol"); @@ -134,7 +140,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z érték"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Egyéni parancs"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Egyéni parancs"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Szonda teszt"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Pont"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Szonda határon kívül"); @@ -154,6 +160,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési pont"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi háló építés"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Háló varázsló"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); @@ -161,9 +168,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktívál"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktívál"); PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy höfok"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Ágy höfok"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fej höfok"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Fej höfok"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Egyéni ágy höfok"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fejhöfok"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Egyéni fejhöfok"); PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló szerkesztés"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni háló szerkesztés"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított háló"); @@ -239,7 +246,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); PROGMEM Language_Str MSG_LEDS2 = _UxGT("LED-ek #2"); PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerő"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni szín"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros intenzitás"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld intenzitás"); @@ -272,6 +279,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_CHAMBER = _UxGT("Burkolat"); PROGMEM Language_Str MSG_COOLER = _UxGT("Lézer hütövíz"); PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Hütö kapcsoló"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); PROGMEM Language_Str MSG_LASER = _UxGT("Lézer"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Hütés sebesség"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); @@ -298,6 +306,16 @@ namespace Language_hu { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); + 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("Kiválaszt"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); @@ -505,6 +523,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló szintezés"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); @@ -566,17 +585,17 @@ namespace Language_hu { PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál betöltése"); PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes betöltése"); PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fej betöltése"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kiadása"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kiadása ~"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kidobás"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kidobás ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kiadás...."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kidobás. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Mind"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU újraindítás"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU újraindul..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Eltávolít, kattint"); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); PROGMEM Language_Str MSG_MIX = _UxGT("Kever"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); @@ -632,7 +651,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd foltyat...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd folytat...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); @@ -683,6 +702,8 @@ namespace Language_hu { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Jobb alsó"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrálás befejezve"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); } #if FAN_COUNT == 1 From 673bccef3e77d33e9bc399171fb8e45be74600c7 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 10 Jun 2021 14:09:29 -0700 Subject: [PATCH 0245/2168] =?UTF-8?q?=F0=9F=94=A8=20Envs=20for=20BTT=20SKR?= =?UTF-8?q?=20Mini=20with=20RET6=20(512K)=20(#22050)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 2 +- Marlin/src/pins/pins.h | 12 ++++++------ ini/stm32f1-maple.ini | 26 ++------------------------ ini/stm32f1.ini | 33 +++++++-------------------------- 4 files changed, 16 insertions(+), 57 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 651df5aedf..9dc951e229 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -321,7 +321,7 @@ #define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) #define BOARD_BTT_SKR_MINI_MZ_V1_0 4027 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) #define BOARD_BTT_SKR_E3_DIP 4028 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) #define BOARD_BTT_SKR_CR6 4029 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3b0f7d42ea..88dd170a9e 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -508,17 +508,17 @@ #elif MB(MKS_ROBIN_E3P) #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_2) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V2_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(BTT_SKR_MINI_MZ_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_maple env:STM32F103RC_btt_512K_maple env:STM32F103RC_btt_USB_maple env:STM32F103RC_btt_512K_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_E3_DIP) - #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple env:STM32F103RC_btt env:STM32F103RC_btt_512K + #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(BTT_SKR_CR6) #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(JGAURORA_A5S_A1) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 349016145c..25ebfb64b6 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -85,19 +85,11 @@ debug_tool = stlink upload_protocol = serial # -# BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) +# BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # # STM32F103RC_btt_maple ............. RCT6 with 256K # STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) -# STM32F103RC_btt_512K_maple ........ RCT6 with 512K -# STM32F103RC_btt_512K_USB_maple .... RCT6 with 512K (USB mass storage) # -# WARNING! If you have an SKR Mini v1.1 or an SKR Mini E3 1.0 / 1.2 / 2.0 / DIP -# and experience a printer freeze, re-flash Marlin using the regular (non-512K) -# build option. 256K chips may be re-branded 512K chips, but this means the -# upper 256K is sketchy, and failure is very likely. -# - [env:STM32F103RC_btt_maple] platform = ${common_stm32f1.platform} extends = common_STM32F103RC_maple @@ -116,20 +108,6 @@ build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} USBComposite for STM32F1@0.91 -[env:STM32F103RC_btt_512K_maple] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt_maple -board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld -board_upload.maximum_size = 524288 -build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DSTM32_FLASH_SIZE=512 - -[env:STM32F103RC_btt_512K_USB_maple] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt_512K_maple -build_flags = ${env:STM32F103RC_btt_512K_maple.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt_512K_maple.lib_deps} - USBComposite for STM32F1@0.91 - # # Generic STM32F103RE environment # @@ -155,7 +133,7 @@ debug_tool = jlink upload_protocol = jlink # -# BigTree SKR Mini E3 DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) +# BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt_maple ............. RET6 # STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 150ddba01e..9954411c14 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -34,19 +34,6 @@ src_filter = ${common.default_src_filter} + + Date: Fri, 11 Jun 2021 00:57:12 +0000 Subject: [PATCH 0246/2168] [cron] Bump distribution date (2021-06-11) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 212b7e9246..b6441f8056 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 "2021-06-10" + #define STRING_DISTRIBUTION_DATE "2021-06-11" #endif /** From 629551d9bc10fd10baf8684c6830baf83e6caa9b Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Fri, 11 Jun 2021 13:51:29 -0700 Subject: [PATCH 0247/2168] =?UTF-8?q?=E2=9C=A8=20More=20flexible=20redunda?= =?UTF-8?q?nt=20temp=20sensor=20(#22085)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 28 ++- Marlin/Configuration_adv.h | 6 + Marlin/src/HAL/LPC1768/tft/xpt2046.h | 2 +- Marlin/src/HAL/STM32/tft/xpt2046.h | 2 +- Marlin/src/HAL/STM32F1/tft/xpt2046.h | 2 +- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/gcode/temp/M105.cpp | 6 +- Marlin/src/inc/Conditionals_post.h | 193 +++++++++++++--- Marlin/src/inc/SanityCheck.h | 91 +++++++- Marlin/src/module/temperature.cpp | 217 ++++++++++++------ Marlin/src/module/temperature.h | 46 ++-- Marlin/src/module/thermistor/thermistor_1.h | 2 +- Marlin/src/module/thermistor/thermistor_10.h | 2 +- .../src/module/thermistor/thermistor_1010.h | 2 +- .../src/module/thermistor/thermistor_1047.h | 2 +- Marlin/src/module/thermistor/thermistor_11.h | 2 +- Marlin/src/module/thermistor/thermistor_110.h | 2 +- Marlin/src/module/thermistor/thermistor_12.h | 2 +- Marlin/src/module/thermistor/thermistor_13.h | 2 +- Marlin/src/module/thermistor/thermistor_147.h | 2 +- Marlin/src/module/thermistor/thermistor_15.h | 2 +- Marlin/src/module/thermistor/thermistor_17.h | 2 +- Marlin/src/module/thermistor/thermistor_18.h | 2 +- Marlin/src/module/thermistor/thermistor_2.h | 2 +- Marlin/src/module/thermistor/thermistor_20.h | 2 +- Marlin/src/module/thermistor/thermistor_201.h | 2 +- Marlin/src/module/thermistor/thermistor_202.h | 2 +- Marlin/src/module/thermistor/thermistor_21.h | 2 +- Marlin/src/module/thermistor/thermistor_22.h | 2 +- Marlin/src/module/thermistor/thermistor_23.h | 2 +- Marlin/src/module/thermistor/thermistor_3.h | 2 +- Marlin/src/module/thermistor/thermistor_30.h | 2 +- Marlin/src/module/thermistor/thermistor_331.h | 2 +- Marlin/src/module/thermistor/thermistor_332.h | 2 +- Marlin/src/module/thermistor/thermistor_4.h | 2 +- Marlin/src/module/thermistor/thermistor_5.h | 2 +- Marlin/src/module/thermistor/thermistor_501.h | 2 +- Marlin/src/module/thermistor/thermistor_502.h | 2 +- Marlin/src/module/thermistor/thermistor_503.h | 2 +- Marlin/src/module/thermistor/thermistor_51.h | 2 +- Marlin/src/module/thermistor/thermistor_512.h | 2 +- Marlin/src/module/thermistor/thermistor_52.h | 2 +- Marlin/src/module/thermistor/thermistor_55.h | 2 +- Marlin/src/module/thermistor/thermistor_6.h | 2 +- Marlin/src/module/thermistor/thermistor_60.h | 2 +- Marlin/src/module/thermistor/thermistor_61.h | 2 +- Marlin/src/module/thermistor/thermistor_66.h | 2 +- Marlin/src/module/thermistor/thermistor_666.h | 2 +- Marlin/src/module/thermistor/thermistor_67.h | 2 +- Marlin/src/module/thermistor/thermistor_7.h | 2 +- Marlin/src/module/thermistor/thermistor_70.h | 2 +- Marlin/src/module/thermistor/thermistor_71.h | 2 +- Marlin/src/module/thermistor/thermistor_75.h | 2 +- Marlin/src/module/thermistor/thermistor_8.h | 2 +- Marlin/src/module/thermistor/thermistor_9.h | 2 +- Marlin/src/module/thermistor/thermistor_99.h | 2 +- Marlin/src/module/thermistor/thermistor_998.h | 2 +- Marlin/src/module/thermistor/thermistor_999.h | 2 +- Marlin/src/module/thermistor/thermistors.h | 124 +++++----- buildroot/bin/mftest | 2 +- buildroot/bin/opt_disable | 2 +- buildroot/bin/opt_enable | 2 +- buildroot/bin/opt_set | 2 +- buildroot/bin/pins_set | 2 +- buildroot/share/git/mfconfig | 2 +- 65 files changed, 573 insertions(+), 254 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index cb7740a294..717cdd9236 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -472,6 +472,7 @@ #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 #define TEMP_SENSOR_COOLER 0 +#define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 #define DUMMY_THERMISTOR_998_VALUE 25 @@ -483,11 +484,6 @@ //#define MAX31865_SENSOR_OHMS_1 100 //#define MAX31865_CALIBRATION_OHMS_1 430 -// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings -// from the two sensors differ too much the print will be aborted. -//#define TEMP_SENSOR_1_AS_REDUNDANT -#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10 - #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 #define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer #define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target @@ -500,6 +496,28 @@ #define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer #define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +/** + * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) + * + * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another + * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C), + * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting + * the Bed sensor (-1) will disable bed heating/monitoring. + * + * Use the following to select temp sensors: + * -5 : Cooler + * -4 : Probe + * -3 : not used + * -2 : Chamber + * -1 : Bed + * 0-7 : E0 through E7 + */ +#if TEMP_SENSOR_REDUNDANT + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading. + #define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for. + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. +#endif + // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. #define HEATER_0_MINTEMP 5 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5bd3c51603..2a7f06c733 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -125,6 +125,12 @@ #define PROBE_BETA 3950 // Beta value #endif +#if TEMP_SENSOR_REDUNDANT == 1000 + #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define REDUNDANT_BETA 3950 // Beta value +#endif + // // Hephestos 2 24V heated bed upgrade kit. // https://store.bq.com/en/heated-bed-kit-hephestos2 diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h index 65602bda0f..aba0799e44 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h @@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 5b8acf4b87..2cff3e29d0 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -56,7 +56,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h index 65602bda0f..aba0799e44 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h @@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 40e6d77c74..54598e035a 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1157,10 +1157,10 @@ void setup() { SETUP_RUN(HAL_init()); // Init and disable SPI thermocouples; this is still needed - #if TEMP_SENSOR_0_IS_MAX_TC + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0) OUT_WRITE(MAX6675_SS_PIN, HIGH); // Disable #endif - #if TEMP_SENSOR_1_IS_MAX_TC + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) OUT_WRITE(MAX6675_SS2_PIN, HIGH); // Disable #endif diff --git a/Marlin/src/gcode/temp/M105.cpp b/Marlin/src/gcode/temp/M105.cpp index eefc3ae9f1..4de5ba8eef 100644 --- a/Marlin/src/gcode/temp/M105.cpp +++ b/Marlin/src/gcode/temp/M105.cpp @@ -35,11 +35,7 @@ void GcodeSuite::M105() { #if HAS_TEMP_SENSOR - thermalManager.print_heater_states(target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , parser.boolval('R') - #endif - ); + thermalManager.print_heater_states(target_extruder OPTARG(HAS_TEMP_REDUNDANT, parser.boolval('R'))); SERIAL_EOL(); diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d28822cf38..a5a1070b03 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -512,11 +512,99 @@ * Temp Sensor defines */ -#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n) || TEMP_SENSOR_COOLER == (n)) - +#define ANY_TEMP_SENSOR_IS(n) ( \ + n == TEMP_SENSOR_0 || n == TEMP_SENSOR_1 || n == TEMP_SENSOR_2 || n == TEMP_SENSOR_3 \ + || n == TEMP_SENSOR_4 || n == TEMP_SENSOR_5 || n == TEMP_SENSOR_6 || n == TEMP_SENSOR_7 \ + || n == TEMP_SENSOR_BED \ + || n == TEMP_SENSOR_PROBE \ + || n == TEMP_SENSOR_CHAMBER \ + || n == TEMP_SENSOR_COOLER \ + || n == TEMP_SENSOR_REDUNDANT ) #if ANY_TEMP_SENSOR_IS(1000) #define HAS_USER_THERMISTORS 1 #endif +#undef ANY_TEMP_SENSOR_IS + +// Usurp a sensor to do redundant readings +#if TEMP_SENSOR_REDUNDANT && !PIN_EXISTS(TEMP_REDUNDANT) + #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 + #if !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 + #if !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_BED_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #if !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_0_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #if !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_1_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 + #if !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_2_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 + #if !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_3_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 + #if !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_4_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 + #if !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_5_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 + #if !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_6_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 + #if !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_7_PIN + #endif + #endif + + #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 + #endif +#endif #if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 #define TEMP_SENSOR_0_IS_MAX_TC 1 @@ -540,7 +628,6 @@ #elif TEMP_SENSOR_0 == -1 #define TEMP_SENSOR_0_IS_AD595 1 #elif TEMP_SENSOR_0 > 0 - #define TEMP_SENSOR_0_THERMISTOR_ID TEMP_SENSOR_0 #define TEMP_SENSOR_0_IS_THERMISTOR 1 #if TEMP_SENSOR_0 == 1000 #define TEMP_SENSOR_0_IS_CUSTOM 1 @@ -583,7 +670,6 @@ #elif TEMP_SENSOR_1 == -1 #define TEMP_SENSOR_1_IS_AD595 1 #elif TEMP_SENSOR_1 > 0 - #define TEMP_SENSOR_1_THERMISTOR_ID TEMP_SENSOR_1 #define TEMP_SENSOR_1_IS_THERMISTOR 1 #if TEMP_SENSOR_1 == 1000 #define TEMP_SENSOR_1_IS_CUSTOM 1 @@ -595,35 +681,92 @@ #undef HEATER_1_MAXTEMP #endif -#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 +#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 + #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 + #define HAS_MAX_TC 1 + #if TEMP_SENSOR_REDUNDANT == -3 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 + #else + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 + #endif + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #endif + #if TEMP_SENSOR_REDUNDANT == -5 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 + #elif TEMP_SENSOR_REDUNDANT == -3 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 + #elif TEMP_SENSOR_REDUNDANT == -2 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 + #endif + #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) + #if TEMP_SENSOR_REDUNDANT == -5 + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -3 + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -2 + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #endif + #endif +#elif TEMP_SENSOR_REDUNDANT == -4 + #define TEMP_SENSOR_REDUNDANT_IS_AD8495 1 +#elif TEMP_SENSOR_REDUNDANT == -1 + #define TEMP_SENSOR_REDUNDANT_IS_AD595 1 +#elif TEMP_SENSOR_REDUNDANT > 0 + #define TEMP_SENSOR_REDUNDANT_IS_THERMISTOR 1 + #if TEMP_SENSOR_REDUNDANT == 1000 + #define TEMP_SENSOR_REDUNDANT_IS_CUSTOM 1 + #elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 + #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." + #endif +#endif + +#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 #define HAS_MAX31855 1 #endif -#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 #define HAS_MAX31865 1 #endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 #define HAS_MAX6675 1 #endif // // Compatibility layer for MAX (SPI) temp boards // +#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) + #if PIN_EXISTS(MAX6675_SS) - #if TEMP_SENSOR_0_IS_MAX31855 + #if TEMP_SENSOR_IS_MAX(0, MAX31855) #define MAX31855_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_0_IS_MAX31865 + #elif TEMP_SENSOR_IS_MAX(0, MAX31865) #define MAX31865_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_0_IS_MAX6675 + #elif TEMP_SENSOR_IS_MAX(0, MAX6675) #define MAX6675_CS_PIN MAX6675_SS_PIN #endif #endif #if PIN_EXISTS(MAX6675_SS2) - #if TEMP_SENSOR_1_IS_MAX31855 + #if TEMP_SENSOR_IS_MAX(1, MAX31855) #define MAX31855_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_1_IS_MAX31865 + #elif TEMP_SENSOR_IS_MAX(1, MAX31865) #define MAX31865_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_1_IS_MAX6675 + #elif TEMP_SENSOR_IS_MAX(1, MAX6675) #define MAX6675_CS2_PIN MAX6675_SS2_PIN #endif #endif @@ -698,7 +841,6 @@ #elif TEMP_SENSOR_2 == -1 #define TEMP_SENSOR_2_IS_AD595 1 #elif TEMP_SENSOR_2 > 0 - #define TEMP_SENSOR_2_THERMISTOR_ID TEMP_SENSOR_2 #define TEMP_SENSOR_2_IS_THERMISTOR 1 #if TEMP_SENSOR_2 == 1000 #define TEMP_SENSOR_2_IS_CUSTOM 1 @@ -719,7 +861,6 @@ #elif TEMP_SENSOR_3 == -1 #define TEMP_SENSOR_3_IS_AD595 1 #elif TEMP_SENSOR_3 > 0 - #define TEMP_SENSOR_3_THERMISTOR_ID TEMP_SENSOR_3 #define TEMP_SENSOR_3_IS_THERMISTOR 1 #if TEMP_SENSOR_3 == 1000 #define TEMP_SENSOR_3_IS_CUSTOM 1 @@ -740,7 +881,6 @@ #elif TEMP_SENSOR_4 == -1 #define TEMP_SENSOR_4_IS_AD595 1 #elif TEMP_SENSOR_4 > 0 - #define TEMP_SENSOR_4_THERMISTOR_ID TEMP_SENSOR_4 #define TEMP_SENSOR_4_IS_THERMISTOR 1 #if TEMP_SENSOR_4 == 1000 #define TEMP_SENSOR_4_IS_CUSTOM 1 @@ -761,7 +901,6 @@ #elif TEMP_SENSOR_5 == -1 #define TEMP_SENSOR_5_IS_AD595 1 #elif TEMP_SENSOR_5 > 0 - #define TEMP_SENSOR_5_THERMISTOR_ID TEMP_SENSOR_5 #define TEMP_SENSOR_5_IS_THERMISTOR 1 #if TEMP_SENSOR_5 == 1000 #define TEMP_SENSOR_5_IS_CUSTOM 1 @@ -782,7 +921,6 @@ #elif TEMP_SENSOR_6 == -1 #define TEMP_SENSOR_6_IS_AD595 1 #elif TEMP_SENSOR_6 > 0 - #define TEMP_SENSOR_6_THERMISTOR_ID TEMP_SENSOR_6 #define TEMP_SENSOR_6_IS_THERMISTOR 1 #if TEMP_SENSOR_6 == 1000 #define TEMP_SENSOR_6_IS_CUSTOM 1 @@ -803,7 +941,6 @@ #elif TEMP_SENSOR_7 == -1 #define TEMP_SENSOR_7_IS_AD595 1 #elif TEMP_SENSOR_7 > 0 - #define TEMP_SENSOR_7_THERMISTOR_ID TEMP_SENSOR_7 #define TEMP_SENSOR_7_IS_THERMISTOR 1 #if TEMP_SENSOR_7 == 1000 #define TEMP_SENSOR_7_IS_CUSTOM 1 @@ -824,7 +961,6 @@ #elif TEMP_SENSOR_BED == -1 #define TEMP_SENSOR_BED_IS_AD595 1 #elif TEMP_SENSOR_BED > 0 - #define TEMP_SENSOR_BED_THERMISTOR_ID TEMP_SENSOR_BED #define TEMP_SENSOR_BED_IS_THERMISTOR 1 #if TEMP_SENSOR_BED == 1000 #define TEMP_SENSOR_BED_IS_CUSTOM 1 @@ -845,7 +981,6 @@ #elif TEMP_SENSOR_CHAMBER == -1 #define TEMP_SENSOR_CHAMBER_IS_AD595 1 #elif TEMP_SENSOR_CHAMBER > 0 - #define TEMP_SENSOR_CHAMBER_THERMISTOR_ID TEMP_SENSOR_CHAMBER #define TEMP_SENSOR_CHAMBER_IS_THERMISTOR 1 #if TEMP_SENSOR_CHAMBER == 1000 #define TEMP_SENSOR_CHAMBER_IS_CUSTOM 1 @@ -858,20 +993,19 @@ #endif #if TEMP_SENSOR_COOLER == -4 - #define COOLER_USES_AD8495 1 + #define TEMP_SENSOR_COOLER_IS_AD8495 1 #elif TEMP_SENSOR_COOLER == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_COOLER." #elif TEMP_SENSOR_COOLER == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_COOLER." #elif TEMP_SENSOR_COOLER == -1 - #define COOLER_USES_AD595 1 + #define TEMP_SENSOR_COOLER_IS_AD595 1 #elif TEMP_SENSOR_COOLER > 0 - #define TEMP_SENSOR_COOLER_THERMISTOR_ID TEMP_SENSOR_COOLER #define TEMP_SENSOR_COOLER_IS_THERMISTOR 1 #if TEMP_SENSOR_COOLER == 1000 - #define COOLER_USER_THERMISTOR 1 + #define TEMP_SENSOR_COOLER_IS_CUSTOM 1 #elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 - #define COOLER_DUMMY_THERMISTOR 1 + #define TEMP_SENSOR_COOLER_IS_DUMMY 1 #endif #else #undef COOLER_MINTEMP @@ -887,7 +1021,6 @@ #elif TEMP_SENSOR_PROBE == -1 #define TEMP_SENSOR_PROBE_IS_AD595 1 #elif TEMP_SENSOR_PROBE > 0 - #define TEMP_SENSOR_PROBE_THERMISTOR_ID TEMP_SENSOR_PROBE #define TEMP_SENSOR_PROBE_IS_THERMISTOR 1 #if TEMP_SENSOR_PROBE == 1000 #define TEMP_SENSOR_PROBE_IS_CUSTOM 1 @@ -2345,6 +2478,9 @@ #if HAS_ADC_TEST(COOLER) #define HAS_TEMP_ADC_COOLER 1 #endif +#if HAS_ADC_TEST(REDUNDANT) + #define HAS_TEMP_ADC_REDUNDANT 1 +#endif #define HAS_TEMP(N) ANY(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_MAX_TC, TEMP_SENSOR_##N##_IS_DUMMY) #if HAS_HOTEND && HAS_TEMP(0) @@ -2362,6 +2498,9 @@ #if HAS_TEMP(COOLER) #define HAS_TEMP_COOLER 1 #endif +#if HAS_TEMP(REDUNDANT) + #define HAS_TEMP_REDUNDANT 1 +#endif #if ENABLED(JOYSTICK) #if PIN_EXISTS(JOY_X) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index d5f763ce9d..41d123326c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -568,6 +568,10 @@ #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." #elif defined(NEOPIXEL_BKGD_LED_INDEX) #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." +#elif defined(TEMP_SENSOR_1_AS_REDUNDANT) + #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." +#elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) + #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" #endif constexpr float arm[] = AXIS_RELATIVE_MODES; @@ -1887,19 +1891,88 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_CHAMBER 1000 requires CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS and CHAMBER_BETA in Configuration_adv.h." #elif TEMP_SENSOR_PROBE_IS_CUSTOM && !(defined(PROBE_PULLUP_RESISTOR_OHMS) && defined(PROBE_RESISTANCE_25C_OHMS) && defined(PROBE_BETA)) #error "TEMP_SENSOR_PROBE 1000 requires PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS and PROBE_BETA in Configuration_adv.h." +#elif TEMP_SENSOR_REDUNDANT_IS_CUSTOM && !(defined(REDUNDANT_PULLUP_RESISTOR_OHMS) && defined(REDUNDANT_RESISTANCE_25C_OHMS) && defined(REDUNDANT_BETA)) + #error "TEMP_SENSOR_REDUNDANT 1000 requires REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS and REDUNDANT_BETA in Configuration_adv.h." #endif /** * Pins and Sensor IDs must be set for each heater */ #if TEMP_SENSOR_0_IS_MAX6675 && !ANY_PIN(MAX6675_SS, MAX31855_CS, MAX31865_CS, MAX6675_CS) - #error "TEMP_SENSOR_0 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #error "TEMP_SENSOR_0 -2 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." #elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." #elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." #endif +/** + * Redundant temperature sensor config + */ +#if HAS_TEMP_REDUNDANT + #if !defined(TEMP_SENSOR_REDUNDANT_SOURCE) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_SOURCE." + #elif !defined(TEMP_SENSOR_REDUNDANT_TARGET) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == TEMP_SENSOR_REDUNDANT_TARGET + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be the same as TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE < -5 || TEMP_SENSOR_REDUNDANT_SOURCE > 7 + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_TARGET < -5 || TEMP_SENSOR_REDUNDANT_TARGET > 7 + #error "TEMP_SENSOR_REDUNDANT_TARGET must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -3 + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be -3 (not used)." + #elif TEMP_SENSOR_REDUNDANT_TARGET == -3 + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be -3 (not used)." + #elif HAS_MULTI_HOTEND && TEMP_SENSOR_REDUNDANT_SOURCE < HOTENDS + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be after the last TEMP_SENSOR used with a hotend; you can't use a sensor in the middle of two hotends." + #endif + + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 && HAS_HOTEND + #error "TEMP_SENSOR_REDUNDANT_SOURCE can not be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -5 && HAS_TEMP_COOLER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Cooler (-5): TEMP_SENSOR_COOLER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 && HAS_TEMP_PROBE + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Probe (-4): TEMP_SENSOR_PROBE has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 && HAS_TEMP_CHAMBER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Chamber (-2): TEMP_SENSOR_CHAMBER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 && HAS_TEMP_BED + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Bed (-1): TEMP_SENSOR_BED has already defined the sensor." + #endif + + #if TEMP_SENSOR_REDUNDANT_TARGET == 0 && !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E0 (0): requires TEMP_0_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 1 && !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E1 (1): requires TEMP_1_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 2 && !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E2 (2): requires TEMP_2_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 3 && !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E3 (3): requires TEMP_3_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 4 && !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E4 (4): requires TEMP_4_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 5 && !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E5 (5): requires TEMP_5_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 6 && !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E6 (6): requires TEMP_6_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 7 && !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E7 (7): requires TEMP_7_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Bed (-1): requires TEMP_BED_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Chamber (-2): requires TEMP_CHAMBER_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Probe (-4): requires TEMP_PROBE_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -5 && !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Cooler (-5): requires TEMP_COOLER_PIN" + #endif + + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 && !PIN_EXISTS(MAX6675_SS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 0 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 && !PIN_EXISTS(MAX6675_SS2) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 1 requires a MAX6675_SS2_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #endif +#endif + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_1_IS_MAX6675 && !ANY_PIN(MAX6675_SS2, MAX31855_CS2, MAX31865_CS2, MAX6675_CS2) #error "TEMP_SENSOR_1 requires a MAX6675_SS2_PIN, MAX6675_CS2_PIN, MAX31855_CS2_PIN, or MAX31865_CS2_PIN." @@ -1907,8 +1980,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS." #elif !ANY_PIN(TEMP_1, MAX6675_SS2) && !TEMP_SENSOR_1_IS_DUMMY #error "TEMP_1_PIN or MAX6675_SS2_PIN not defined for this board." - #elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - #error "HOTENDS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT." #endif #if HOTENDS > 2 #if TEMP_SENSOR_2 == 0 @@ -2006,7 +2077,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif TEMP_SENSOR_7 != 0 #error "TEMP_SENSOR_7 shouldn't be set with only 2 HOTENDS." #endif -#elif TEMP_SENSOR_1 != 0 && DISABLED(TEMP_SENSOR_1_AS_REDUNDANT) +#elif TEMP_SENSOR_1 != 0 #error "TEMP_SENSOR_1 shouldn't be set with only 1 HOTEND." #elif TEMP_SENSOR_2 != 0 #error "TEMP_SENSOR_2 shouldn't be set with only 1 HOTEND." @@ -2068,14 +2139,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) && TEMP_SENSOR_1 == 0 - #error "TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT." -#endif - -#if TEMP_SENSOR_0_IS_MAX31865 && !(defined(MAX31865_SENSOR_OHMS_0) && defined(MAX31865_CALIBRATION_OHMS_0)) - #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0 is MAX31865." -#elif TEMP_SENSOR_1_IS_MAX31865 && !(defined(MAX31865_SENSOR_OHMS_1) && defined(MAX31865_CALIBRATION_OHMS_1)) - #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1 is MAX31865." +#if TEMP_SENSOR_IS_MAX(0, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_0) && defined(MAX31865_CALIBRATION_OHMS_0)) + #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." +#elif TEMP_SENSOR_IS_MAX(1, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_1) && defined(MAX31865_CALIBRATION_OHMS_1)) + #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1/TEMP_SENSOR_REDUNDANT is MAX31865." #endif /** diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e2a1899202..a5922cf553 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -56,13 +56,15 @@ #include "../feature/host_actions.h" #endif +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && ENABLED(TEMP_SENSOR_REDUNDANT_SOURCE) && TEMP_SENSOR_REDUNDANT_SOURCE == n)) + // LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library #if LIB_USR_MAX31855 #include #if PIN_EXISTS(MAX31855_MISO) && PIN_EXISTS(MAX31855_SCK) #define MAX31855_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX31855 && PIN_EXISTS(MAX31855_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX31855) && PIN_EXISTS(MAX31855_CS) #define HAS_MAX31855_TEMP 1 Adafruit_MAX31855 max31855_0 = Adafruit_MAX31855(MAX31855_CS_PIN #if MAX31855_USES_SW_SPI @@ -73,7 +75,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX31855 && PIN_EXISTS(MAX31855_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX31855) && PIN_EXISTS(MAX31855_CS2) #define HAS_MAX31855_TEMP 1 Adafruit_MAX31855 max31855_1 = Adafruit_MAX31855(MAX31855_CS2_PIN #if MAX31855_USES_SW_SPI @@ -96,7 +98,7 @@ #if PIN_EXISTS(MAX31865_MISO) && PIN_EXISTS(MAX31865_SCK) #define MAX31865_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX31865 && PIN_EXISTS(MAX31865_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX31865) && PIN_EXISTS(MAX31865_CS) #define HAS_MAX31865_TEMP 1 Adafruit_MAX31865 max31865_0 = Adafruit_MAX31865(MAX31865_CS_PIN #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) @@ -107,7 +109,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX31865 && PIN_EXISTS(MAX31865_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX31865) && PIN_EXISTS(MAX31865_CS2) #define HAS_MAX31865_TEMP 1 Adafruit_MAX31865 max31865_1 = Adafruit_MAX31865(MAX31865_CS2_PIN #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) @@ -126,7 +128,7 @@ #if PIN_EXISTS(MAX6675_MISO) && PIN_EXISTS(MAX6675_SCK) #define MAX6675_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX6675_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) #define HAS_MAX6675_TEMP 1 MAX6675 max6675_0 = MAX6675(MAX6675_CS_PIN #if MAX6675_USES_SW_SPI @@ -137,7 +139,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX6675_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) #define HAS_MAX6675_TEMP 1 MAX6675 max6675_1 = MAX6675(MAX6675_CS2_PIN #if MAX6675_USES_SW_SPI @@ -154,7 +156,7 @@ #define NO_THERMO_TEMPS 1 #endif -#if (TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC) && PINS_EXIST(MAX6675_SCK, MAX6675_DO) && NO_THERMO_TEMPS +#if (TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && PINS_EXIST(MAX6675_SCK, MAX6675_DO) && NO_THERMO_TEMPS #define THERMO_SEPARATE_SPI 1 #endif @@ -210,15 +212,10 @@ #endif #if HAS_HOTEND_THERMISTOR - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static const temp_entry_t* heater_ttbl_map[2] = { TEMPTABLE_0, TEMPTABLE_1 }; - static constexpr uint8_t heater_ttbllen_map[2] = { TEMPTABLE_0_LEN, TEMPTABLE_1_LEN }; - #else - #define NEXT_TEMPTABLE(N) ,TEMPTABLE_##N - #define NEXT_TEMPTABLE_LEN(N) ,TEMPTABLE_##N##_LEN - static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0 REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); - static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); - #endif + #define NEXT_TEMPTABLE(N) ,TEMPTABLE_##N + #define NEXT_TEMPTABLE_LEN(N) ,TEMPTABLE_##N##_LEN + static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0 REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); + static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); #endif Temperature thermalManager; @@ -257,13 +254,14 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #if HAS_HOTEND hotend_info_t Temperature::temp_hotend[HOTENDS]; - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - temp_info_t Temperature::temp_redundant; - #endif #define _HMT(N) HEATER_##N##_MAXTEMP, const celsius_t Temperature::hotend_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); #endif +#if HAS_TEMP_REDUNDANT + redundant_temp_info_t Temperature::temp_redundant; +#endif + #if ENABLED(AUTO_POWER_E_FANS) uint8_t Temperature::autofan_speed[HOTENDS]; // = { 0 } #endif @@ -1219,8 +1217,12 @@ void Temperature::manage_heater() { if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0); #endif #if TEMP_SENSOR_1_IS_MAX_TC - if (TERN(TEMP_SENSOR_1_AS_REDUNDANT, degHotendRedundant(), degHotend(1)) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); - if (TERN(TEMP_SENSOR_1_AS_REDUNDANT, degHotendRedundant(), degHotend(1)) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); + if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + #endif + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC + if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); + if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); #endif #endif @@ -1254,16 +1256,16 @@ void Temperature::manage_heater() { } #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - // Make sure measured temperatures are close together - if (ABS(degHotend(0) - degHotendRedundant()) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) - _temp_error(H_E0, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); - #endif - } // HOTEND_LOOP #endif // HAS_HOTEND + #if HAS_TEMP_REDUNDANT + // Make sure measured temperatures are close together + if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) + _temp_error((heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); + #endif + #if HAS_AUTO_FAN if (ELAPSED(ms, next_auto_fan_check_ms)) { // only need to check fan state very infrequently checkExtruderAutoFans(); @@ -1613,13 +1615,16 @@ void Temperature::manage_heater() { { true, 0, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 }, #endif #if TEMP_SENSOR_CHAMBER_IS_CUSTOM - { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 } + { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 }, #endif #if TEMP_SENSOR_COOLER_IS_CUSTOM - { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 } + { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 }, #endif #if TEMP_SENSOR_PROBE_IS_CUSTOM - { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 } + { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, + #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + { true, 0, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, #endif }; COPY(user_thermistor, default_user_thermistor); @@ -1653,6 +1658,7 @@ void Temperature::manage_heater() { TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? PSTR("COOLER") :) TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? PSTR("PROBE") :) + TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? PSTR("REDUNDANT") :) nullptr ); SERIAL_EOL(); @@ -1708,7 +1714,7 @@ void Temperature::manage_heater() { // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. celsius_float_t Temperature::analog_to_celsius_hotend(const int16_t raw, const uint8_t e) { - if (e >= HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) { + if (e >= HOTENDS) { SERIAL_ERROR_START(); SERIAL_ECHO(e); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); @@ -1886,6 +1892,28 @@ void Temperature::manage_heater() { } #endif // HAS_TEMP_PROBE +#if HAS_TEMP_REDUNDANT + // For redundant temperature measurement. + celsius_float_t Temperature::analog_to_celsius_redundant(const int16_t raw) { + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); + #elif TEMP_SENSOR_REDUNDANT_IS_AD595 + return TEMP_AD595(raw); + #elif TEMP_SENSOR_REDUNDANT_IS_AD8495 + return TEMP_AD8495(raw); + #else + UNUSED(raw); + return 0; + #endif + } +#endif // HAS_TEMP_REDUNDANT + /** * Convert the raw sensor readings into actual Celsius temperatures and * validate raw temperatures. Bad readings generate min/maxtemp errors. @@ -1903,26 +1931,34 @@ void Temperature::updateTemperaturesFromRawValues() { watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); - TERN_(TEMP_SENSOR_1_IS_MAX_TC, TERN(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant, temp_hotend[1]).raw = READ_MAX_TC(1)); + TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].raw = READ_MAX_TC(1)); + TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(TEMP_SENSOR_REDUNDANT_SOURCE)); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant.celsius = analog_to_celsius_hotend(temp_redundant.raw, 1)); - TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); - TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); - TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); + TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); + TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.celsius = analog_to_celsius_redundant(temp_redundant.raw)); TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); #if HAS_HOTEND - static constexpr int8_t temp_dir[] = { - TERN(TEMP_SENSOR_0_IS_MAX_TC, 0, TEMPDIR(0)) + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 0 + #else + TEMPDIR(0) + #endif #if HAS_MULTI_HOTEND - , TERN(TEMP_SENSOR_1_IS_MAX_TC, 0, TEMPDIR(1)) + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + , 0 + #else + , TEMPDIR(1) + #endif #if HOTENDS > 2 #define _TEMPDIR(N) , TEMPDIR(N) REPEAT_S(2, HOTENDS, _TEMPDIR) @@ -2031,42 +2067,42 @@ void Temperature::init() { #endif // Init (and disable) SPI thermocouples - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX6675_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) OUT_WRITE(MAX6675_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX6675_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) OUT_WRITE(MAX6675_CS2_PIN, HIGH); #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX31855_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31855_CS) OUT_WRITE(MAX31855_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX31855_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31855_CS2) OUT_WRITE(MAX31855_CS2_PIN, HIGH); #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX31865_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31865_CS) OUT_WRITE(MAX31865_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX31865_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31865_CS2) OUT_WRITE(MAX31865_CS2_PIN, HIGH); #endif #if HAS_MAX31865_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX31865, max31865_0.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - TERN_(TEMP_SENSOR_1_IS_MAX31865, max31865_1.begin(MAX31865_2WIRE)); + TERN_(TEMP_SENSOR_IS_MAX(0, MAX31865), max31865_0.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + TERN_(TEMP_SENSOR_IS_MAX(1, MAX31865), max31865_1.begin(MAX31865_2WIRE)); #endif #if HAS_MAX31855_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX31855, max31855_0.begin()); - TERN_(TEMP_SENSOR_1_IS_MAX31855, max31855_1.begin()); + TERN_(TEMP_SENSOR_IS_MAX(0, MAX31855), max31855_0.begin()); + TERN_(TEMP_SENSOR_IS_MAX(1, MAX31855), max31855_1.begin()); #endif #if HAS_MAX6675_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX6675, max6675_0.begin()); - TERN_(TEMP_SENSOR_1_IS_MAX6675, max6675_1.begin()); + TERN_(TEMP_SENSOR_IS_MAX(0, MAX6675), max6675_0.begin()); + TERN_(TEMP_SENSOR_IS_MAX(1, MAX6675), max6675_1.begin()); #endif #if MB(RUMBA) // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector #define _AD(N) (TEMP_SENSOR_##N##_IS_AD595 || TEMP_SENSOR_##N##_IS_AD8495) - #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) + #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) || _AD(REDUNDANT) MCUCR = _BV(JTD); MCUCR = _BV(JTD); #endif @@ -2074,10 +2110,22 @@ void Temperature::init() { // Thermistor activation by MCU pin #if PIN_EXISTS(TEMP_0_TR_ENABLE) - OUT_WRITE(TEMP_0_TR_ENABLE_PIN, ENABLED(TEMP_SENSOR_0_IS_MAX_TC)); + OUT_WRITE(TEMP_0_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 1 + #else + 0 + #endif + ); #endif #if PIN_EXISTS(TEMP_1_TR_ENABLE) - OUT_WRITE(TEMP_1_TR_ENABLE_PIN, ENABLED(TEMP_SENSOR_1_IS_MAX_TC)); + OUT_WRITE(TEMP_1_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + 1 + #else + 0 + #endif + ); #endif #if HAS_HEATER_0 @@ -2206,6 +2254,9 @@ void Temperature::init() { #if HAS_TEMP_ADC_PROBE HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif + #if HAS_TEMP_ADC_REDUNDANT + HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); + #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) HAL_ANALOG_SELECT(FILWIDTH_PIN); #endif @@ -2268,7 +2319,7 @@ void Temperature::init() { temp_range[NR].raw_max -= TEMPDIR(NR) * (OVERSAMPLENR); \ }while(0) - #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR_ ##N## _THERMISTOR_ID && TEMP_SENSOR_ ##N## _THERMISTOR_ID != 998 && TEMP_SENSOR_ ##N## _THERMISTOR_ID != 999 && defined(HEATER_##N##_##M##TEMP)) + #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR_##N > 0 && TEMP_SENSOR_##N != 998 && TEMP_SENSOR_##N != 999 && defined(HEATER_##N##_##M##TEMP)) #if _MINMAX_TEST(0, MIN) _TEMP_MIN_E(0); @@ -2335,6 +2386,22 @@ void Temperature::init() { while (analog_to_celsius_cooler(mintemp_raw_COOLER) > COOLER_MINTEMP) mintemp_raw_COOLER += TEMPDIR(COOLER) * (OVERSAMPLENR); while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif + + #if HAS_TEMP_REDUNDANT + temp_redundant.target = &( + #if TEMP_SENSOR_REDUNDANT_TARGET == -5 && HAS_TEMP_COOLER + temp_cooler + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && HAS_TEMP_PROBE + temp_probe + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && HAS_TEMP_CHAMBER + temp_chamber + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && HAS_TEMP_BED + temp_bed + #else + temp_hotend[TEMP_SENSOR_REDUNDANT_TARGET] + #endif + ); + #endif } #if HAS_THERMAL_PROTECTION @@ -2373,7 +2440,7 @@ void Temperature::init() { , " ; Idle Timeout:", heater_idle[idle_index].timed_out #endif ); - //*/ + */ #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart @@ -2570,12 +2637,12 @@ void Temperature::disable_all_heaters() { #else constexpr uint8_t hindex = 0; #define THERMO_TEMP(I) max_tc_temp - #if TEMP_SENSOR_1_IS_MAX31865 + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) #define THERMO_SEL(A,B) B #else #define THERMO_SEL(A,B) A #endif - #if TEMP_SENSOR_0_IS_MAX6675 + #if TEMP_SENSOR_IS_MAX(0, MAX6675) #define MAX6675_WRITE(V) WRITE(MAX6675_SS_PIN, V) #define MAX6675_SET_OUTPUT() SET_OUTPUT(MAX6675_SS_PIN) #else @@ -2723,12 +2790,12 @@ void Temperature::update_raw_temperatures() { temp_hotend[0].update(); #endif - #if HAS_TEMP_ADC_1 - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - temp_redundant.update(); - #elif !TEMP_SENSOR_1_IS_MAX_TC - temp_hotend[1].update(); - #endif + #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_1_IS_MAX_TC + temp_hotend[1].update(); + #endif + + #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_REDUNDANT_IS_MAX_TC + temp_redundant.update(); #endif TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); @@ -2764,13 +2831,13 @@ void Temperature::readings_ready() { #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].reset(); - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant.reset()); #endif TERN_(HAS_HEATED_BED, temp_bed.reset()); TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); TERN_(HAS_TEMP_PROBE, temp_probe.reset()); TERN_(HAS_TEMP_COOLER, temp_cooler.reset()); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.reset()); TERN_(HAS_JOY_ADC_X, joystick.x.reset()); TERN_(HAS_JOY_ADC_Y, joystick.y.reset()); @@ -3196,9 +3263,14 @@ void Temperature::isr() { case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif + #if HAS_TEMP_ADC_REDUNDANT + case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; + #endif + #if HAS_TEMP_ADC_1 case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; - case MeasureTemp_1: ACCUMULATE_ADC(TERN(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant, temp_hotend[1])); break; + case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 @@ -3332,6 +3404,7 @@ void Temperature::isr() { * Chamber: " C:nnn.nn /nnn.nn" * Probe: " P:nnn.nn /nnn.nn" * Cooler: " L:nnn.nn /nnn.nn" + * Redundant: " R:nnn.nn /nnn.nn" * Extruder: " T0:nnn.nn /nnn.nn" * With ADC: " T0:nnn.nn /nnn.nn (nnn.nn)" */ @@ -3356,7 +3429,7 @@ void Temperature::isr() { #if HAS_TEMP_COOLER case H_COOLER: k = 'L'; break; #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) + #if HAS_TEMP_REDUNDANT case H_REDUNDANT: k = 'R'; break; #endif } @@ -3382,13 +3455,10 @@ void Temperature::isr() { } void Temperature::print_heater_states(const uint8_t target_extruder - OPTARG(TEMP_SENSOR_1_AS_REDUNDANT, const bool include_r/*=false*/) + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r/*=false*/) ) { #if HAS_TEMP_HOTEND print_heater_state(H_NONE, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (include_r) print_heater_state(H_REDUNDANT, degHotendRedundant(), degTargetHotend(0) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTempRedundant())); - #endif #endif #if HAS_HEATED_BED print_heater_state(H_BED, degBed(), degTargetBed() OPTARG(SHOW_TEMP_ADC_VALUES, rawBedTemp())); @@ -3402,6 +3472,9 @@ void Temperature::isr() { #if HAS_TEMP_PROBE print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp()) ); #endif + #if HAS_TEMP_REDUNDANT + if (include_r) print_heater_state(H_REDUNDANT, degRedundant(), degRedundantTarget() OPTARG(SHOW_TEMP_ADC_VALUES, rawRedundantTemp())); + #endif #if HAS_MULTI_HOTEND HOTEND_LOOP() print_heater_state((heater_id_t)e, degHotend(e), degTargetHotend(e) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(e))); #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 660fde8af6..e0dffc3f3a 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -105,6 +105,9 @@ enum ADCSensorState : char { #if HAS_TEMP_ADC_PROBE PrepareTemp_PROBE, MeasureTemp_PROBE, #endif + #if HAS_TEMP_ADC_REDUNDANT + PrepareTemp_REDUNDANT, MeasureTemp_REDUNDANT, + #endif #if HAS_TEMP_ADC_1 PrepareTemp_1, MeasureTemp_1, #endif @@ -185,6 +188,13 @@ typedef struct TempInfo { inline void update() { raw = acc; } } temp_info_t; +#if HAS_TEMP_REDUNDANT + // A redundant temperature sensor + typedef struct RedundantTempInfo : public TempInfo { + temp_info_t* target; + } redundant_temp_info_t; +#endif + // A PWM heater with temperature sensor typedef struct HeaterInfo : public TempInfo { celsius_t target; @@ -299,9 +309,12 @@ typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_ra #if TEMP_SENSOR_CHAMBER_IS_CUSTOM CTI_CHAMBER, #endif - #if COOLER_USER_THERMISTOR + #if TEMP_SENSOR_COOLER_IS_CUSTOM CTI_COOLER, #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + CTI_REDUNDANT, + #endif USER_THERMISTORS }; @@ -323,9 +336,6 @@ class Temperature { public: #if HAS_HOTEND - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static temp_info_t temp_redundant; - #endif static hotend_info_t temp_hotend[HOTENDS]; static const celsius_t hotend_maxtemp[HOTENDS]; static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } @@ -342,6 +352,9 @@ class Temperature { #if ENABLED(HAS_TEMP_COOLER) static cooler_info_t temp_cooler; #endif + #if HAS_TEMP_REDUNDANT + static redundant_temp_info_t temp_redundant; + #endif #if ENABLED(AUTO_POWER_E_FANS) static uint8_t autofan_speed[HOTENDS]; @@ -538,6 +551,9 @@ class Temperature { #if HAS_TEMP_COOLER static celsius_float_t analog_to_celsius_cooler(const int16_t raw); #endif + #if HAS_TEMP_REDUNDANT + static celsius_float_t analog_to_celsius_redundant(const int16_t raw); + #endif #if HAS_FAN @@ -626,10 +642,6 @@ class Temperature { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius); } - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static inline celsius_float_t degHotendRedundant() { return temp_redundant.celsius; } - #endif - static inline celsius_t wholeDegHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, static_cast(temp_hotend[HOTEND_INDEX].celsius + 0.5f)); } @@ -638,9 +650,6 @@ class Temperature { static inline int16_t rawHotendTemp(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw); } - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static inline int16_t rawHotendTempRedundant() { return temp_redundant.raw; } - #endif #endif static inline celsius_t degTargetHotend(const uint8_t E_NAME) { @@ -778,6 +787,17 @@ class Temperature { #endif #endif + #if HAS_TEMP_REDUNDANT + #if ENABLED(SHOW_TEMP_ADC_VALUES) + static inline int16_t rawRedundantTemp() { return temp_redundant.raw; } + static inline int16_t rawRedundanTargetTemp() { return (*temp_redundant.target).raw; } + #endif + static inline celsius_float_t degRedundant() { return temp_redundant.celsius; } + static inline celsius_float_t degRedundantTarget() { return (*temp_redundant.target).celsius; } + static inline celsius_t wholeDegRedundant() { return static_cast(temp_redundant.celsius + 0.5f); } + static inline celsius_t wholeDegRedundantTarget() { return static_cast((*temp_redundant.target).celsius + 0.5f); } + #endif + #if HAS_COOLER static inline void setTargetCooler(const celsius_t celsius) { temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET); @@ -855,7 +875,7 @@ class Temperature { #if HAS_TEMP_SENSOR static void print_heater_states(const uint8_t target_extruder - OPTARG(TEMP_SENSOR_1_AS_REDUNDANT, const bool include_r=false) + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r=false) ); #if ENABLED(AUTO_REPORT_TEMPERATURES) struct AutoReportTemp { static void report(); }; @@ -888,7 +908,7 @@ class Temperature { // MAX Thermocouples #if HAS_MAX_TC - #define MAX_TC_COUNT 1 + BOTH(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC) + #define MAX_TC_COUNT COUNT_ENABLED(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC, TEMP_SENSOR_REDUNDANT_IS_MAX_TC) #if MAX_TC_COUNT > 1 #define HAS_MULTI_MAX_TC 1 #define READ_MAX_TC(N) read_max_tc(N) diff --git a/Marlin/src/module/thermistor/thermistor_1.h b/Marlin/src/module/thermistor/thermistor_1.h index fad7908375..2ebf8da550 100644 --- a/Marlin/src/module/thermistor/thermistor_1.h +++ b/Marlin/src/module/thermistor/thermistor_1.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_1[] PROGMEM = { +constexpr temp_entry_t temptable_1[] PROGMEM = { { OV( 23), 300 }, { OV( 25), 295 }, { OV( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_10.h b/Marlin/src/module/thermistor/thermistor_10.h index c24ad40bf4..9f2285c3fd 100644 --- a/Marlin/src/module/thermistor/thermistor_10.h +++ b/Marlin/src/module/thermistor/thermistor_10.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, RS thermistor 198-961 -const temp_entry_t temptable_10[] PROGMEM = { +constexpr temp_entry_t temptable_10[] PROGMEM = { { OV( 1), 929 }, { OV( 36), 299 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_1010.h b/Marlin/src/module/thermistor/thermistor_1010.h index 8ab5e3b364..6f2e3ab318 100644 --- a/Marlin/src/module/thermistor/thermistor_1010.h +++ b/Marlin/src/module/thermistor/thermistor_1010.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1010 1 // Pt1000 with 1k0 pullup -const temp_entry_t temptable_1010[] PROGMEM = { +constexpr temp_entry_t temptable_1010[] PROGMEM = { PtLine( 0, 1000, 1000), PtLine( 25, 1000, 1000), PtLine( 50, 1000, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_1047.h b/Marlin/src/module/thermistor/thermistor_1047.h index 6e1b61f9d0..fb901d0a8d 100644 --- a/Marlin/src/module/thermistor/thermistor_1047.h +++ b/Marlin/src/module/thermistor/thermistor_1047.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1047 1 // Pt1000 with 4k7 pullup -const temp_entry_t temptable_1047[] PROGMEM = { +constexpr temp_entry_t temptable_1047[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 1000, 4700), PtLine( 50, 1000, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_11.h b/Marlin/src/module/thermistor/thermistor_11.h index 345d009a64..52f89814e7 100644 --- a/Marlin/src/module/thermistor/thermistor_11.h +++ b/Marlin/src/module/thermistor/thermistor_11.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, QU-BD silicone bed QWG-104F-3950 thermistor -const temp_entry_t temptable_11[] PROGMEM = { +constexpr temp_entry_t temptable_11[] PROGMEM = { { OV( 1), 938 }, { OV( 31), 314 }, { OV( 41), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_110.h b/Marlin/src/module/thermistor/thermistor_110.h index 215495e2c6..5d76d1ee1b 100644 --- a/Marlin/src/module/thermistor/thermistor_110.h +++ b/Marlin/src/module/thermistor/thermistor_110.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_110 1 // Pt100 with 1k0 pullup -const temp_entry_t temptable_110[] PROGMEM = { +constexpr temp_entry_t temptable_110[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 1000), PtLine( 50, 100, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_12.h b/Marlin/src/module/thermistor/thermistor_12.h index d1ee23b2b7..c0cbd254cf 100644 --- a/Marlin/src/module/thermistor/thermistor_12.h +++ b/Marlin/src/module/thermistor/thermistor_12.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4700 K, 4.7 kOhm pull-up, (personal calibration for Makibox hot bed) -const temp_entry_t temptable_12[] PROGMEM = { +constexpr temp_entry_t temptable_12[] PROGMEM = { { OV( 35), 180 }, // top rating 180C { OV( 211), 140 }, { OV( 233), 135 }, diff --git a/Marlin/src/module/thermistor/thermistor_13.h b/Marlin/src/module/thermistor/thermistor_13.h index bb622240c8..7e87373948 100644 --- a/Marlin/src/module/thermistor/thermistor_13.h +++ b/Marlin/src/module/thermistor/thermistor_13.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor -const temp_entry_t temptable_13[] PROGMEM = { +constexpr temp_entry_t temptable_13[] PROGMEM = { { OV( 20.04), 300 }, { OV( 23.19), 290 }, { OV( 26.71), 280 }, diff --git a/Marlin/src/module/thermistor/thermistor_147.h b/Marlin/src/module/thermistor/thermistor_147.h index 6d846ad5be..542e4844ec 100644 --- a/Marlin/src/module/thermistor/thermistor_147.h +++ b/Marlin/src/module/thermistor/thermistor_147.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_147 1 // Pt100 with 4k7 pullup -const temp_entry_t temptable_147[] PROGMEM = { +constexpr temp_entry_t temptable_147[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 4700), PtLine( 50, 100, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_15.h b/Marlin/src/module/thermistor/thermistor_15.h index 46dcce8c1e..ce98248793 100644 --- a/Marlin/src/module/thermistor/thermistor_15.h +++ b/Marlin/src/module/thermistor/thermistor_15.h @@ -22,7 +22,7 @@ #pragma once // 100k bed thermistor in JGAurora A5. Calibrated by Sam Pinches 21st Jan 2018 using cheap k-type thermocouple inserted into heater block, using TM-902C meter. -const temp_entry_t temptable_15[] PROGMEM = { +constexpr temp_entry_t temptable_15[] PROGMEM = { { OV( 31), 275 }, { OV( 33), 270 }, { OV( 35), 260 }, diff --git a/Marlin/src/module/thermistor/thermistor_17.h b/Marlin/src/module/thermistor/thermistor_17.h index 32b5bb77a8..55d3bc39d0 100644 --- a/Marlin/src/module/thermistor/thermistor_17.h +++ b/Marlin/src/module/thermistor/thermistor_17.h @@ -22,7 +22,7 @@ #pragma once // Dagoma NTC 100k white thermistor -const temp_entry_t temptable_17[] PROGMEM = { +constexpr temp_entry_t temptable_17[] PROGMEM = { { OV( 16), 309 }, { OV( 18), 307 }, { OV( 20), 300 }, diff --git a/Marlin/src/module/thermistor/thermistor_18.h b/Marlin/src/module/thermistor/thermistor_18.h index 9c2d81b3e6..061cf78129 100644 --- a/Marlin/src/module/thermistor/thermistor_18.h +++ b/Marlin/src/module/thermistor/thermistor_18.h @@ -22,7 +22,7 @@ #pragma once // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - version (measured/tested/approved) -const temp_entry_t temptable_18[] PROGMEM = { +constexpr temp_entry_t temptable_18[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 284 }, { OV( 20), 275 }, diff --git a/Marlin/src/module/thermistor/thermistor_2.h b/Marlin/src/module/thermistor/thermistor_2.h index d0e1e4f3df..a899fd17ee 100644 --- a/Marlin/src/module/thermistor/thermistor_2.h +++ b/Marlin/src/module/thermistor/thermistor_2.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance // -const temp_entry_t temptable_2[] PROGMEM = { +constexpr temp_entry_t temptable_2[] PROGMEM = { { OV( 1), 848 }, { OV( 30), 300 }, // top rating 300C { OV( 34), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_20.h b/Marlin/src/module/thermistor/thermistor_20.h index 73094f1460..a8267e93e4 100644 --- a/Marlin/src/module/thermistor/thermistor_20.h +++ b/Marlin/src/module/thermistor/thermistor_20.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_20 1 // Pt100 with INA826 amp on Ultimaker v2.0 electronics -const temp_entry_t temptable_20[] PROGMEM = { +constexpr temp_entry_t temptable_20[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_201.h b/Marlin/src/module/thermistor/thermistor_201.h index 44d5280681..9c083a2d1b 100644 --- a/Marlin/src/module/thermistor/thermistor_201.h +++ b/Marlin/src/module/thermistor/thermistor_201.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_201 1 // Pt100 with LMV324 amp on Overlord v1.1 electronics -const temp_entry_t temptable_201[] PROGMEM = { +constexpr temp_entry_t temptable_201[] PROGMEM = { { OV( 0), 0 }, { OV( 8), 1 }, { OV( 23), 6 }, diff --git a/Marlin/src/module/thermistor/thermistor_202.h b/Marlin/src/module/thermistor/thermistor_202.h index c5229607ae..e1b0ee258e 100644 --- a/Marlin/src/module/thermistor/thermistor_202.h +++ b/Marlin/src/module/thermistor/thermistor_202.h @@ -3,7 +3,7 @@ // Temptable sent from dealer technologyoutlet.co.uk // -const temp_entry_t temptable_202[] PROGMEM = { +constexpr temp_entry_t temptable_202[] PROGMEM = { { OV( 1), 864 }, { OV( 35), 300 }, { OV( 38), 295 }, diff --git a/Marlin/src/module/thermistor/thermistor_21.h b/Marlin/src/module/thermistor/thermistor_21.h index 2ca705b950..f8a5de2e15 100644 --- a/Marlin/src/module/thermistor/thermistor_21.h +++ b/Marlin/src/module/thermistor/thermistor_21.h @@ -28,7 +28,7 @@ // Pt100 with INA826 amplifier board with 5v supply based on Thermistor 20, with 3v3 ADC reference on the mainboard. // If the ADC reference and INA826 board supply voltage are identical, Thermistor 20 instead. -const temp_entry_t temptable_21[] PROGMEM = { +constexpr temp_entry_t temptable_21[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_22.h b/Marlin/src/module/thermistor/thermistor_22.h index 6f4a31050a..90e1af8c1a 100644 --- a/Marlin/src/module/thermistor/thermistor_22.h +++ b/Marlin/src/module/thermistor/thermistor_22.h @@ -21,7 +21,7 @@ */ // 100k hotend thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_22[] PROGMEM = { +constexpr temp_entry_t temptable_22[] PROGMEM = { { OV( 1), 352 }, { OV( 6), 341 }, { OV( 11), 330 }, diff --git a/Marlin/src/module/thermistor/thermistor_23.h b/Marlin/src/module/thermistor/thermistor_23.h index 02ff9fb2b6..9b806af5b7 100644 --- a/Marlin/src/module/thermistor/thermistor_23.h +++ b/Marlin/src/module/thermistor/thermistor_23.h @@ -21,7 +21,7 @@ */ // 100k hotbed thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_23[] PROGMEM = { +constexpr temp_entry_t temptable_23[] PROGMEM = { { OV( 1), 938 }, { OV( 11), 423 }, { OV( 21), 351 }, diff --git a/Marlin/src/module/thermistor/thermistor_3.h b/Marlin/src/module/thermistor/thermistor_3.h index 74e00e2ba4..cb6d75738e 100644 --- a/Marlin/src/module/thermistor/thermistor_3.h +++ b/Marlin/src/module/thermistor/thermistor_3.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4120 K, 4.7 kOhm pull-up, mendel-parts -const temp_entry_t temptable_3[] PROGMEM = { +constexpr temp_entry_t temptable_3[] PROGMEM = { { OV( 1), 864 }, { OV( 21), 300 }, { OV( 25), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_30.h b/Marlin/src/module/thermistor/thermistor_30.h index bc1781b135..daf4d29aa7 100644 --- a/Marlin/src/module/thermistor/thermistor_30.h +++ b/Marlin/src/module/thermistor/thermistor_30.h @@ -28,7 +28,7 @@ // B Value Tolerance + / - 1% // Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) // Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak) -const temp_entry_t temptable_30[] PROGMEM = { +constexpr temp_entry_t temptable_30[] PROGMEM = { { OV( 1), 938 }, { OV( 298), 125 }, // 1193 - 125° { OV( 321), 121 }, // 1285 - 121° diff --git a/Marlin/src/module/thermistor/thermistor_331.h b/Marlin/src/module/thermistor/thermistor_331.h index ccb0f6b62d..847dbc30a0 100644 --- a/Marlin/src/module/thermistor/thermistor_331.h +++ b/Marlin/src/module/thermistor/thermistor_331.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.5)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_331[] PROGMEM = { +constexpr temp_entry_t temptable_331[] PROGMEM = { { OVM( 23), 300 }, { OVM( 25), 295 }, { OVM( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_332.h b/Marlin/src/module/thermistor/thermistor_332.h index 9502f1bdae..83a5d39f0f 100644 --- a/Marlin/src/module/thermistor/thermistor_332.h +++ b/Marlin/src/module/thermistor/thermistor_332.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.327)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_332[] PROGMEM = { +constexpr temp_entry_t temptable_332[] PROGMEM = { { OVM( 268), 150 }, { OVM( 293), 145 }, { OVM( 320), 141 }, diff --git a/Marlin/src/module/thermistor/thermistor_4.h b/Marlin/src/module/thermistor/thermistor_4.h index 92d907249b..98192a1124 100644 --- a/Marlin/src/module/thermistor/thermistor_4.h +++ b/Marlin/src/module/thermistor/thermistor_4.h @@ -22,7 +22,7 @@ #pragma once // R25 = 10 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, Generic 10k thermistor -const temp_entry_t temptable_4[] PROGMEM = { +constexpr temp_entry_t temptable_4[] PROGMEM = { { OV( 1), 430 }, { OV( 54), 137 }, { OV( 107), 107 }, diff --git a/Marlin/src/module/thermistor/thermistor_5.h b/Marlin/src/module/thermistor/thermistor_5.h index 1d5fa2fec7..69ef99fae1 100644 --- a/Marlin/src/module/thermistor/thermistor_5.h +++ b/Marlin/src/module/thermistor/thermistor_5.h @@ -26,7 +26,7 @@ // ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan) // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance -const temp_entry_t temptable_5[] PROGMEM = { +constexpr temp_entry_t temptable_5[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 300 }, // top rating 300C { OV( 20), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_501.h b/Marlin/src/module/thermistor/thermistor_501.h index d40e341f7e..0e142628ec 100644 --- a/Marlin/src/module/thermistor/thermistor_501.h +++ b/Marlin/src/module/thermistor/thermistor_501.h @@ -22,7 +22,7 @@ #pragma once // 100k Zonestar thermistor. Adjusted By Hally -const temp_entry_t temptable_501[] PROGMEM = { +constexpr temp_entry_t temptable_501[] PROGMEM = { { OV( 1), 713 }, { OV( 14), 300 }, // Top rating 300C { OV( 16), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_502.h b/Marlin/src/module/thermistor/thermistor_502.h index 69cee2431c..3ddbf30d47 100644 --- a/Marlin/src/module/thermistor/thermistor_502.h +++ b/Marlin/src/module/thermistor/thermistor_502.h @@ -23,7 +23,7 @@ // Unknown thermistor for the Zonestar P802M hot bed. Adjusted By Nerseth // These were the shipped settings from Zonestar in original firmware: P802M_8_Repetier_V1.6_Zonestar.zip -const temp_entry_t temptable_502[] PROGMEM = { +constexpr temp_entry_t temptable_502[] PROGMEM = { { OV( 56.0 / 4), 300 }, { OV( 187.0 / 4), 250 }, { OV( 615.0 / 4), 190 }, diff --git a/Marlin/src/module/thermistor/thermistor_503.h b/Marlin/src/module/thermistor/thermistor_503.h index fc4bffffdb..6ffe4b4a66 100644 --- a/Marlin/src/module/thermistor/thermistor_503.h +++ b/Marlin/src/module/thermistor/thermistor_503.h @@ -23,7 +23,7 @@ // Zonestar (Z8XM2) Heated Bed thermistor. Added By AvanOsch // These are taken from the Zonestar settings in original Repetier firmware: Z8XM2_ZRIB_LCD12864_V51.zip -const temp_entry_t temptable_503[] PROGMEM = { +constexpr temp_entry_t temptable_503[] PROGMEM = { { OV( 12), 300 }, { OV( 27), 270 }, { OV( 47), 250 }, diff --git a/Marlin/src/module/thermistor/thermistor_51.h b/Marlin/src/module/thermistor/thermistor_51.h index d02dd47ba5..ee63a0e61b 100644 --- a/Marlin/src/module/thermistor/thermistor_51.h +++ b/Marlin/src/module/thermistor/thermistor_51.h @@ -26,7 +26,7 @@ // Verified by linagee. // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: Twice the resolution and better linearity from 150C to 200C -const temp_entry_t temptable_51[] PROGMEM = { +constexpr temp_entry_t temptable_51[] PROGMEM = { { OV( 1), 350 }, { OV( 190), 250 }, // top rating 250C { OV( 203), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_512.h b/Marlin/src/module/thermistor/thermistor_512.h index e8021e1e48..e380b4a16b 100644 --- a/Marlin/src/module/thermistor/thermistor_512.h +++ b/Marlin/src/module/thermistor/thermistor_512.h @@ -22,7 +22,7 @@ // 100k thermistor supplied with RPW-Ultra hotend, 4.7k pullup -const temp_entry_t temptable_512[] PROGMEM = { +constexpr temp_entry_t temptable_512[] PROGMEM = { { OV(26), 300 }, { OV(28), 295 }, { OV(30), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_52.h b/Marlin/src/module/thermistor/thermistor_52.h index 5c9cb9dc4d..f3bb75d462 100644 --- a/Marlin/src/module/thermistor/thermistor_52.h +++ b/Marlin/src/module/thermistor/thermistor_52.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_52[] PROGMEM = { +constexpr temp_entry_t temptable_52[] PROGMEM = { { OV( 1), 500 }, { OV( 125), 300 }, // top rating 300C { OV( 142), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_55.h b/Marlin/src/module/thermistor/thermistor_55.h index 707b7d420a..41004a97ef 100644 --- a/Marlin/src/module/thermistor/thermistor_55.h +++ b/Marlin/src/module/thermistor/thermistor_55.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_55[] PROGMEM = { +constexpr temp_entry_t temptable_55[] PROGMEM = { { OV( 1), 500 }, { OV( 76), 300 }, { OV( 87), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_6.h b/Marlin/src/module/thermistor/thermistor_6.h index 68113419e5..b5e79a9b0e 100644 --- a/Marlin/src/module/thermistor/thermistor_6.h +++ b/Marlin/src/module/thermistor/thermistor_6.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 8.2 kOhm pull-up, 100k Epcos (?) thermistor -const temp_entry_t temptable_6[] PROGMEM = { +constexpr temp_entry_t temptable_6[] PROGMEM = { { OV( 1), 350 }, { OV( 28), 250 }, // top rating 250C { OV( 31), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_60.h b/Marlin/src/module/thermistor/thermistor_60.h index a3fe50559f..a057080e45 100644 --- a/Marlin/src/module/thermistor/thermistor_60.h +++ b/Marlin/src/module/thermistor/thermistor_60.h @@ -31,7 +31,7 @@ // beta: 3950 // min adc: 1 at 0.0048828125 V // max adc: 1023 at 4.9951171875 V -const temp_entry_t temptable_60[] PROGMEM = { +constexpr temp_entry_t temptable_60[] PROGMEM = { { OV( 51), 272 }, { OV( 61), 258 }, { OV( 71), 247 }, diff --git a/Marlin/src/module/thermistor/thermistor_61.h b/Marlin/src/module/thermistor/thermistor_61.h index ed4c4c8859..deeec356a1 100644 --- a/Marlin/src/module/thermistor/thermistor_61.h +++ b/Marlin/src/module/thermistor/thermistor_61.h @@ -30,7 +30,7 @@ // Resistance Tolerance + / -1% // B Value 3950K at 25/50 deg. C // B Value Tolerance + / - 1% -const temp_entry_t temptable_61[] PROGMEM = { +constexpr temp_entry_t temptable_61[] PROGMEM = { { OV( 2.00), 420 }, // Guestimate to ensure we dont lose a reading and drop temps to -50 when over { OV( 12.07), 350 }, { OV( 12.79), 345 }, diff --git a/Marlin/src/module/thermistor/thermistor_66.h b/Marlin/src/module/thermistor/thermistor_66.h index 0ad5994ea8..3b057ac696 100644 --- a/Marlin/src/module/thermistor/thermistor_66.h +++ b/Marlin/src/module/thermistor/thermistor_66.h @@ -22,7 +22,7 @@ #pragma once // R25 = 2.5 MOhm, beta25 = 4500 K, 4.7 kOhm pull-up, DyzeDesign 500 °C Thermistor -const temp_entry_t temptable_66[] PROGMEM = { +constexpr temp_entry_t temptable_66[] PROGMEM = { { OV( 17.5), 850 }, { OV( 17.9), 500 }, { OV( 21.7), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_666.h b/Marlin/src/module/thermistor/thermistor_666.h index 490dbd5f3e..bba3e606fc 100644 --- a/Marlin/src/module/thermistor/thermistor_666.h +++ b/Marlin/src/module/thermistor/thermistor_666.h @@ -33,7 +33,7 @@ * B: 0.00031362 * C: -2.03978e-07 */ -const temp_entry_t temptable_666[] PROGMEM = { +constexpr temp_entry_t temptable_666[] PROGMEM = { { OV( 1), 794 }, { OV( 18), 288 }, { OV( 35), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_67.h b/Marlin/src/module/thermistor/thermistor_67.h index 7d6d7f697d..10fa9310b1 100644 --- a/Marlin/src/module/thermistor/thermistor_67.h +++ b/Marlin/src/module/thermistor/thermistor_67.h @@ -22,7 +22,7 @@ #pragma once // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor -const temp_entry_t temptable_67[] PROGMEM = { +constexpr temp_entry_t temptable_67[] PROGMEM = { { OV( 22 ), 500 }, { OV( 23 ), 490 }, { OV( 25 ), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_7.h b/Marlin/src/module/thermistor/thermistor_7.h index 7a73755984..964897859e 100644 --- a/Marlin/src/module/thermistor/thermistor_7.h +++ b/Marlin/src/module/thermistor/thermistor_7.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3974 K, 4.7 kOhm pull-up, Honeywell 135-104LAG-J01 -const temp_entry_t temptable_7[] PROGMEM = { +constexpr temp_entry_t temptable_7[] PROGMEM = { { OV( 1), 941 }, { OV( 19), 362 }, { OV( 37), 299 }, // top rating 300C diff --git a/Marlin/src/module/thermistor/thermistor_70.h b/Marlin/src/module/thermistor/thermistor_70.h index 466b925553..f0163dcabc 100644 --- a/Marlin/src/module/thermistor/thermistor_70.h +++ b/Marlin/src/module/thermistor/thermistor_70.h @@ -26,7 +26,7 @@ // ANENG AN8009 DMM with a K-type probe used for measurements. // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, bqh2 stock thermistor -const temp_entry_t temptable_70[] PROGMEM = { +constexpr temp_entry_t temptable_70[] PROGMEM = { { OV( 18), 270 }, { OV( 27), 248 }, { OV( 34), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_71.h b/Marlin/src/module/thermistor/thermistor_71.h index abd7fc5b98..c94b4d5bbc 100644 --- a/Marlin/src/module/thermistor/thermistor_71.h +++ b/Marlin/src/module/thermistor/thermistor_71.h @@ -27,7 +27,7 @@ // Beta = 3974 // R1 = 0 Ohm // R2 = 4700 Ohm -const temp_entry_t temptable_71[] PROGMEM = { +constexpr temp_entry_t temptable_71[] PROGMEM = { { OV( 35), 300 }, { OV( 51), 269 }, { OV( 59), 258 }, diff --git a/Marlin/src/module/thermistor/thermistor_75.h b/Marlin/src/module/thermistor/thermistor_75.h index 79800d2e40..bb2ecce7dc 100644 --- a/Marlin/src/module/thermistor/thermistor_75.h +++ b/Marlin/src/module/thermistor/thermistor_75.h @@ -34,7 +34,7 @@ //#define HIGH_TEMP_RANGE_75 -const temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor +constexpr temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor { OV(111.06), 200 }, // v=0.542 r=571.747 res=0.501 degC/count #ifdef HIGH_TEMP_RANGE_75 diff --git a/Marlin/src/module/thermistor/thermistor_8.h b/Marlin/src/module/thermistor/thermistor_8.h index 9e19168fed..4b0f791f16 100644 --- a/Marlin/src/module/thermistor/thermistor_8.h +++ b/Marlin/src/module/thermistor/thermistor_8.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 10 kOhm pull-up, NTCS0603E3104FHT -const temp_entry_t temptable_8[] PROGMEM = { +constexpr temp_entry_t temptable_8[] PROGMEM = { { OV( 1), 704 }, { OV( 54), 216 }, { OV( 107), 175 }, diff --git a/Marlin/src/module/thermistor/thermistor_9.h b/Marlin/src/module/thermistor/thermistor_9.h index 29097420ec..3830a7dfcc 100644 --- a/Marlin/src/module/thermistor/thermistor_9.h +++ b/Marlin/src/module/thermistor/thermistor_9.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, GE Sensing AL03006-58.2K-97-G1 -const temp_entry_t temptable_9[] PROGMEM = { +constexpr temp_entry_t temptable_9[] PROGMEM = { { OV( 1), 936 }, { OV( 36), 300 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_99.h b/Marlin/src/module/thermistor/thermistor_99.h index 839a511c09..f813abae69 100644 --- a/Marlin/src/module/thermistor/thermistor_99.h +++ b/Marlin/src/module/thermistor/thermistor_99.h @@ -24,7 +24,7 @@ // 100k bed thermistor with a 10K pull-up resistor - made by $ buildroot/share/scripts/createTemperatureLookupMarlin.py --rp=10000 -const temp_entry_t temptable_99[] PROGMEM = { +constexpr temp_entry_t temptable_99[] PROGMEM = { { OV( 5.81), 350 }, // v=0.028 r= 57.081 res=13.433 degC/count { OV( 6.54), 340 }, // v=0.032 r= 64.248 res=11.711 degC/count { OV( 7.38), 330 }, // v=0.036 r= 72.588 res=10.161 degC/count diff --git a/Marlin/src/module/thermistor/thermistor_998.h b/Marlin/src/module/thermistor/thermistor_998.h index e4cfbbaa0d..753cdd40bc 100644 --- a/Marlin/src/module/thermistor/thermistor_998.h +++ b/Marlin/src/module/thermistor/thermistor_998.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_998_VALUE 25 #endif -const temp_entry_t temptable_998[] PROGMEM = { +constexpr temp_entry_t temptable_998[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_998_VALUE }, { OV(1023), DUMMY_THERMISTOR_998_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistor_999.h b/Marlin/src/module/thermistor/thermistor_999.h index 0271c47f85..41e44ef631 100644 --- a/Marlin/src/module/thermistor/thermistor_999.h +++ b/Marlin/src/module/thermistor/thermistor_999.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_999_VALUE 25 #endif -const temp_entry_t temptable_999[] PROGMEM = { +constexpr temp_entry_t temptable_999[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_999_VALUE }, { OV(1023), DUMMY_THERMISTOR_999_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 97d268c303..a6cd7c86df 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -42,7 +42,16 @@ #define OV_SCALE(N) (N) #define OV(N) int16_t(OV_SCALE(N) * (OVERSAMPLENR) * (THERMISTOR_TABLE_SCALE)) -#define ANY_THERMISTOR_IS(n) (TEMP_SENSOR_0_THERMISTOR_ID == n || TEMP_SENSOR_1_THERMISTOR_ID == n || TEMP_SENSOR_2_THERMISTOR_ID == n || TEMP_SENSOR_3_THERMISTOR_ID == n || TEMP_SENSOR_4_THERMISTOR_ID == n || TEMP_SENSOR_5_THERMISTOR_ID == n || TEMP_SENSOR_6_THERMISTOR_ID == n || TEMP_SENSOR_7_THERMISTOR_ID == n || TEMP_SENSOR_BED_THERMISTOR_ID == n || TEMP_SENSOR_CHAMBER_THERMISTOR_ID == n || TEMP_SENSOR_COOLER_THERMISTOR_ID == n || TEMP_SENSOR_PROBE_THERMISTOR_ID == n) +#define TEMP_SENSOR_IS(n,H) (n == TEMP_SENSOR_##H) +#define ANY_THERMISTOR_IS(n) ( TEMP_SENSOR_IS(n, 0) || TEMP_SENSOR_IS(n, 1) \ + || TEMP_SENSOR_IS(n, 2) || TEMP_SENSOR_IS(n, 3) \ + || TEMP_SENSOR_IS(n, 4) || TEMP_SENSOR_IS(n, 5) \ + || TEMP_SENSOR_IS(n, 6) || TEMP_SENSOR_IS(n, 7) \ + || TEMP_SENSOR_IS(n, BED) \ + || TEMP_SENSOR_IS(n, CHAMBER) \ + || TEMP_SENSOR_IS(n, COOLER) \ + || TEMP_SENSOR_IS(n, PROBE) \ + || TEMP_SENSOR_IS(n, REDUNDANT) ) typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; @@ -198,146 +207,128 @@ typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; #include "thermistor_999.h" #endif #if ANY_THERMISTOR_IS(1000) // Custom - const temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; + constexpr temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; #endif #define _TT_NAME(_N) temptable_ ## _N #define TT_NAME(_N) _TT_NAME(_N) - -#if TEMP_SENSOR_0_THERMISTOR_ID - #define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0_THERMISTOR_ID) +#if TEMP_SENSOR_0 > 0 + #define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0) #define TEMPTABLE_0_LEN COUNT(TEMPTABLE_0) -#elif TEMP_SENSOR_0_IS_THERMISTOR - #error "No heater 0 thermistor table specified" #else #define TEMPTABLE_0 nullptr #define TEMPTABLE_0_LEN 0 #endif -#if TEMP_SENSOR_1_THERMISTOR_ID - #define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1_THERMISTOR_ID) +#if TEMP_SENSOR_1 > 0 + #define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1) #define TEMPTABLE_1_LEN COUNT(TEMPTABLE_1) -#elif TEMP_SENSOR_1_IS_THERMISTOR - #error "No heater 1 thermistor table specified" #else #define TEMPTABLE_1 nullptr #define TEMPTABLE_1_LEN 0 #endif -#if TEMP_SENSOR_2_THERMISTOR_ID - #define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2_THERMISTOR_ID) +#if TEMP_SENSOR_2 > 0 + #define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2) #define TEMPTABLE_2_LEN COUNT(TEMPTABLE_2) -#elif TEMP_SENSOR_2_IS_THERMISTOR - #error "No heater 2 thermistor table specified" #else #define TEMPTABLE_2 nullptr #define TEMPTABLE_2_LEN 0 #endif -#if TEMP_SENSOR_3_THERMISTOR_ID - #define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3_THERMISTOR_ID) +#if TEMP_SENSOR_3 > 0 + #define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3) #define TEMPTABLE_3_LEN COUNT(TEMPTABLE_3) -#elif TEMP_SENSOR_3_IS_THERMISTOR - #error "No heater 3 thermistor table specified" #else #define TEMPTABLE_3 nullptr #define TEMPTABLE_3_LEN 0 #endif -#if TEMP_SENSOR_4_THERMISTOR_ID - #define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4_THERMISTOR_ID) +#if TEMP_SENSOR_4 > 0 + #define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4) #define TEMPTABLE_4_LEN COUNT(TEMPTABLE_4) -#elif TEMP_SENSOR_4_IS_THERMISTOR - #error "No heater 4 thermistor table specified" #else #define TEMPTABLE_4 nullptr #define TEMPTABLE_4_LEN 0 #endif -#if TEMP_SENSOR_5_THERMISTOR_ID - #define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5_THERMISTOR_ID) +#if TEMP_SENSOR_5 > 0 + #define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5) #define TEMPTABLE_5_LEN COUNT(TEMPTABLE_5) -#elif TEMP_SENSOR_5_IS_THERMISTOR - #error "No heater 5 thermistor table specified" #else #define TEMPTABLE_5 nullptr #define TEMPTABLE_5_LEN 0 #endif -#if TEMP_SENSOR_6_THERMISTOR_ID - #define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6_THERMISTOR_ID) +#if TEMP_SENSOR_6 > 0 + #define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6) #define TEMPTABLE_6_LEN COUNT(TEMPTABLE_6) -#elif TEMP_SENSOR_6_IS_THERMISTOR - #error "No heater 6 thermistor table specified" #else #define TEMPTABLE_6 nullptr #define TEMPTABLE_6_LEN 0 #endif -#if TEMP_SENSOR_7_THERMISTOR_ID - #define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7_THERMISTOR_ID) +#if TEMP_SENSOR_7 > 0 + #define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7) #define TEMPTABLE_7_LEN COUNT(TEMPTABLE_7) -#elif TEMP_SENSOR_7_IS_THERMISTOR - #error "No heater 7 thermistor table specified" #else #define TEMPTABLE_7 nullptr #define TEMPTABLE_7_LEN 0 #endif -#ifdef TEMP_SENSOR_BED_THERMISTOR_ID - #define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED_THERMISTOR_ID) +#if TEMP_SENSOR_BED > 0 + #define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED) #define TEMPTABLE_BED_LEN COUNT(TEMPTABLE_BED) -#elif TEMP_SENSOR_BED_IS_THERMISTOR - #error "No bed thermistor table specified" #else #define TEMPTABLE_BED_LEN 0 #endif -#ifdef TEMP_SENSOR_CHAMBER_THERMISTOR_ID - #define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER_THERMISTOR_ID) +#if TEMP_SENSOR_CHAMBER > 0 + #define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER) #define TEMPTABLE_CHAMBER_LEN COUNT(TEMPTABLE_CHAMBER) -#elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR - #error "No chamber thermistor table specified" #else #define TEMPTABLE_CHAMBER_LEN 0 #endif -#ifdef TEMP_SENSOR_COOLER_THERMISTOR_ID - #define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER_THERMISTOR_ID) +#if TEMP_SENSOR_COOLER > 0 + #define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER) #define TEMPTABLE_COOLER_LEN COUNT(TEMPTABLE_COOLER) -#elif TEMP_SENSOR_COOLER_IS_THERMISTOR - #error "No cooler thermistor table specified" #else #define TEMPTABLE_COOLER_LEN 0 #endif -#ifdef TEMP_SENSOR_PROBE_THERMISTOR_ID - #define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE_THERMISTOR_ID) + +#if TEMP_SENSOR_PROBE > 0 + #define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE) #define TEMPTABLE_PROBE_LEN COUNT(TEMPTABLE_PROBE) -#elif TEMP_SENSOR_PROBE_IS_THERMISTOR - #error "No probe thermistor table specified" #else #define TEMPTABLE_PROBE_LEN 0 #endif +#if TEMP_SENSOR_REDUNDANT > 0 + #define TEMPTABLE_REDUNDANT TT_NAME(TEMP_SENSOR_REDUNDANT) + #define TEMPTABLE_REDUNDANT_LEN COUNT(TEMPTABLE_REDUNDANT) +#else + #define TEMPTABLE_REDUNDANT_LEN 0 +#endif + // The SCAN_THERMISTOR_TABLE macro needs alteration? -static_assert( - TEMPTABLE_0_LEN < 256 && TEMPTABLE_1_LEN < 256 - && TEMPTABLE_2_LEN < 256 && TEMPTABLE_3_LEN < 256 - && TEMPTABLE_4_LEN < 256 && TEMPTABLE_5_LEN < 256 - && TEMPTABLE_6_LEN < 256 && TEMPTABLE_7_LEN < 256 - && TEMPTABLE_BED_LEN < 256 && TEMPTABLE_CHAMBER_LEN < 256 - && TEMPTABLE_COOLER_LEN < 256 && TEMPTABLE_PROBE_LEN < 256, - "Temperature conversion tables over 255 entries need special consideration." +static_assert(255 > TEMPTABLE_0_LEN || 255 > TEMPTABLE_1_LEN || 255 > TEMPTABLE_2_LEN || 255 > TEMPTABLE_3_LEN + || 255 > TEMPTABLE_4_LEN || 255 > TEMPTABLE_5_LEN || 255 > TEMPTABLE_6_LEN || 255 > TEMPTABLE_7_LEN + || 255 > TEMPTABLE_BED_LEN + || 255 > TEMPTABLE_CHAMBER_LEN + || 255 > TEMPTABLE_COOLER_LEN + || 255 > TEMPTABLE_PROBE_LEN + || 255 > TEMPTABLE_REDUNDANT_LEN + , "Temperature conversion tables over 255 entries need special consideration." ); // Set the high and low raw values for the heaters // For thermistors the highest temperature results in the lowest ADC value // For thermocouples the highest temperature results in the highest ADC value -#define __TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N -#define _TT_REV(N) __TT_REV(N) -#define TT_REV(N) _TT_REV(TEMP_SENSOR_##N##_THERMISTOR_ID) +#define _TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N +#define TT_REV(N) TERN0(TEMP_SENSOR_##N##_IS_THERMISTOR, DEFER4(_TT_REV)(TEMP_SENSOR_##N)) #define _TT_REVRAW(N) !TEMP_SENSOR_##N##_IS_THERMISTOR #define TT_REVRAW(N) (TT_REV(N) || _TT_REVRAW(N)) @@ -522,6 +513,15 @@ static_assert( #define TEMP_SENSOR_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif +#ifndef TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP + #if TT_REVRAW(REDUNDANT) + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP 0 + #else + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP 0 + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #endif +#endif #undef __TT_REV #undef _TT_REV diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index ea7472c5da..e0c1d8f38d 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -37,7 +37,7 @@ env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 tee TESTPATH=buildroot/tests STATE_FILE="./.pio/.mftestrc" -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) shopt -s extglob nocasematch diff --git a/buildroot/bin/opt_disable b/buildroot/bin/opt_disable index 18ec03aa94..0444e1b773 100755 --- a/buildroot/bin/opt_disable +++ b/buildroot/bin/opt_disable @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do DID=0 ; FOUND=0 diff --git a/buildroot/bin/opt_enable b/buildroot/bin/opt_enable index d341ee9bd3..f9be82cbd1 100755 --- a/buildroot/bin/opt_enable +++ b/buildroot/bin/opt_enable @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do DID=0 ; FOUND=0 diff --git a/buildroot/bin/opt_set b/buildroot/bin/opt_set index 3f67d78900..b9935512a4 100755 --- a/buildroot/bin/opt_set +++ b/buildroot/bin/opt_set @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) while [[ $# > 1 ]]; do DID=0 diff --git a/buildroot/bin/pins_set b/buildroot/bin/pins_set index 860c64940f..158c5224e6 100755 --- a/buildroot/bin/pins_set +++ b/buildroot/bin/pins_set @@ -6,6 +6,6 @@ NAM=${PINPATH[1]} PIN=$2 VAL=$3 -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || (echo "ERROR: pins_set Can't find ${PIN}" >&2 && exit 9) diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index fb48d6b5a4..70642a5d39 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -149,7 +149,7 @@ if [[ $ACTION == "init" ]]; then ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset TPARA..." >/dev/null # Update the %VERSION% in the README.md file - SED=$(which gsed || which sed) + SED=$(which gsed sed | head -n1) VERS=$( echo $EXPORT | $SED 's/release-//' ) eval "${SED} -E -i~ -e 's/%VERSION%/$VERS/g' README.md" rm -f README.md~ From c2f67cf8ee5625b869d5cded06c6df333aa1af73 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Fri, 11 Jun 2021 22:53:23 +0200 Subject: [PATCH 0248/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Six=20Linear=20A?= =?UTF-8?q?xes=20followup=20(Fix=20M503)=20(#22112)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 0a88d63e8c..27ba7cbc75 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3163,7 +3163,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( #if IS_CARTESIAN - LIST_N(LINEAR_AXES, + LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), SP_Y_STR, LINEAR_UNIT(home_offset.y), SP_Z_STR, LINEAR_UNIT(home_offset.z), From 221bec5ce8ccf7d7e374e24047d2853641db2472 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Fri, 11 Jun 2021 18:13:22 -0300 Subject: [PATCH 0249/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20boot=20/=20SD=20?= =?UTF-8?q?for=20STM32=20(F103Rx)=20boards=20(#22087)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.h | 1 + Marlin/src/MarlinCore.cpp | 9 +++++++++ Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 1 + 3 files changed, 11 insertions(+) diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 2441c46eab..02bee57ba3 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -195,6 +195,7 @@ uint16_t HAL_adc_get_result(); #ifdef STM32F1xx #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG #endif #define PLATFORM_M997_SUPPORT diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 54598e035a..78c97cf3a3 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1126,6 +1126,7 @@ void setup() { #endif #if HAS_FREEZE_PIN + SETUP_LOG("FREEZE_PIN"); SET_INPUT_PULLUP(FREEZE_PIN); #endif @@ -1134,11 +1135,19 @@ void setup() { OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); #endif + #ifdef JTAGSWD_RESET + SETUP_LOG("JTAGSWD_RESET"); + JTAGSWD_RESET(); + #endif + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + delay(10); // Disable any hardware debug to free up pins for IO #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + SETUP_LOG("JTAGSWD_DISABLE"); JTAGSWD_DISABLE(); #elif defined(JTAG_DISABLE) + SETUP_LOG("JTAG_DISABLE"); JTAG_DISABLE(); #else #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 27aa84e44f..9b71570b08 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -288,3 +288,4 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define SDSS ONBOARD_SD_CS_PIN From 72b9f84723d7975178e126ee2529df321d6a27e1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Jun 2021 18:33:07 -0500 Subject: [PATCH 0250/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Z=20endstop=20en?= =?UTF-8?q?um?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to 92dea8e6cc --- Marlin/src/module/endstops.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index d983d69871..e8365ce1ed 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -81,7 +81,7 @@ enum EndstopEnum : char { #if HAS_Y_MIN || HAS_Y_MAX , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) #endif - #if HAS_Z_MIN || HAS_Z_MAX + #if HAS_Z_MIN || HAS_Z_MAX || HOMING_Z_WITH_PROBE , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) #endif }; From 799a4ecab94d89a40b6f3b2507138a9c4e10813a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Jun 2021 19:29:59 -0500 Subject: [PATCH 0251/2168] =?UTF-8?q?=F0=9F=93=9D=20Describe=20G12=20XYZ?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/clean/G12.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 216db5bae3..b19932eb98 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -42,6 +42,7 @@ * P0 S : Stroke cleaning with S strokes * P1 Sn T : Zigzag cleaning with S repeats and T zigzags * P2 Sn R : Circle cleaning with S repeats and R radius + * X, Y, Z : Specify axes to move during cleaning. Default: ALL. */ void GcodeSuite::G12() { // Don't allow nozzle cleaning without homing first From cc100429f2509463db1fad18901b0c1e0655c646 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 12 Jun 2021 00:52:56 +0000 Subject: [PATCH 0252/2168] [cron] Bump distribution date (2021-06-12) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b6441f8056..465d7f5789 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 "2021-06-11" + #define STRING_DISTRIBUTION_DATE "2021-06-12" #endif /** From 4eecc20ebc4f1f27265ded0e124451083190c7c8 Mon Sep 17 00:00:00 2001 From: mrv96 Date: Sat, 12 Jun 2021 18:19:37 +0200 Subject: [PATCH 0253/2168] =?UTF-8?q?=F0=9F=94=A8=20Robin=20Nano=20V3=20ov?= =?UTF-8?q?erridable=20POWER=5FLOSS=5FPIN=20(#22123)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 1146582a5b..5a056b97cd 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -190,7 +190,9 @@ #define FIL_RUNOUT2_PIN MT_DET_2 #endif -#define POWER_LOSS_PIN PW_DET +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PW_DET +#endif #define PS_ON_PIN PW_OFF // From 87344ae7f354c6bbb4a8faa44d4b1b188e2df662 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 12 Jun 2021 11:40:35 -0500 Subject: [PATCH 0254/2168] =?UTF-8?q?=F0=9F=94=A8=20Remove=20obsolete=20ON?= =?UTF-8?q?=5FBOARD=5FSPI=5FDEVICE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 -- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 2 -- 2 files changed, 4 deletions(-) diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 2e1e02f991..1e7b3f02a2 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -264,5 +264,3 @@ #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 Turbo." #endif - -#define ON_BOARD_SPI_DEVICE 1 // SPI1 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index e76c77e706..a8be2cfc07 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -166,8 +166,6 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 - - #define ON_BOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card #endif From fd3f7b3473a16beaf195777b06435bc1cdfa5703 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 12 Jun 2021 12:30:29 -0500 Subject: [PATCH 0255/2168] =?UTF-8?q?=F0=9F=8E=A8=20Clean=20up=20LPC1768?= =?UTF-8?q?=20SPI=20init?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 18 ++++++------------ 1 file changed, 6 insertions(+), 12 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 99db15f6e9..29f9b43afe 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -66,11 +66,7 @@ #include - #ifndef HAL_SPI_SPEED - #define HAL_SPI_SPEED SPI_FULL_SPEED - #endif - - static uint8_t SPI_speed = HAL_SPI_SPEED; + static uint8_t SPI_speed = SPI_FULL_SPEED; static uint8_t spiTransfer(uint8_t b) { return swSpiTransfer(b, SPI_speed, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); @@ -106,15 +102,13 @@ #else - #ifndef HAL_SPI_SPEED - #ifdef SD_SPI_SPEED - #define HAL_SPI_SPEED SD_SPI_SPEED - #else - #define HAL_SPI_SPEED SPI_FULL_SPEED - #endif + #ifdef SD_SPI_SPEED + #define INIT_SPI_SPEED SD_SPI_SPEED + #else + #define INIT_SPI_SPEED SPI_FULL_SPEED #endif - void spiBegin() { spiInit(HAL_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 + void spiBegin() { spiInit(INIT_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 void spiInit(uint8_t spiRate) { #if SD_MISO_PIN == BOARD_SPI1_MISO_PIN From c221ee1144001add4efb5345fa0ad9b003191510 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 12 Jun 2021 12:31:24 -0500 Subject: [PATCH 0256/2168] =?UTF-8?q?=F0=9F=93=9D=20Number=20SKR=20EXP=20h?= =?UTF-8?q?eaders?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 01f2303a35..066c65be3a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -139,14 +139,14 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** _____ _____ - * NC | . . | GND NC | . . | GND - * NC | . . | M1EN M2EN | . . | M3EN - * M1STP | . . M1DIR M1RX | . . M1DIAG - * M2DIR | . . | M2STP M2RX | . . | M2DIAG - * M3DIR | . . | M3STP M3RX | . . | M3DIAG - * ----- ----- - * EXP2 EXP1 + /** ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 * * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ From 9bf5cddb46259335753513846bb30c38ef4273b7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 12 Jun 2021 16:28:30 -0500 Subject: [PATCH 0257/2168] =?UTF-8?q?=F0=9F=A9=B9=20Use=20`#pragma=20once`?= =?UTF-8?q?=20in=20pins=20files?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/mega/pins_PICA.h | 1 + Marlin/src/pins/mega/pins_PICAOLD.h | 1 + Marlin/src/pins/ramps/pins_K8600.h | 1 + Marlin/src/pins/ramps/pins_TT_OSCAR.h | 1 + Marlin/src/pins/sam/pins_CNCONTROLS_15D.h | 1 + Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 1 + Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V427.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V431.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V452.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V453.h | 1 + Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h | 1 + Marlin/src/pins/teensy2/pins_TEENSYLU.h | 1 + 15 files changed, 15 insertions(+) diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 81f6319377..41afe5d891 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Arduino Mega with PICA pin assignments diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index f53a4cdcd2..e19ea744e5 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once #define HEATER_0_PIN 9 // E0 #define HEATER_1_PIN 10 // E1 diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index c2d91ad7ee..47b52e75e8 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * VERTEX NANO Arduino Mega with RAMPS EFB v1.4 pin assignments. diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 18d0f1770e..aba8f80e61 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once #include "env_validate.h" diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index a63c337880..d44f6490da 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CNControls V15 for HMS434 with DUE pin assignments diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 908bbc6b22..a52af48e11 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 3e73c33acb..37ebb567a6 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 421e339058..6b3c4ed8fa 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality 4.2.x (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 6585d40d45..d106c98e13 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY 4.2.10 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h index 64ef046bd3..c327abee77 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY v4.2.7 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h index ff9f76054e..e8ae84da8f 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY v4.3.1 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index 9acbb42a88..ad4ddff0ce 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.2 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index f990b2f7b4..cdb87adece 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.3 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index c73c92080e..39dccf1271 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.2 and v4.5.3 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index f551d802cf..535ce534d4 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -18,6 +18,7 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see . */ +#pragma once /** * Rev C 2 JUN 2017 From a9faf9effaa2c98a64097167f46dc6501cad89df Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 13 Jun 2021 00:59:15 +0000 Subject: [PATCH 0258/2168] [cron] Bump distribution date (2021-06-13) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 465d7f5789..2e9e60ab65 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 "2021-06-12" + #define STRING_DISTRIBUTION_DATE "2021-06-13" #endif /** From 90dc41139fb0bd55bdd3cab16b978842ed525e7b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 13 Jun 2021 15:43:33 -0500 Subject: [PATCH 0259/2168] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Refactor=20bu?= =?UTF-8?q?ild=20encrypt=20/=20rename=20(#22124)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/STM32F103RC_fysetc.py | 4 +-- buildroot/share/PlatformIO/scripts/lerdge.py | 15 +++++----- buildroot/share/PlatformIO/scripts/marlin.py | 8 +++-- .../share/PlatformIO/scripts/mks_encrypt.py | 9 +++--- buildroot/share/PlatformIO/scripts/openblt.py | 17 ++++++----- .../PlatformIO/scripts/stm32_bootloader.py | 25 ++++++++-------- ini/stm32f1.ini | 14 +++------ ini/stm32f4.ini | 30 ++++++++----------- 8 files changed, 59 insertions(+), 63 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index f64f928787..5a09dd3d14 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -8,10 +8,10 @@ Import("env") # Custom HEX from ELF env.AddPostAction( - join("$BUILD_DIR","${PROGNAME}.elf"), + join("$BUILD_DIR", "${PROGNAME}.elf"), env.VerboseAction(" ".join([ "$OBJCOPY", "-O ihex", "$TARGET", # TARGET=.pio/build/fysetc_STM32F1/firmware.elf - "\"" + join("$BUILD_DIR","${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path + "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path ]), "Building $TARGET")) # In-line command with arguments diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 55f0a65ace..5c35c19e7d 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -27,11 +27,12 @@ def encrypt_file(input, output_file, file_length): output_file.write(input_file) return -# Encrypt ${PROGNAME}.bin and save it as build.firmware +# Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt def encrypt(source, target, env): - print("Encrypting to:", board.get("build.firmware")) + fwname = board.get("build.encrypt") + print("Encrypting %s to %s" % (target[0].path, fwname)) firmware = open(target[0].path, "rb") - renamed = open(target[0].dir.path + "/" + board.get("build.firmware"), "wb") + renamed = open(target[0].dir.path + "/" + fwname, "wb") length = os.path.getsize(target[0].path) encrypt_file(firmware, renamed, length) @@ -39,8 +40,8 @@ def encrypt(source, target, env): firmware.close() renamed.close() -if 'firmware' in board.get("build").keys(): - marlin.add_post_action(encrypt); +if 'encrypt' in board.get("build").keys(): + marlin.add_post_action(encrypt); else: - print("You need to define output file via board_build.firmware = 'filename' parameter") - exit(1); + print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") + exit(1); diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index d83ebceee2..23c1b95742 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -7,10 +7,12 @@ import os,shutil from SCons.Script import DefaultEnvironment env = DefaultEnvironment() +from os.path import join + def copytree(src, dst, symlinks=False, ignore=None): for item in os.listdir(src): - s = os.path.join(src, item) - d = os.path.join(dst, item) + s = join(src, item) + d = join(dst, item) if os.path.isdir(s): shutil.copytree(s, d, symlinks, ignore) else: @@ -64,7 +66,7 @@ def encrypt_mks(source, target, env, new_name): renamed.close() def add_post_action(action): - env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", action); + env.AddPostAction(join("$BUILD_DIR", "${PROGNAME}.bin"), action); # Apply customizations for a MKS Robin def prepare_robin(address, ldname, fwname): diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py index 59322a6388..bd3548ab36 100644 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ b/buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -3,6 +3,7 @@ # # Apply encryption and save as 'build.firmware' for these environments: # - env:mks_robin +# - env:mks_robin_e3 # - env:flsun_hispeedv1 # - env:mks_robin_nano35 # @@ -11,18 +12,18 @@ Import("env") from SCons.Script import DefaultEnvironment board = DefaultEnvironment().BoardConfig() -if 'firmware' in board.get("build").keys(): +if 'encrypt' in board.get("build").keys(): import marlin - # Encrypt ${PROGNAME}.bin and save it as build.firmware + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, board.get("build.firmware")) + marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) marlin.add_post_action(encrypt); else: import sys - print("You need to define output file via board_build.firmware = 'filename' parameter", file=sys.stderr) + print("You need to define output file via board_build.encrypt = 'filename' parameter", file=sys.stderr) env.Exit(1); diff --git a/buildroot/share/PlatformIO/scripts/openblt.py b/buildroot/share/PlatformIO/scripts/openblt.py index 01cd9c9ef2..6e71ca9eb8 100644 --- a/buildroot/share/PlatformIO/scripts/openblt.py +++ b/buildroot/share/PlatformIO/scripts/openblt.py @@ -6,10 +6,13 @@ from os.path import join Import("env") -env.AddPostAction( - "$BUILD_DIR/${PROGNAME}.elf", - env.VerboseAction(" ".join([ - "$OBJCOPY", "-O", "srec", - "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"$BUILD_DIR/${PROGNAME}.srec\"" - ]), "Building " + join("$BUILD_DIR", "${PROGNAME}.srec")) -) +board = env.BoardConfig() +board_keys = board.get("build").keys() +if 'encrypt' in board_keys: + env.AddPostAction( + join("$BUILD_DIR", "${PROGNAME}.bin"), + env.VerboseAction(" ".join([ + "$OBJCOPY", "-O", "srec", + "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encrypt")) + "\"" + ]), "Building $TARGET") + ) diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py index b2b5daadb6..eb28b901d2 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -1,23 +1,18 @@ # # stm32_bootloader.py # -import os,sys,shutil,marlin +import os,sys,marlin Import("env") from SCons.Script import DefaultEnvironment board = DefaultEnvironment().BoardConfig() -# -# Copy the firmware.bin file to build.firmware, no encryption -# -def noencrypt(source, target, env): - firmware = os.path.join(target[0].dir.path, board.get("build.firmware")) - shutil.copy(target[0].path, firmware) +board_keys = board.get("build").keys() # # For build.offset define LD_FLASH_OFFSET, used by ldscript.ld # -if 'offset' in board.get("build").keys(): +if 'offset' in board_keys: LD_FLASH_OFFSET = board.get("build.offset") marlin.relocate_vtab(LD_FLASH_OFFSET) @@ -35,9 +30,13 @@ if 'offset' in board.get("build").keys(): env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) # -# Only copy the file if there's no encrypt +# For build.rename simply rename the firmware file. # -board_keys = board.get("build").keys() -if 'firmware' in board_keys and ('encrypt' not in board_keys or board.get("build.encrypt") == 'No'): - import marlin - marlin.add_post_action(noencrypt) +if 'rename' in board_keys: + + def rename_target(source, target, env): + firmware = os.path.join(target[0].dir.path, board.get("build.rename")) + import shutil + shutil.copy(target[0].path, firmware) + + marlin.add_post_action(rename_target) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 9954411c14..de5c4b6c85 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -84,8 +84,6 @@ platform = ${common_stm32.platform} extends = common_STM32F103RC build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 board_build.offset = 0x7000 -board_build.encrypt = No -board_build.firmware = firmware.bin board_upload.offset_address = 0x08007000 [env:STM32F103RC_btt_USB] @@ -113,8 +111,7 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Zx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.encrypt = Yes -board_build.firmware = Robin.bin +board_build.encrypt = Robin.bin build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} @@ -136,8 +133,7 @@ build_flags = ${common_stm32.build_flags} build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC monitor_speed = 115200 board_build.offset = 0x5000 -board_build.encrypt = Yes -board_build.firmware = Robin_e3.bin +board_build.encrypt = Robin_e3.bin board_upload.offset_address = 0x08005000 debug_tool = stlink extra_scripts = ${env:STM32F103RC.extra_scripts} @@ -215,8 +211,7 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.firmware = Robin_mini.bin -board_build.encrypt = Yes +board_build.encrypt = Robin_mini.bin board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC extra_scripts = ${common_stm32.extra_scripts} @@ -236,8 +231,7 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.encrypt = Yes -board_build.firmware = Robin_nano35.bin +board_build.encrypt = Robin_nano35.bin board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC debug_tool = jlink diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 021574ad26..4fa5fa24ab 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -113,9 +113,8 @@ board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = firmware.srec +board_build.encrypt = firmware.srec # Just openblt.py (not stm32_bootloader.py) generates the file -board_build.encrypt = Yes board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 @@ -265,7 +264,7 @@ extends = common_stm32 board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_LERDGE board_build.offset = 0x10000 -board_build.encrypt = Yes +board_build.encrypt = firmware.bin extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -280,9 +279,9 @@ build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUS # Lerdge X # [env:LERDGEX] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_X_firmware_force.bin +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_X_firmware_force.bin # # Lerdge X with USB Flash Drive Support @@ -297,9 +296,9 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge S # [env:LERDGES] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_firmware_force.bin +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_firmware_force.bin # # Lerdge S with USB Flash Drive Support @@ -314,10 +313,10 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge K # [env:LERDGEK] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_K_firmware_force.bin -build_flags = ${lerdge_common.build_flags} -DLERDGEK +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_K_firmware_force.bin +build_flags = ${lerdge_common.build_flags} -DLERDGEK # # Lerdge K with USB Flash Drive Support @@ -347,8 +346,6 @@ board_build.core = stm32 board_build.variant = MARLIN_F446VE board_build.ldscript = ldscript.ld board_build.offset = 0x0000 -board_build.encrypt = No -board_build.firmware = firmware.bin extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -365,7 +362,6 @@ board = genericSTM32F407VET6 board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = firmware.bin board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC @@ -392,7 +388,7 @@ board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = Robin_nano_v3.bin +board_build.rename = Robin_nano_v3.bin board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 build_unflags = ${common_stm32.build_unflags} From 31d84bac4c63368b54a05e4ba8fc1cde2f3b79a2 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 13 Jun 2021 14:56:18 -0700 Subject: [PATCH 0260/2168] =?UTF-8?q?=F0=9F=90=9B=20Use=20whole=20PROBE=5F?= =?UTF-8?q?TEMP=5FCOMPENSATION=20values=20(#22130)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 22 +++++++++++----------- Marlin/src/feature/probe_temp_comp.h | 8 ++++---- Marlin/src/inc/SanityCheck.h | 22 ++++++++++++++++++++++ buildroot/tests/BIGTREE_BTT002 | 6 ++++++ 4 files changed, 43 insertions(+), 15 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2a7f06c733..726058ebbc 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -202,7 +202,7 @@ #define COOLER_MAXTEMP 26 // (°C) #define COOLER_DEFAULT_TEMP 16 // (°C) #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target - #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element e.g. TEC, External chiller via relay + #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay) #define COOLER_INVERTING false #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required. #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc. @@ -1961,21 +1961,21 @@ //#define USE_TEMP_EXT_COMPENSATION // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START - // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples. + // (e.g., 30), in steps of PTC_SAMPLE_RES (e.g., 5) with PTC_SAMPLE_COUNT (e.g., 10) samples. - //#define PTC_SAMPLE_START 30.0f - //#define PTC_SAMPLE_RES 5.0f - //#define PTC_SAMPLE_COUNT 10U + //#define PTC_SAMPLE_START 30 // (°C) + //#define PTC_SAMPLE_RES 5 // (°C) + //#define PTC_SAMPLE_COUNT 10 // Bed temperature calibration builds a similar table. - //#define BTC_SAMPLE_START 60.0f - //#define BTC_SAMPLE_RES 5.0f - //#define BTC_SAMPLE_COUNT 10U + //#define BTC_SAMPLE_START 60 // (°C) + //#define BTC_SAMPLE_RES 5 // (°C) + //#define BTC_SAMPLE_COUNT 10 // The temperature the probe should be at while taking measurements during bed temperature // calibration. - //#define BTC_PROBE_TEMP 30.0f + //#define BTC_PROBE_TEMP 30 // (°C) // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. @@ -1984,7 +1984,7 @@ // Height to raise the Z-probe between heating and taking the next measurement. Some probes // may fail to untrigger if they have been triggered for a long time, which can be solved by // increasing the height the probe is raised to. - //#define PTC_PROBE_RAISE 15U + //#define PTC_PROBE_RAISE 15 // If the probe is outside of the defined range, use linear extrapolation using the closest // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] @@ -2099,7 +2099,7 @@ // @section motion // The number of linear moves that can be in the planner at once. -// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) #if BOTH(SDSUPPORT, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 #elif ENABLED(SDSUPPORT) diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 2e5ae85a43..f5f922410c 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -47,7 +47,7 @@ typedef struct { // Probe temperature calibration constants #ifndef PTC_SAMPLE_COUNT - #define PTC_SAMPLE_COUNT 10U + #define PTC_SAMPLE_COUNT 10 #endif #ifndef PTC_SAMPLE_RES #define PTC_SAMPLE_RES 5 @@ -55,14 +55,14 @@ typedef struct { #ifndef PTC_SAMPLE_START #define PTC_SAMPLE_START 30 #endif -#define PTC_SAMPLE_END ((PTC_SAMPLE_START) + (PTC_SAMPLE_COUNT) * (PTC_SAMPLE_RES)) +#define PTC_SAMPLE_END (PTC_SAMPLE_START + (PTC_SAMPLE_COUNT) * PTC_SAMPLE_RES) // Bed temperature calibration constants #ifndef BTC_PROBE_TEMP #define BTC_PROBE_TEMP 30 #endif #ifndef BTC_SAMPLE_COUNT - #define BTC_SAMPLE_COUNT 10U + #define BTC_SAMPLE_COUNT 10 #endif #ifndef BTC_SAMPLE_RES #define BTC_SAMPLE_RES 5 @@ -70,7 +70,7 @@ typedef struct { #ifndef BTC_SAMPLE_START #define BTC_SAMPLE_START 60 #endif -#define BTC_SAMPLE_END ((BTC_SAMPLE_START) + (BTC_SAMPLE_COUNT) * (BTC_SAMPLE_RES)) +#define BTC_SAMPLE_END (BTC_SAMPLE_START + (BTC_SAMPLE_COUNT) * BTC_SAMPLE_RES) #ifndef PTC_PROBE_HEATING_OFFSET #define PTC_PROBE_HEATING_OFFSET 0.5f diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 41d123326c..ffb79a6baa 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -580,6 +580,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Probe temp compensation requirements */ + #if ENABLED(PROBE_TEMP_COMPENSATION) #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array)." @@ -590,6 +591,27 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #elif !defined(PTC_PROBE_POS) #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." #endif + + #ifdef PTC_SAMPLE_START + constexpr int _ptc_sample_start = PTC_SAMPLE_START; + static_assert(_test_ptc_sample_start != PTC_SAMPLE_START, "PTC_SAMPLE_START must be a whole number."); + #endif + #ifdef PTC_SAMPLE_RES + constexpr int _ptc_sample_res = PTC_SAMPLE_END; + static_assert(_test_ptc_sample_res != PTC_SAMPLE_END, "PTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_SAMPLE_START + constexpr int _btc_sample_start = BTC_SAMPLE_START; + static_assert(_test_btc_sample_start != BTC_SAMPLE_START, "BTC_SAMPLE_START must be a whole number."); + #endif + #ifdef BTC_SAMPLE_RES + constexpr int _btc_sample_res = BTC_SAMPLE_END; + static_assert(_test_btc_sample_res != BTC_SAMPLE_END, "BTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_PROBE_TEMP + constexpr int _btc_probe_temp = BTC_PROBE_TEMP; + static_assert(_test_btc_probe_temp != BTC_PROBE_TEMP, "BTC_PROBE_TEMP must be a whole number."); + #endif #endif /** diff --git a/buildroot/tests/BIGTREE_BTT002 b/buildroot/tests/BIGTREE_BTT002 index ba13e3eafd..7288c5ef52 100755 --- a/buildroot/tests/BIGTREE_BTT002 +++ b/buildroot/tests/BIGTREE_BTT002 @@ -16,5 +16,11 @@ opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 \ Y_DRIVER_TYPE TMC2130 exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" "$3" +# +# A test with Probe Temperature Compensation enabled +# +use_example_configs Prusa/MK3S-BigTreeTech-BTT002 +exec_test $1 $2 "BigTreeTech BTT002 with Prusa MK3S and related options" "$3" + # clean up restore_configs From 0669053b78a81e871909fb6a7dafa16cebcb1f95 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 13 Jun 2021 21:01:53 -0300 Subject: [PATCH 0261/2168] =?UTF-8?q?=F0=9F=94=A8=20Fix=20Serial+MSC=20for?= =?UTF-8?q?=20=5FUSB=20envs=20(#22116)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../share/PlatformIO/scripts/generic_create_variant.py | 2 +- ini/stm32f1.ini | 10 ++++------ ini/stm32f4.ini | 4 ++-- 3 files changed, 7 insertions(+), 9 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 75c62ef70e..7f76ef9426 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -28,7 +28,7 @@ if len(platform_packages) == 0: else: platform_name = PackageSpec(platform_packages[0]).name -if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "tool-stm32duino" ]: +if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: platform_name = "framework-arduinoststm32" FRAMEWORK_DIR = platform.get_package_dir(platform_name) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index de5c4b6c85..dca640cd50 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -89,14 +89,13 @@ board_upload.offset_address = 0x08007000 [env:STM32F103RC_btt_USB] extends = env:STM32F103RC_btt platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.build_flags} -DUSBCON - -DUSE_USBHOST_HS + -DUSE_USB_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 - -DUSE_USB_HS_IN_FS -DUSBD_USE_CDC_MSC # @@ -188,14 +187,13 @@ upload_protocol = jlink [env:STM32F103RE_btt_USB] extends = env:STM32F103RE_btt platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${env:STM32F103RE_btt.build_flags} ${env:stm32_flash_drive.build_flags} -DUSBCON - -DUSE_USBHOST_HS + -DUSE_USB_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 - -DUSE_USB_HS_IN_FS -DUSBD_USE_CDC_MSC # diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 4fa5fa24ab..dec7fea568 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -145,7 +145,7 @@ debug_init_break = # USB Flash Drive mix-ins for STM32 # [stm_flash_drive] -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 @@ -420,7 +420,7 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} [env:mks_robin_nano_v3_usb_flash_drive_msc] platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3 -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-2.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} -DUSBCON From 82ac7da0a7752288e9c13bf7aa096b407981ecd1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 14 Jun 2021 00:55:40 +0000 Subject: [PATCH 0262/2168] [cron] Bump distribution date (2021-06-14) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2e9e60ab65..cf6586f3f0 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 "2021-06-13" + #define STRING_DISTRIBUTION_DATE "2021-06-14" #endif /** From d5510ea519da96c3c6077ebdea35cfe7f115eff7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 13 Jun 2021 20:19:43 -0500 Subject: [PATCH 0263/2168] =?UTF-8?q?=F0=9F=8E=A8=20General=20cleanup=20of?= =?UTF-8?q?=20extui/dgus?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit In relation to #22121 --- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 48 ++-- Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h | 18 ++ .../lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 185 ++++++++-------- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 8 +- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 206 +++++++++--------- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 12 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 173 +++++++-------- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 1 - .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 8 +- .../lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 191 +++++++--------- .../extui/dgus/origin/DGUSScreenHandler.cpp | 12 +- 11 files changed, 405 insertions(+), 457 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index a1de499f46..2e8df757eb 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -180,7 +180,7 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { float valuesend = 0; switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: valuesend = value; break; case VP_E0_PID_I: valuesend = unscalePID_i(value); break; case VP_E0_PID_D: valuesend = unscalePID_d(value); break; @@ -393,7 +393,7 @@ void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *va switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_T_E0_Set: NOMORE(newvalue, HEATER_0_MAXTEMP); thermalManager.setTargetHotend(newvalue, 0); @@ -427,10 +427,8 @@ void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_p uint8_t target_extruder; switch (var.VP) { default: return; - #if HOTENDS >= 1 - case VP_Flowrate_E0: target_extruder = 0; break; - #endif - #if HOTENDS >= 2 + case VP_Flowrate_E0: target_extruder = 0; break; + #if HAS_MULTI_EXTRUDER case VP_Flowrate_E1: target_extruder = 1; break; #endif } @@ -450,11 +448,11 @@ void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr ExtUI::extruder_t target_extruder; switch (var.VP) { - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_MOVE_E0: target_extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; + #if HAS_MULTI_EXTRUDER + case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; + #endif #endif default: return; } @@ -526,11 +524,11 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo ExtUI::extruder_t extruder; switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_EXTRUDERS case VP_E0_STEP_PER_MM: extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #if HAS_MULTI_EXTRUDER + case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #endif #endif } DEBUG_ECHOLNPAIR_F("value:", value); @@ -548,7 +546,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo switch (var.VP) { default: break; #if ENABLED(PIDTEMP) - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_PID_AUTOTUNE_E0: // Autotune Extruder 0 sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E0); break; @@ -598,17 +596,17 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr uint8_t preheat_temp = 0; switch (var.VP) { - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_CONTROL: + #if HOTENDS >= 2 + case VP_E1_CONTROL: + #if HOTENDS >= 3 + case VP_E2_CONTROL: + #endif + #endif + preheat_temp = PREHEAT_1_TEMP_HOTEND; + break; #endif - #if HOTENDS >= 2 - case VP_E1_CONTROL: - #endif - #if HOTENDS >= 3 - case VP_E2_CONTROL: - #endif - preheat_temp = PREHEAT_1_TEMP_HOTEND; - break; case VP_BED_CONTROL: preheat_temp = PREHEAT_1_TEMP_BED; @@ -660,7 +658,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_BED_PREHEAT: thermalManager.setTargetHotend(e_temp, 0); TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h index 9aeb5b73b1..8ee2761c89 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h @@ -56,3 +56,21 @@ inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (v #endif extern DGUSScreenHandler ScreenHandler; + +// Helper to define a DGUS_VP_Variable for common use-cases. +#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = sizeof(VPADRVAR), \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} + +// Helper to define a DGUS_VP_Variable when the size of the var cannot be determined automatically (e.g., a string) +#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = STRLEN, \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 5e164d289e..4ca7db7f40 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -41,14 +41,11 @@ uint16_t distanceToMove = 10; #endif -const uint16_t VPList_Boot[] PROGMEM = { - VP_MARLIN_VERSION, - 0x0000 -}; +const uint16_t VPList_Boot[] PROGMEM = { VP_MARLIN_VERSION, 0x0000 }; const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 + // VP_M117, for completeness, but it cannot be auto-uploaded. + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, #endif #if HOTENDS >= 2 @@ -70,7 +67,7 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -83,8 +80,8 @@ const uint16_t VPList_Temp[] PROGMEM = { }; const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -105,11 +102,11 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HAS_MULTI_EXTRUDER + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, @@ -117,7 +114,7 @@ const uint16_t VPList_Status2[] PROGMEM = { }; const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -135,11 +132,11 @@ const uint16_t VPList_ManualMove[] PROGMEM = { }; const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif VP_EPos, 0x0000 @@ -156,23 +153,23 @@ const uint16_t VPList_SD_FlowRates[] PROGMEM = { }; const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; @@ -184,7 +181,7 @@ const uint16_t VPList_SDFileList[] PROGMEM = { const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -204,11 +201,11 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { }; const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, // ERROR: Flowrate is per-extruder, not per-hotend + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -222,11 +219,11 @@ const uint16_t VPList_StepPerMM[] PROGMEM = { VP_X_STEP_PER_MM, VP_Y_STEP_PER_MM, VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 + #if HAS_EXTRUDERS VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, + #if HAS_MULTI_EXTRUDER + VP_E1_STEP_PER_MM, + #endif #endif 0x0000 }; @@ -265,7 +262,7 @@ const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { }; const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HAS_HEATED_BED @@ -275,14 +272,14 @@ const uint16_t VPList_FLCPreheat[] PROGMEM = { }; const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 }; const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 @@ -316,14 +313,6 @@ const struct VPMapping VPMap[] PROGMEM = { const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -333,96 +322,96 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #endif #if HOTENDS >= 2 VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -430,7 +419,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), @@ -442,11 +431,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_EXTRUDERS VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_MULTI_EXTRUDER + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -463,7 +452,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -475,10 +464,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 8b97003f6f..78828e14c5 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -249,7 +249,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -329,7 +329,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); #endif #if HOTENDS >= 2 @@ -340,13 +340,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); break; #endif - #if HOTENDS >= 2 + #if HAS_MULTI_EXTRUDER case VP_E1_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E1; thermalManager.setTargetHotend(e_temp, filament_data.extruder); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index a9fa407dd3..536c2b09b8 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -48,11 +48,11 @@ const uint16_t VPList_Boot[] PROGMEM = { const uint16_t VPList_Main[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, @@ -70,11 +70,11 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -84,11 +84,11 @@ const uint16_t VPList_Temp[] PROGMEM = { const uint16_t VPList_Status[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -105,11 +105,11 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, @@ -117,11 +117,11 @@ const uint16_t VPList_Status2[] PROGMEM = { }; const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -135,11 +135,11 @@ const uint16_t VPList_ManualMove[] PROGMEM = { }; const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif VP_EPos, 0x0000 @@ -156,22 +156,22 @@ const uint16_t VPList_SD_FlowRates[] PROGMEM = { }; const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif 0x0000 }; const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HOTENDS >= 2 + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; @@ -183,11 +183,11 @@ const uint16_t VPList_SDFileList[] PROGMEM = { const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -203,11 +203,11 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { }; const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -225,11 +225,11 @@ const uint16_t VPList_StepPerMM[] PROGMEM = { VP_X_STEP_PER_MM, VP_Y_STEP_PER_MM, VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, + #if HOTENDS >= 2 + VP_E1_STEP_PER_MM, + #endif #endif 0x0000 }; @@ -268,7 +268,7 @@ const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { }; const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HAS_HEATED_BED @@ -278,14 +278,14 @@ const uint16_t VPList_FLCPreheat[] PROGMEM = { }; const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 }; const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 @@ -319,14 +319,6 @@ const struct VPMapping VPMap[] PROGMEM = { const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -336,92 +328,92 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif #if HOTENDS >= 2 VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -429,23 +421,23 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), #endif VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -462,7 +454,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -474,10 +466,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index f3729d1253..eab5e27507 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -249,7 +249,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -329,18 +329,18 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); - #endif - #if HOTENDS >= 2 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif #endif GotoScreen(DGUSLCD_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index a18fcb14fa..d598f100de 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -120,11 +120,11 @@ const uint16_t VPList_Boot[] PROGMEM = { const uint16_t VPList_Main[] PROGMEM = { // VP_M117, for completeness, but it cannot be auto-uploaded. - #if HOTENDS >= 1 + #if HAS_HOTEND MKSLIST_E_ITEM(0) VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - MKSLIST_E_ITEM(1) + #if HOTENDS >= 2 + MKSLIST_E_ITEM(1) VP_E1_STATUS, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, @@ -498,20 +498,6 @@ const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; const char H43Version[] PROGMEM = "MKS H43_V1.30"; const char Updata_Time[] PROGMEM = STRING_DISTRIBUTION_DATE; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) \ - { \ - .VP = VPADR, .memadr = VPADRVAR, .size = sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR \ - } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR) \ - { \ - .VP = VPADR, .memadr = VPADRVAR, .size = STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR \ - } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -522,109 +508,109 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), // Back Button - VPHELPER(VP_BACK_PAGE, nullptr, &ScreenHandler.ScreenBackChange, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_BACK_PAGE, nullptr, ScreenHandler.ScreenBackChange, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_X_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Y_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Z_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_X_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Y_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Z_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, &ScreenHandler.GetManualMovestep, nullptr), + VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, ScreenHandler.GetManualMovestep, nullptr), - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_LEVEL_POINT, nullptr, &ScreenHandler.ManualAssistLeveling, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_LEVEL_POINT, nullptr, ScreenHandler.ManualAssistLeveling, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay}, - {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay}, + {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, // Temperature Data - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_LOAD_Filament, nullptr, &ScreenHandler.MKS_FilamentLoad, nullptr), - VPHELPER(VP_UNLOAD_Filament, nullptr, &ScreenHandler.MKS_FilamentUnLoad, nullptr), - VPHELPER(VP_Filament_distance, &distanceFilament, &ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, &ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_LOAD_Filament, nullptr, ScreenHandler.MKS_FilamentLoad, nullptr), + VPHELPER(VP_UNLOAD_Filament, nullptr, ScreenHandler.MKS_FilamentUnLoad, nullptr), + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif #endif #if HOTENDS >= 2 VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_Filament_distance, &distanceFilament, &ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, &ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, &ScreenHandler.DGUSLCD_SendFanToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, ScreenHandler.DGUSLCD_SendFanToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -646,8 +632,8 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Print Progress VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), - //LCD Control - VPHELPER(VP_LCD_BLK, &lcd_default_light, &ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + // LCD Control + VPHELPER(VP_LCD_BLK, &lcd_default_light, ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay_MKS), @@ -665,22 +651,22 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_Y_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Y_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif #endif VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Y_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HOTENDS >= 2 + VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif #endif VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, ScreenHandler.HandleTravelAccChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), @@ -748,18 +734,17 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), #if ENABLED(PREVENT_COLD_EXTRUSION) - VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, ScreenHandler.GetMinExtrudeTemp, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif - VPHELPER(VP_AutoTurnOffSw, nullptr, &ScreenHandler.GetTurnOffCtrl, nullptr), + VPHELPER(VP_AutoTurnOffSw, nullptr, ScreenHandler.GetTurnOffCtrl, nullptr), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #endif - // SDCard File listing @@ -781,8 +766,8 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, &ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), #endif #if HAS_BED_PROBE VPHELPER(VP_OFFSET_X, &probe.offset.x, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -798,15 +783,15 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index c648d06218..74992823af 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -575,7 +575,6 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { settings.save(); } else if (mesh_point_count == 0) { - mesh_point_count = GRID_MAX_POINTS; soft_endstop._enabled = true; settings.save(); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 4a67b4afda..0fc4c713f0 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -189,12 +189,12 @@ public: static void PrintReturn(DGUS_VP_Variable &var, void *val_ptr); #endif - // OK Button the Confirm screen. + // OK Button on the Confirm screen. static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); - // Update data after went to new screen (by display or by GotoScreen) - // remember: store the last-displayed screen, so it can get returned to. - // (e.g for pop up messages) + // Update data after going to a new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can be returned to. + // (e.g for popup messages) static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); // Recall the remembered screen. diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index 1c2944bb4f..b5d252a444 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -55,11 +55,11 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -69,11 +69,11 @@ const uint16_t VPList_Temp[] PROGMEM = { const uint16_t VPList_Status[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -90,72 +90,40 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { // VP_M117, for completeness, but it cannot be auto-uploaded - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; - -const uint16_t VPList_ManualMove[] PROGMEM = { - VP_XPos, VP_YPos, VP_ZPos, - 0x0000 -}; - -const uint16_t VPList_ManualExtrude[] PROGMEM = { - VP_EPos, - 0x0000 -}; - -const uint16_t VPList_FanAndFeedrate[] PROGMEM = { - VP_Feedrate_Percentage, VP_Fan0_Percentage, - 0x0000 -}; - -const uint16_t VPList_SD_FlowRates[] PROGMEM = { - VP_Flowrate_E0, VP_Flowrate_E1, - 0x0000 -}; - -const uint16_t VPList_SDFileList[] PROGMEM = { - VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, - 0x0000 -}; - -const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { - VP_PrintProgress_Percentage, VP_PrintTime, - 0x0000 -}; +const uint16_t VPList_ManualMove[] PROGMEM = { VP_XPos, VP_YPos, VP_ZPos, 0x0000 }; +const uint16_t VPList_ManualExtrude[] PROGMEM = { VP_EPos, 0x0000 }; +const uint16_t VPList_FanAndFeedrate[] PROGMEM = { VP_Feedrate_Percentage, VP_Fan0_Percentage, 0x0000 }; +const uint16_t VPList_SD_FlowRates[] PROGMEM = { VP_Flowrate_E0, VP_Flowrate_E1, 0x0000 }; +const uint16_t VPList_SDFileList[] PROGMEM = { VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, 0x0000 }; +const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, - { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, + { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -165,72 +133,71 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_T_E0_Is, nullptr, nullptr, SET_VARIABLE(getActualTemp_celsius, E0, long)), - VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), - SET_VARIABLE(getTargetTemp_celsius, E0)), - VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), SET_VARIABLE(getTargetTemp_celsius, E0)), + VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), @@ -241,14 +208,14 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -256,23 +223,23 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), #endif VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -289,7 +256,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -301,10 +268,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index f05dfc6f70..70efb355fc 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -251,7 +251,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -331,18 +331,18 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); - #endif - #if HOTENDS >= 2 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif #endif GotoScreen(DGUSLCD_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); From b87e2ceda18fb07fb75605710cc897cd39f9f142 Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Mon, 14 Jun 2021 09:31:38 +0800 Subject: [PATCH 0264/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20ExtUI/DGUS=20Cel?= =?UTF-8?q?sius=20display=20(#22121)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 4 +- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 4 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 9 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 181 +----------------- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 4 + .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 1 + .../lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 2 +- 7 files changed, 17 insertions(+), 188 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 4ca7db7f40..79f39f93d8 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -356,7 +356,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -377,7 +377,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index 536c2b09b8..3d0e073e5c 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -362,7 +362,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -383,7 +383,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index d598f100de..7d8581c9f3 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -543,7 +543,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -568,7 +568,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), @@ -588,7 +588,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), @@ -635,6 +635,9 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // LCD Control VPHELPER(VP_LCD_BLK, &lcd_default_light, ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + // SD File - Back + VPHELPER(VP_SD_FileSelect_Back, nullptr, ScreenHandler.SD_FileBack, nullptr), + // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay_MKS), diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index fef7002ad8..cd86ec5105 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -241,191 +241,11 @@ enum DGUSLCD_Screens : uint8_t { DGUSLDC_SCREEN_UNUSED = 255 }; -// Display Memory layout used (T5UID) -// Except system variables this is arbitrary, just to organize stuff.... - -// 0x0000 .. 0x0FFF -- System variables and reserved by the display -// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version -// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) -// 0x3000 .. 0x4FFF -- Marlin Data to be displayed -// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused - -// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, -// so that we can keep variables nicely together in the address space. - -// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. - -// constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible -// constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible -// constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. -// constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. - -// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. -// constexpr uint16_t VP_MSGSTR1 = 0x1100; -// constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... -// constexpr uint16_t VP_MSGSTR2 = 0x1140; -// constexpr uint8_t VP_MSGSTR2_LEN = 0x20; -// constexpr uint16_t VP_MSGSTR3 = 0x1180; -// constexpr uint8_t VP_MSGSTR3_LEN = 0x20; -// constexpr uint16_t VP_MSGSTR4 = 0x11C0; -// constexpr uint8_t VP_MSGSTR4_LEN = 0x20; - -// Screenchange request for screens that only make sense when printer is idle. -// e.g movement is only allowed if printer is not printing. -// Marlin must confirm by setting the screen manually. -// constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; -// constexpr uint16_t VP_SCREENCHANGE = 0x2001; // Key-Return button to new menu pressed. Data contains target screen in low byte and info in high byte. -// constexpr uint16_t VP_TEMP_ALL_OFF = 0x2002; // Turn all heaters off. Value arbitrary ;)= -// constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. -// constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. - -// // Buttons on the SD-Card File listing. -// constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down -// constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. -// constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) - -// constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints -// constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) -// constexpr uint16_t VP_SD_Print_Setting = 0x2040; -// constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up - -// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values -// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) -// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us -// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. -// constexpr uint16_t VP_MOVE_X = 0x2100; -// constexpr uint16_t VP_MOVE_Y = 0x2102; -// constexpr uint16_t VP_MOVE_Z = 0x2104; -// constexpr uint16_t VP_MOVE_E0 = 0x2110; -// constexpr uint16_t VP_MOVE_E1 = 0x2112; -// //constexpr uint16_t VP_MOVE_E2 = 0x2114; -// //constexpr uint16_t VP_MOVE_E3 = 0x2116; -// //constexpr uint16_t VP_MOVE_E4 = 0x2118; -// //constexpr uint16_t VP_MOVE_E5 = 0x211A; -// constexpr uint16_t VP_HOME_ALL = 0x2120; -// constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; -// constexpr uint16_t VP_XYZ_HOME = 0x2132; - -// Power loss recovery -// 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; - -// // Heater Control Buttons , triged between "cool down" and "heat PLA" state -// constexpr uint16_t VP_E0_CONTROL = 0x2210; -// constexpr uint16_t VP_E1_CONTROL = 0x2212; -// //constexpr uint16_t VP_E2_CONTROL = 0x2214; -// //constexpr uint16_t VP_E3_CONTROL = 0x2216; -// //constexpr uint16_t VP_E4_CONTROL = 0x2218; -// //constexpr uint16_t VP_E5_CONTROL = 0x221A; -// constexpr uint16_t VP_BED_CONTROL = 0x221C; - -// // Preheat -// constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; -// constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; -// //constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; -// //constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; -// //constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; -// //constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; - -// // Filament load and unload -// // constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; -// // constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; - -// // Settings store , reset - -// // PID autotune -// constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; -// constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; -// //constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; -// //constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; -// //constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; -// //constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; -// constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; -// // Calibrate Z -// constexpr uint16_t VP_Z_CALIBRATE = 0x2430; - -// First layer cal -// constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded - -// Firmware version on the boot screen. -// constexpr uint16_t VP_MARLIN_VERSION = 0x3000; -// constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. // Place for status messages. constexpr uint16_t VP_M117 = 0x7020; constexpr uint8_t VP_M117_LEN = 0x20; -// // Temperatures. -// constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer -// constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer -// constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer -// // reserved to support up to 6 Extruders: -// constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer -// constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer -// constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer -// constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer -// constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer -// constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer -// constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer -// constexpr uint16_t VP_T_E5_Is = 0x3074; // 4 Byte Integer -// constexpr uint16_t VP_T_E5_Set = 0x3076; // 2 Byte Integer -// constexpr uint16_t VP_T_E6_Is = 0x3078; // 4 Byte Integer -// constexpr uint16_t VP_T_E6_Set = 0x307A; // 2 Byte Integer -// constexpr uint16_t VP_T_E7_Is = 0x3078; // 4 Byte Integer -// constexpr uint16_t VP_T_E7_Set = 0x307A; // 2 Byte Integer - - -// constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer -// constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer - -// constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer -// constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer -// // reserved for up to 6 Extruders: -// constexpr uint16_t VP_Flowrate_E2 = 0x3094; -// constexpr uint16_t VP_Flowrate_E3 = 0x3096; -// constexpr uint16_t VP_Flowrate_E4 = 0x3098; -// constexpr uint16_t VP_Flowrate_E5 = 0x309A; - -// constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) - -// Actual Position -// constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy - -// constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) - -// constexpr uint16_t VP_PrintTime = 0x3140; -// constexpr uint16_t VP_PrintTime_LEN = 32; - -// constexpr uint16_t VP_PrintAccTime = 0x3160; -// constexpr uint16_t VP_PrintAccTime_LEN = 32; - -// constexpr uint16_t VP_PrintsTotal = 0x3180; -// constexpr uint16_t VP_PrintsTotal_LEN = 16; - -// // SDCard File Listing -// constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. -// constexpr uint16_t DGUS_SD_FILESPERSCREEN = 8; // FIXME move that info to the display and read it from there. -// constexpr uint16_t VP_SD_FileName0 = 0x3200; -// constexpr uint16_t VP_SD_FileName1 = 0x3220; -// constexpr uint16_t VP_SD_FileName2 = 0x3240; -// constexpr uint16_t VP_SD_FileName3 = 0x3260; -// constexpr uint16_t VP_SD_FileName4 = 0x3280; -// constexpr uint16_t VP_SD_FileName5 = 0x32A0; -// constexpr uint16_t VP_SD_FileName6 = 0x32C0; -// constexpr uint16_t VP_SD_FileName7 = 0x32E0; - // Heater status constexpr uint16_t VP_E0_STATUS = 0x3410; constexpr uint16_t VP_E1_STATUS = 0x3412; @@ -635,6 +455,7 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_SD_Print_LiveAdjustZ_Confirm = 0x3060; constexpr uint16_t VP_ZOffset_Distance = 0x3070; constexpr uint16_t VP_ZOffset_DE_DIS = 0x3080; + constexpr uint16_t VP_SD_FileSelect_Back = 0x3082; // SDCard File Listing constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. constexpr uint16_t DGUS_SD_FILESPERSCREEN = 10; // FIXME move that info to the display and read it from there. diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 74992823af..aabe6fc531 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -588,6 +588,10 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { #endif // MESH_BED_LEVELING } +void DGUSScreenHandler::SD_FileBack(DGUS_VP_Variable&, void*) { + GotoScreen(MKSLCD_SCREEN_HOME); +} + void DGUSScreenHandler::LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t lcd_value = swap16(*(uint16_t *)val_ptr); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 0fc4c713f0..7d5263c6b8 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -93,6 +93,7 @@ public: static void DGUS_RunoutInit(void); static void DGUS_ExtrudeLoadInit(void); static void LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr); + static void SD_FileBack(DGUS_VP_Variable &var, void *val_ptr); // Hook for manual move. static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index b5d252a444..af57f3dccc 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -183,7 +183,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), From 3a03f76f3c82e93800a07dd2b28a34d0c53245e3 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 13 Jun 2021 18:43:43 -0700 Subject: [PATCH 0265/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20UBL=20'R'=20para?= =?UTF-8?q?meter=20and=20adjust=20'P'=20(#22129)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 4 +-- Marlin/src/feature/bedlevel/ubl/ubl.h | 8 +++--- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 28 ++++++++++----------- Marlin/src/lcd/menu/menu_ubl.cpp | 6 ++--- 4 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index b7a2c380ce..37c8be5bd8 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -164,7 +164,7 @@ static void serial_echo_column_labels(const uint8_t sp) { * 2: TODO: Display on Graphical LCD * 4: Compact Human-Readable */ -void unified_bed_leveling::display_map(const int map_type) { +void unified_bed_leveling::display_map(const uint8_t map_type) { const bool was = gcode.set_autoreport_paused(true); constexpr uint8_t eachsp = 1 + 6 + 1, // [-3.567] @@ -263,7 +263,7 @@ bool unified_bed_leveling::sanity_check() { void GcodeSuite::M1004() { #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "") - #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R255") + #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R") #if HAS_HOTEND if (parser.seenval('H')) { // Handle H# parameter to set Hotend temp diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 562f15f74b..cf00a282cf 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -47,10 +47,10 @@ struct mesh_index_pair; typedef struct { bool C_seen; - int8_t V_verbosity, + int8_t KLS_storage_slot; + uint8_t R_repetition, + V_verbosity, P_phase, - R_repetition, - KLS_storage_slot, T_map_type; float B_shim_thickness, C_constant; @@ -98,7 +98,7 @@ public: static void report_state(); static void save_ubl_active_state_and_disable(); static void restore_ubl_active_state_and_leave(); - static void display_map(const int) _O0; + static void display_map(const uint8_t) _O0; static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const xy_pos_t&, const bool=false, MeshFlags *done_flags=nullptr) _O0; static mesh_index_pair find_furthest_invalid_mesh_point() _O0; static void reset(); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index b5773b0d46..11c05f6054 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -305,7 +305,7 @@ void unified_bed_leveling::G29() { bool probe_deployed = false; if (G29_parse_parameters()) return; // Abort on parameter error - const int8_t p_val = parser.intval('P', -1); + const uint8_t p_val = parser.byteval('P'); const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); #if ENABLED(HAS_MULTI_HOTEND) const uint8_t old_tool_index = active_extruder; @@ -321,7 +321,7 @@ void unified_bed_leveling::G29() { // Invalidate one or more nearby mesh points, possibly all. if (parser.seen('I')) { - int16_t count = parser.has_value() ? parser.value_int() : 1; + uint8_t count = parser.has_value() ? parser.value_byte() : 1; bool invalidate_all = count >= GRID_MAX_POINTS; if (!invalidate_all) { while (count--) { @@ -345,7 +345,7 @@ void unified_bed_leveling::G29() { } if (parser.seen('Q')) { - const int test_pattern = parser.has_value() ? parser.value_int() : -99; + const int16_t test_pattern = parser.has_value() ? parser.value_int() : -99; if (!WITHIN(test_pattern, -1, 2)) { SERIAL_ECHOLNPGM("Invalid test_pattern value. (-1 to 2)\n"); return; @@ -592,7 +592,7 @@ void unified_bed_leveling::G29() { // if (parser.seen('L')) { // Load Current Mesh Data - param.KLS_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; int16_t a = settings.calc_num_meshes(); @@ -617,10 +617,10 @@ void unified_bed_leveling::G29() { // if (parser.seen('S')) { // Store (or Save) Current Mesh Data - param.KLS_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; - if (param.KLS_storage_slot == -1) // Special case, the user wants to 'Export' the mesh to the - return report_current_mesh(); // host program to be saved on the user's computer + if (param.KLS_storage_slot == -1) // Special case: 'Export' the mesh to the + return report_current_mesh(); // host so it can be saved in a file. int16_t a = settings.calc_num_meshes(); @@ -673,7 +673,7 @@ void unified_bed_leveling::G29() { */ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t offset) { float sum = 0; - int n = 0; + uint8_t n = 0; GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { sum += z_values[x][y]; @@ -734,7 +734,7 @@ void unified_bed_leveling::shift_mesh_height() { do { if (do_ubl_mesh_map) display_map(param.T_map_type); - const int point_num = (GRID_MAX_POINTS) - count + 1; + const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); @@ -1083,7 +1083,7 @@ bool unified_bed_leveling::G29_parse_parameters() { param.R_repetition = 0; if (parser.seen('R')) { - param.R_repetition = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS; + param.R_repetition = parser.has_value() ? parser.value_byte() : GRID_MAX_POINTS; NOMORE(param.R_repetition, GRID_MAX_POINTS); if (param.R_repetition < 1) { SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); @@ -1091,14 +1091,14 @@ bool unified_bed_leveling::G29_parse_parameters() { } } - param.V_verbosity = parser.intval('V'); + param.V_verbosity = parser.byteval('V'); if (!WITHIN(param.V_verbosity, 0, 4)) { SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n"); err_flag = true; } if (parser.seen('P')) { - const int pv = parser.value_int(); + const uint8_t pv = parser.value_byte(); #if !HAS_BED_PROBE if (pv == 1) { SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); @@ -1181,7 +1181,7 @@ bool unified_bed_leveling::G29_parse_parameters() { } #endif - param.T_map_type = parser.intval('T'); + param.T_map_type = parser.byteval('T'); if (!WITHIN(param.T_map_type, 0, 2)) { SERIAL_ECHOLNPGM("Invalid map type.\n"); return UBL_ERR; @@ -1833,7 +1833,7 @@ void unified_bed_leveling::smart_fill_mesh() { return; } - param.KLS_storage_slot = parser.value_int(); + param.KLS_storage_slot = (int8_t)parser.value_int(); float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; settings.load_mesh(param.KLS_storage_slot, &tmp_z_values); diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 880b76ff76..467bd81acf 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -176,7 +176,7 @@ void _menu_ubl_height_adjust() { void _lcd_ubl_edit_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_TOOLS); - GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29P4RT")); GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29P4T")); SUBMENU(MSG_UBL_MESH_HEIGHT_ADJUST, _menu_ubl_height_adjust); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); @@ -594,9 +594,9 @@ void _menu_ubl_tools() { GCODES_ITEM(MSG_UBL_1_BUILD_COLD_MESH, PSTR("G29NP1")); GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, PSTR("G29P3T0")); SUBMENU(MSG_UBL_3_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4RT")); SUBMENU(MSG_UBL_5_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4RT")); ACTION_ITEM(MSG_UBL_7_SAVE_MESH, _lcd_ubl_save_mesh_cmd); END_MENU(); } From ef321cb7230f0bc89c8ea491033a5f93496306b9 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Sun, 13 Jun 2021 22:47:38 -0300 Subject: [PATCH 0266/2168] =?UTF-8?q?=F0=9F=90=9B=20Include=20common=20TFT?= =?UTF-8?q?=20driver=20macros=20(#22125)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/tft_io/tft_io.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index c06e86b281..29c7da235c 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -39,12 +39,6 @@ #if TFT_DRIVER == R61505 || TFT_DRIVER == AUTO #include "r65105.h" #endif -#if TFT_DRIVER == ILI9328 || TFT_DRIVER == AUTO - #include "ili9328.h" -#endif -#if TFT_DRIVER == ILI9341 || TFT_DRIVER == AUTO - #include "ili9341.h" -#endif #if TFT_DRIVER == ILI9488 || TFT_DRIVER == ILI9488_ID1 || TFT_DRIVER == AUTO #include "ili9488.h" #endif @@ -52,6 +46,9 @@ #include "ssd1963.h" #endif +#include "ili9341.h" +#include "ili9328.h" + #define DEBUG_OUT ENABLED(DEBUG_GRAPHICAL_TFT) #include "../../core/debug_out.h" From a3e8bb99e472042c7db0b2d0be8d515ee715cf28 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Sun, 13 Jun 2021 23:08:46 -0400 Subject: [PATCH 0267/2168] =?UTF-8?q?=F0=9F=8E=A8=20ExtUI=20"user=20click"?= =?UTF-8?q?=20and=20other=20tweaks=20(#22122)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 4 +- Marlin/src/lcd/extui/ui_api.cpp | 180 ++++++++++++++------------ Marlin/src/lcd/extui/ui_api.h | 8 +- Marlin/src/lcd/marlinui.cpp | 12 +- Marlin/src/lcd/marlinui.h | 16 ++- Marlin/src/module/probe.cpp | 2 +- Marlin/src/module/temperature.cpp | 4 +- Marlin/src/module/temperature.h | 2 +- 8 files changed, 125 insertions(+), 103 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 055acc1ed4..21336f0b9a 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -70,7 +70,7 @@ void GcodeSuite::G29() { return; } - int8_t ix, iy; + int8_t ix, iy = 0; switch (state) { case MeshReport: @@ -88,6 +88,7 @@ void GcodeSuite::G29() { mbl_probe_index = 0; if (!ui.wait_for_move) { queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2")); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); return; } state = MeshNext; @@ -109,6 +110,7 @@ void GcodeSuite::G29() { else { // Save Z for the previous mesh position mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z)); SET_SOFT_ENDSTOP_LOOSE(false); } // If there's another point to sample, move there with optional lift. diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index b0def618fd..ddeb02e3be 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -47,6 +47,7 @@ #include "../marlinui.h" #include "../../gcode/queue.h" +#include "../../gcode/gcode.h" #include "../../module/motion.h" #include "../../module/planner.h" #include "../../module/probe.h" @@ -353,14 +354,9 @@ namespace ExtUI { extruder_t getTool(const uint8_t extruder) { switch (extruder) { - case 7: return E7; - case 6: return E6; - case 5: return E5; - case 4: return E4; - case 3: return E3; - case 2: return E2; - case 1: return E1; - default: return E0; + default: + case 0: return E0; case 1: return E1; case 2: return E2; case 3: return E3; + case 4: return E4; case 5: return E5; case 6: return E6; case 7: return E7; } } @@ -372,8 +368,8 @@ namespace ExtUI { switch (axis) { #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) case X: return axis_should_home(X_AXIS); - case Y: return axis_should_home(Y_AXIS); - case Z: return axis_should_home(Z_AXIS); + OPTCODE(HAS_Y_AXIS, case Y: return axis_should_home(Y_AXIS)) + OPTCODE(HAS_Z_AXIS, case Z: return axis_should_home(Z_AXIS)) #else case X: case Y: case Z: return true; #endif @@ -385,6 +381,8 @@ namespace ExtUI { return !thermalManager.tooColdToExtrude(extruder - E0); } + GcodeSuite::MarlinBusyState getMachineBusyState() { return TERN0(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state); } + #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; } @@ -396,18 +394,27 @@ namespace ExtUI { #if AXIS_IS_TMC(X) case X: return stepperX.getMilliamps(); #endif - #if AXIS_IS_TMC(X2) - case X2: return stepperX2.getMilliamps(); - #endif #if AXIS_IS_TMC(Y) case Y: return stepperY.getMilliamps(); #endif - #if AXIS_IS_TMC(Y2) - case Y2: return stepperY2.getMilliamps(); - #endif #if AXIS_IS_TMC(Z) case Z: return stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + case I: return stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + case J: return stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + case K: return stepperK.getMilliamps(); + #endif + #if AXIS_IS_TMC(X2) + case X2: return stepperX2.getMilliamps(); + #endif + #if AXIS_IS_TMC(Y2) + case Y2: return stepperY2.getMilliamps(); + #endif #if AXIS_IS_TMC(Z2) case Z2: return stepperZ2.getMilliamps(); #endif @@ -450,18 +457,27 @@ namespace ExtUI { #if AXIS_IS_TMC(X) case X: stepperX.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(X2) - case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Y) case Y: stepperY.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(Y2) - case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Z) case Z: stepperZ.rms_current(constrain(mA, 400, 1500)); break; #endif + #if AXIS_IS_TMC(I) + case I: stepperI.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(J) + case J: stepperJ.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(K) + case K: stepperK.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(X2) + case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(Y2) + case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; + #endif #if AXIS_IS_TMC(Z2) case Z2: stepperZ2.rms_current(constrain(mA, 400, 1500)); break; #endif @@ -501,66 +517,59 @@ namespace ExtUI { int getTMCBumpSensitivity(const axis_t axis) { switch (axis) { - #if ENABLED(X_SENSORLESS) - case X: return stepperX.homing_threshold(); - #endif - #if ENABLED(X2_SENSORLESS) - case X2: return stepperX2.homing_threshold(); - #endif - #if ENABLED(Y_SENSORLESS) - case Y: return stepperY.homing_threshold(); - #endif - #if ENABLED(Y2_SENSORLESS) - case Y2: return stepperY2.homing_threshold(); - #endif - #if ENABLED(Z_SENSORLESS) - case Z: return stepperZ.homing_threshold(); - #endif - #if ENABLED(Z2_SENSORLESS) - case Z2: return stepperZ2.homing_threshold(); - #endif - #if ENABLED(Z3_SENSORLESS) - case Z3: return stepperZ3.homing_threshold(); - #endif - #if ENABLED(Z4_SENSORLESS) - case Z4: return stepperZ4.homing_threshold(); - #endif + OPTCODE(X_SENSORLESS, case X: return stepperX.homing_threshold()) + OPTCODE(Y_SENSORLESS, case Y: return stepperY.homing_threshold()) + OPTCODE(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()) + OPTCODE(I_SENSORLESS, case I: return stepperI.homing_threshold()) + OPTCODE(J_SENSORLESS, case J: return stepperJ.homing_threshold()) + OPTCODE(K_SENSORLESS, case K: return stepperK.homing_threshold()) + OPTCODE(X2_SENSORLESS, case X2: return stepperX2.homing_threshold()) + OPTCODE(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold()) + OPTCODE(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold()) + OPTCODE(Z3_SENSORLESS, case Z3: return stepperZ3.homing_threshold()) + OPTCODE(Z4_SENSORLESS, case Z4: return stepperZ4.homing_threshold()) default: return 0; } } void setTMCBumpSensitivity(const_float_t value, const axis_t axis) { switch (axis) { - #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS - #if X_SENSORLESS - case X: stepperX.homing_threshold(value); break; - #endif - #if X2_SENSORLESS - case X2: stepperX2.homing_threshold(value); break; - #endif - #if Y_SENSORLESS - case Y: stepperY.homing_threshold(value); break; - #endif - #if Y2_SENSORLESS - case Y2: stepperY2.homing_threshold(value); break; - #endif - #if Z_SENSORLESS - case Z: stepperZ.homing_threshold(value); break; - #endif - #if Z2_SENSORLESS - case Z2: stepperZ2.homing_threshold(value); break; - #endif - #if Z3_SENSORLESS - case Z3: stepperZ3.homing_threshold(value); break; - #endif - #if Z4_SENSORLESS - case Z4: stepperZ4.homing_threshold(value); break; - #endif - #else - UNUSED(value); + #if X_SENSORLESS + case X: stepperX.homing_threshold(value); break; + #endif + #if Y_SENSORLESS + case Y: stepperY.homing_threshold(value); break; + #endif + #if Z_SENSORLESS + case Z: stepperZ.homing_threshold(value); break; + #endif + #if I_SENSORLESS + case I: stepperI.homing_threshold(value); break; + #endif + #if J_SENSORLESS + case J: stepperJ.homing_threshold(value); break; + #endif + #if K_SENSORLESS + case K: stepperK.homing_threshold(value); break; + #endif + #if X2_SENSORLESS + case X2: stepperX2.homing_threshold(value); break; + #endif + #if Y2_SENSORLESS + case Y2: stepperY2.homing_threshold(value); break; + #endif + #if Z2_SENSORLESS + case Z2: stepperZ2.homing_threshold(value); break; + #endif + #if Z3_SENSORLESS + case Z3: stepperZ3.homing_threshold(value); break; + #endif + #if Z4_SENSORLESS + case Z4: stepperZ4.homing_threshold(value); break; #endif default: break; } + UNUSED(value); } #endif @@ -661,9 +670,7 @@ namespace ExtUI { #if HAS_JUNCTION_DEVIATION - float getJunctionDeviation_mm() { - return planner.junction_deviation_mm; - } + float getJunctionDeviation_mm() { return planner.junction_deviation_mm; } void setJunctionDeviation_mm(const_float_t value) { planner.junction_deviation_mm = constrain(value, 0.001, 0.3); @@ -682,7 +689,7 @@ namespace ExtUI { #endif #if PREHEAT_COUNT - uint16_t getMaterial_preset_E(const uint16_t index) { return ui.material_preset[index].hotend_temp; } + uint16_t getMaterial_preset_E(const uint16_t index) { return ui.material_preset[index].hotend_temp; } #if HAS_HEATED_BED uint16_t getMaterial_preset_B(const uint16_t index) { return ui.material_preset[index].bed_temp; } #endif @@ -709,9 +716,13 @@ namespace ExtUI { switch (axis) { #if ENABLED(BABYSTEP_XY) case X: babystep.add_steps(X_AXIS, steps); break; - case Y: babystep.add_steps(Y_AXIS, steps); break; + #if HAS_Y_AXIS + case Y: babystep.add_steps(Y_AXIS, steps); break; + #endif + #endif + #if HAS_Z_AXIS + case Z: babystep.add_steps(Z_AXIS, steps); break; #endif - case Z: babystep.add_steps(Z_AXIS, steps); break; default: return false; }; return true; @@ -750,8 +761,8 @@ namespace ExtUI { hotend_offset[e][axis] += mm; normalizeNozzleOffset(X); - normalizeNozzleOffset(Y); - normalizeNozzleOffset(Z); + TERN_(HAS_Y_AXIS, normalizeNozzleOffset(Y)); + TERN_(HAS_Z_AXIS, normalizeNozzleOffset(Z)); } #else UNUSED(linked_nozzles); @@ -1014,8 +1025,7 @@ namespace ExtUI { TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); } - bool awaitingUserConfirm() { return wait_for_user; } - + bool awaitingUserConfirm() { return TERN0(HAS_RESUME_CONTINUE, wait_for_user); } void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } void printFile(const char *filename) { @@ -1038,9 +1048,9 @@ namespace ExtUI { bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED() && card.isMounted()); } - void pausePrint() { ui.pause_print(); } + void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } - void stopPrint() { ui.abort_print(); } + void stopPrint() { ui.abort_print(); } void onUserConfirmRequired_P(PGM_P const pstr) { char msg[strlen_P(pstr) + 1]; diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 9922fa6799..8d8b0e59e4 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -44,6 +44,7 @@ #include "../../inc/MarlinConfig.h" #include "../marlinui.h" +#include "../../gcode/gcode.h" namespace ExtUI { @@ -53,7 +54,7 @@ namespace ExtUI { static constexpr size_t eeprom_data_size = 48; - enum axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4 }; + enum axis_t : uint8_t { X, Y, Z, I, J, K, X2, Y2, Z2, Z3, Z4 }; enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 }; enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER, COOLER }; enum fan_t : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 }; @@ -78,6 +79,8 @@ namespace ExtUI { void injectCommands(char * const); bool commandsInQueue(); + GcodeSuite::MarlinBusyState getMachineBusyState(); + bool isHeaterIdle(const heater_t); bool isHeaterIdle(const extruder_t); void enableHeater(const heater_t); @@ -125,6 +128,7 @@ namespace ExtUI { float getAxisMaxAcceleration_mm_s2(const extruder_t); feedRate_t getMinFeedrate_mm_s(); feedRate_t getMinTravelFeedrate_mm_s(); + feedRate_t getFeedrate_mm_s(); float getPrintingAcceleration_mm_s2(); float getRetractAcceleration_mm_s2(); float getTravelAcceleration_mm_s2(); @@ -186,6 +190,8 @@ namespace ExtUI { void setHostResponse(const uint8_t); #endif + inline void simulateUserClick() { ui.lcd_clicked = true; } + #if ENABLED(PRINTCOUNTER) char* getFailedPrints_str(char buffer[21]); char* getTotalPrints_str(char buffer[21]); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index cff6e19354..d2e26afedf 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -223,6 +223,10 @@ millis_t MarlinUI::next_button_update_ms; // = 0 #endif +#if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + bool MarlinUI::lcd_clicked; +#endif + #if HAS_LCD_MENU #include "menu/menu.h" @@ -247,14 +251,6 @@ millis_t MarlinUI::next_button_update_ms; // = 0 uint8_t MarlinUI::repeat_delay; #endif - bool MarlinUI::lcd_clicked; - - bool MarlinUI::use_click() { - const bool click = lcd_clicked; - lcd_clicked = false; - return click; - } - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) bool MarlinUI::external_control; // = false diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 766e46c66b..14514e2a65 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -474,9 +474,6 @@ public: static void set_selection(const bool sel) { selection = sel; } static bool update_selection(); - static bool lcd_clicked; - static bool use_click(); - static void synchronize(PGM_P const msg=nullptr); static screenFunc_t currentScreen; @@ -527,12 +524,23 @@ public: #elif HAS_WIRED_LCD - static constexpr bool lcd_clicked = false; static constexpr bool on_status_screen() { return true; } FORCE_INLINE static void run_current_screen() { status_screen(); } #endif + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + static bool lcd_clicked; + static inline bool use_click() { + const bool click = lcd_clicked; + lcd_clicked = false; + return click; + } + #else + static constexpr bool lcd_clicked = false; + static inline bool use_click() { return false; } + #endif + #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 0042302fc7..2b3a189884 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -384,7 +384,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { DEBUG_EOL(); TERN_(WAIT_FOR_NOZZLE_HEAT, if (hotend_temp > thermalManager.wholeDegHotend(0) + (TEMP_WINDOW)) thermalManager.wait_for_hotend(0)); - TERN_(WAIT_FOR_BED_HEAT, if (bed_temp > thermalManager.wholeDegBed() + (TEMP_BED_WINDOW)) thermalManager.wait_for_bed_heating()); + TERN_(WAIT_FOR_BED_HEAT, if (bed_temp > thermalManager.wholeDegBed() + (TEMP_BED_WINDOW)) thermalManager.wait_for_bed_heating()); } #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index a5922cf553..e7d4ece721 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3621,7 +3621,7 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif @@ -3755,7 +3755,7 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index e0dffc3f3a..3a8c506a5d 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -174,7 +174,7 @@ enum ADCSensorState : char { #define unscalePID_d(d) ( float(d) * PID_dT ) #endif -#if BOTH(HAS_LCD_MENU, G26_MESH_VALIDATION) +#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) #define G26_CLICK_CAN_CANCEL 1 #endif From d6a7ebce6caf01751551712684e138ca7df93a00 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Mon, 14 Jun 2021 02:39:16 -0300 Subject: [PATCH 0268/2168] =?UTF-8?q?=E2=9C=A8=20MULTI=5FVOLUME=20for=20Co?= =?UTF-8?q?lor=20UI=20and=20MarlinUI=20(#22004)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/msc_sd.cpp | 4 +-- .../lcd/extui/mks_ui/draw_media_select.cpp | 4 +-- Marlin/src/lcd/language/language_en.h | 3 +++ Marlin/src/lcd/menu/menu_media.cpp | 26 +++++++++++++++++-- Marlin/src/sd/cardreader.cpp | 19 ++++++-------- Marlin/src/sd/cardreader.h | 11 ++++---- 6 files changed, 45 insertions(+), 22 deletions(-) diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index cbfb837875..64f2533002 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -33,9 +33,9 @@ public: DiskIODriver* diskIODriver() { #if ENABLED(MULTI_VOLUME) #if SHARED_VOLUME_IS(SD_ONBOARD) - return &card.media_sd_spi; + return &card.media_driver_sdcard; #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) - return &card.media_usbFlashDrive; + return &card.media_driver_usbFlash; #endif #else return card.diskIODriver(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 6fa5cefef0..0394ed6009 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -46,8 +46,8 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; lv_clear_media_select(); switch (obj->mks_obj_id) { - case ID_T_USB_DISK: card.changeMedia(&card.media_usbFlashDrive); break; - case ID_T_SD_DISK: card.changeMedia(&card.media_sd_spi); break; + case ID_T_USB_DISK: card.changeMedia(&card.media_driver_usbFlash); break; + case ID_T_SD_DISK: card.changeMedia(&card.media_driver_sdcard); break; case ID_T_RETURN: TERN_(MKS_TEST, curent_disp_ui = 1); lv_draw_ready_print(); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 33f11c9ffd..9a3f9b6e9f 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -740,6 +740,9 @@ namespace Language_en { PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibration Failed"); PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Card"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Disk"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 7a525d06b5..8630f48b37 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -104,7 +104,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { } }; -void menu_media() { +void menu_media_filelist() { ui.encoder_direction_menus(); #if HAS_MARLINUI_U8GLIB @@ -115,7 +115,11 @@ void menu_media() { #endif START_MENU(); - BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #if ENABLED(MULTI_VOLUME) + ACTION_ITEM(MSG_BACK, []{ ui.goto_screen(menu_media); }); + #else + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #endif if (card.flag.workDirIsRoot) { #if !PIN_EXISTS(SD_DETECT) ACTION_ITEM(MSG_REFRESH, []{ encoderTopLine = 0; card.mount(); }); @@ -138,4 +142,22 @@ void menu_media() { END_MENU(); } +#if ENABLED(MULTI_VOLUME) + void menu_media_select() { + START_MENU(); + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #if ENABLED(VOLUME_SD_ONBOARD) + ACTION_ITEM(MSG_SD_CARD, []{ card.changeMedia(&card.media_driver_sdcard); card.mount(); ui.goto_screen(menu_media_filelist); }); + #endif + #if ENABLED(VOLUME_USB_FLASH_DRIVE) + ACTION_ITEM(MSG_USB_DISK, []{ card.changeMedia(&card.media_driver_usbFlash); card.mount(); ui.goto_screen(menu_media_filelist); }); + #endif + END_MENU(); + } +#endif + +void menu_media() { + TERN(MULTI_VOLUME, menu_media_select, menu_media_filelist)(); +} + #endif // HAS_LCD_MENU && SDSUPPORT diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index dc3df482b5..19b2f04bfd 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -121,13 +121,12 @@ uint8_t CardReader::workDirDepth; #endif // SDCARD_SORT_ALPHA -#if SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - DiskIODriver_USBFlash CardReader::media_usbFlashDrive; +#if HAS_USB_FLASH_DRIVE + DiskIODriver_USBFlash CardReader::media_driver_usbFlash; #endif -#if NEED_SD2CARD_SDIO - DiskIODriver_SDIO CardReader::media_sdio; -#elif NEED_SD2CARD_SPI - DiskIODriver_SPI_SD CardReader::media_sd_spi; + +#if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + CardReader::sdcard_driver_t CardReader::media_driver_sdcard; #endif DiskIODriver* CardReader::driver = nullptr; @@ -144,12 +143,10 @@ uint32_t CardReader::filesize, CardReader::sdpos; CardReader::CardReader() { changeMedia(& - #if SHARED_VOLUME_IS(SD_ONBOARD) - TERN(SDIO_SUPPORT, media_sdio, media_sd_spi) - #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - media_usbFlashDrive + #if HAS_USB_FLASH_DRIVE && !SHARED_VOLUME_IS(SD_ONBOARD) + media_driver_usbFlash #else - TERN(SDIO_SUPPORT, media_sdio, media_sd_spi) + media_driver_sdcard #endif ); diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 35d7627421..943cdae741 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -235,12 +235,13 @@ public: #endif #if SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - static DiskIODriver_USBFlash media_usbFlashDrive; + #define HAS_USB_FLASH_DRIVE 1 + static DiskIODriver_USBFlash media_driver_usbFlash; #endif - #if NEED_SD2CARD_SDIO - static DiskIODriver_SDIO media_sdio; - #elif NEED_SD2CARD_SPI - static DiskIODriver_SPI_SD media_sd_spi; + + #if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + typedef TERN(NEED_SD2CARD_SDIO, DiskIODriver_SDIO, DiskIODriver_SPI_SD) sdcard_driver_t; + static sdcard_driver_t media_driver_sdcard; #endif private: From e130aa39c0f90b516c0a65608ef305d0652c49e2 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Mon, 14 Jun 2021 04:24:49 -0300 Subject: [PATCH 0269/2168] =?UTF-8?q?=F0=9F=94=A5=20Remove=20Chitu=20defau?= =?UTF-8?q?lt=20Touch=20Calibration=20(#22133)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 17 ----------------- Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h | 17 ----------------- 2 files changed, 34 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index d25a1f34f9..8f5893e3b9 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -150,26 +150,9 @@ #define HAS_LOGO_IN_FLASH 0 #elif ENABLED(TFT_COLOR_UI) // Color UI - #define TFT_DRIVER ILI9488 #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if ANY(TFT_LVGL_UI, TFT_COLOR_UI, TFT_CLASSIC_UI) - #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -17181 - #endif - #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 11434 - #endif - #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 501 - #endif - #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -9 - #endif -#endif - // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // Needs to use SPI2 #define SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index 5afa653117..df49da1095 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -165,26 +165,9 @@ #define HAS_LOGO_IN_FLASH 0 #elif ENABLED(TFT_COLOR_UI) // Color UI - #define TFT_DRIVER ILI9488 #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if ANY(TFT_LVGL_UI, TFT_COLOR_UI, TFT_CLASSIC_UI) - #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -17181 - #endif - #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 11434 - #endif - #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 501 - #endif - #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -9 - #endif -#endif - // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // so SPI2 is required. #define SPI_DEVICE 2 From 3d0e8346be1a8da6ec665a8e8afc4b6809ebe4a4 Mon Sep 17 00:00:00 2001 From: Bo Herrmannsen Date: Mon, 14 Jun 2021 11:28:13 +0200 Subject: [PATCH 0270/2168] =?UTF-8?q?=E2=9C=A8=20Extruder=20with=20Dual=20?= =?UTF-8?q?Stepper=20Drivers=20(#21403)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 6 ++++++ Marlin/src/inc/Conditionals_LCD.h | 20 ++++++++++++++++---- Marlin/src/inc/SanityCheck.h | 13 +++++++++++++ Marlin/src/module/stepper/indirection.h | 12 ++++++++++++ Marlin/src/pins/pins_postprocess.h | 12 ++++++++++-- buildroot/tests/DUE | 5 ++--- buildroot/tests/LPC1768 | 2 +- 7 files changed, 60 insertions(+), 10 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 726058ebbc..b56ebbb538 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -677,6 +677,12 @@ #endif #endif +// Drive the E axis with two synchronized steppers +//#define E_DUAL_STEPPER_DRIVERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + //#define INVERT_E1_VS_E0_DIR // Enable if the E motors need opposite DIR states +#endif + /** * Dual X Carriage * diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ea83b5abbc..833fe0d227 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -558,7 +558,12 @@ #undef DISABLE_E #endif -#if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 + + #define E_STEPPERS 2 + +#elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS + #if EXTRUDERS > 4 #define E_STEPPERS 3 #elif EXTRUDERS > 2 @@ -569,17 +574,24 @@ #if DISABLED(SWITCHING_NOZZLE) #define HOTENDS E_STEPPERS #endif -#elif ENABLED(MIXING_EXTRUDER) + +#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally + #define E_STEPPERS MIXING_STEPPERS #define E_MANUAL 1 #if MIXING_STEPPERS == 2 #define HAS_DUAL_MIXING 1 #endif -#elif ENABLED(SWITCHING_TOOLHEAD) + +#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger + #define E_STEPPERS EXTRUDERS #define E_MANUAL EXTRUDERS -#elif HAS_PRUSA_MMU2 + +#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 + #define E_STEPPERS 1 + #endif // No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ffb79a6baa..ae3d639957 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1161,6 +1161,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif +/** + * Dual E Steppers requirements + */ +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #if EXTRUDERS > 1 + #error "E_DUAL_STEPPER_DRIVERS can only be used with EXTRUDERS set to 1." + #elif ENABLED(MIXING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with MIXING_EXTRUDER." + #elif ENABLED(SWITCHING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with SWITCHING_EXTRUDER." + #endif +#endif + /** * Linear Advance 1.5 - Check K value range */ diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 4770fd4dc1..08d0be0b31 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -645,6 +645,11 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + #define E_STEP_WRITE(E,V) do{ E0_STEP_WRITE(V); E1_STEP_WRITE(V); }while(0) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE( INVERT_E0_DIR); E1_DIR_WRITE( INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #elif E_STEPPERS #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) @@ -1013,6 +1018,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset // #if ENABLED(MIXING_EXTRUDER) + /** * Mixing steppers keep all their enable (and direction) states synchronized */ @@ -1020,6 +1026,12 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define _CALL_DIS_E(N) DISABLE_STEPPER_E##N () ; #define ENABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_ENA_E) } #define DISABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_DIS_E) } + +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + + #define ENABLE_AXIS_E0() do{ ENABLE_STEPPER_E0(); ENABLE_STEPPER_E1(); }while(0) + #define DISABLE_AXIS_E0() do{ DISABLE_STEPPER_E0(); DISABLE_STEPPER_E1(); }while(0) + #endif #ifndef ENABLE_AXIS_E0 diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index bd52e30454..ac4459bd02 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -543,9 +543,17 @@ #define _EPIN(p,q) __EPIN(p,q) #define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) -// The X2 axis, if any, should be the next open extruder port -#define X2_E_INDEX E_STEPPERS +// The E0/E1 steppers are always used for Dual E +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #ifndef E1_STEP_PIN + #error "No E1 stepper available for E_DUAL_STEPPER_DRIVERS!" + #endif + #define X2_E_INDEX INCREMENT(E_STEPPERS) +#else + #define X2_E_INDEX E_STEPPERS +#endif +// The X2 axis, if any, should be the next open extruder port #if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) #ifndef X2_STEP_PIN #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index 9931776e00..9eb2157428 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -24,7 +24,7 @@ opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE CALIBRATION_GCODE \ BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ FWRETRACT ARC_SUPPORT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL \ + PSU_CONTROL AUTO_POWER_CONTROL E_DUAL_STEPPER_DRIVERS \ PIDTEMPBED SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER \ PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL \ EXTENSIBLE_UI @@ -38,10 +38,9 @@ restore_configs opt_set MOTHERBOARD BOARD_RADDS NUM_Z_STEPPER_DRIVERS 3 opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS Z_SAFE_HOMING - #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT pins_set ramps/RAMPS X_MAX_PIN -1 pins_set ramps/RAMPS Y_MAX_PIN -1 -exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN" "$3" +exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, E_DUAL_STEPPER_DRIVERS" "$3" # # Test SWITCHING_EXTRUDER diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 95a055d695..b4e489d310 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -16,7 +16,7 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB SERIAL_PORT_3 3 \ NEOPIXEL_TYPE NEO_GRB RGB_LED_R_PIN P2_12 RGB_LED_G_PIN P1_23 RGB_LED_B_PIN P1_22 RGB_LED_W_PIN P1_24 -opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED \ +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED E_DUAL_STEPPER_DRIVERS \ NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_ALWAYS_ON exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3" From a9eff3597dc8afe9de1f4e5037c65de8a503e8e1 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 15 Jun 2021 09:43:50 +1200 Subject: [PATCH 0271/2168] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Prevent=20BFT?= =?UTF-8?q?=20unaligned=20compressed=20data=20corruption=20(#22134)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/binary_stream.h | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 9eb151b27f..2ad7f236a1 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -24,9 +24,11 @@ #include "../inc/MarlinConfig.h" #define BINARY_STREAM_COMPRESSION - #if ENABLED(BINARY_STREAM_COMPRESSION) #include "../libs/heatshrink/heatshrink_decoder.h" + // STM32 (and others?) require a word-aligned buffer for SD card transfers via DMA + static __attribute__((aligned(sizeof(size_t)))) uint8_t decode_buffer[512] = {}; + static heatshrink_decoder hsd; #endif inline bool bs_serial_data_available(const serial_index_t index) { @@ -37,16 +39,6 @@ inline int bs_read_serial(const serial_index_t index) { return SERIAL_IMPL.read(index); } -#if ENABLED(BINARY_STREAM_COMPRESSION) - static heatshrink_decoder hsd; - #if BOTH(ARDUINO_ARCH_STM32F1, SDIO_SUPPORT) - // STM32 requires a word-aligned buffer for SD card transfers via DMA - static __attribute__((aligned(sizeof(size_t)))) uint8_t decode_buffer[512] = {}; - #else - static uint8_t decode_buffer[512] = {}; - #endif -#endif - class SDFileTransferProtocol { private: struct Packet { From 6bdd0fcda183068dcd8fe797a9a835765c3efe9e Mon Sep 17 00:00:00 2001 From: qwewer0 <57561110+qwewer0@users.noreply.github.com> Date: Mon, 14 Jun 2021 23:52:42 +0200 Subject: [PATCH 0272/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Home=20Z=20(and?= =?UTF-8?q?=20maybe=20XY)=20at=20the=20start=20of=20G35=20(#22060)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/G35.cpp | 4 +-- Marlin/src/gcode/calibrate/G34.cpp | 2 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 2 +- Marlin/src/module/motion.cpp | 4 +++ Marlin/src/module/motion.h | 48 +++++++++++++------------ 6 files changed, 34 insertions(+), 28 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index ad2cc67db0..44df6d9273 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -91,8 +91,8 @@ void GcodeSuite::G35() { // Disable duplication mode on homing TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // Home all before this procedure - home_all_axes(); + // Home only Z axis when X and Y is trusted, otherwise all axes, if needed before this procedure + if (!all_axes_trusted()) process_subcommands_now_P(PSTR("G28Z")); bool err_break = false; diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index bcca00dd42..956960866d 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,7 +39,7 @@ void GcodeSuite::G34() { // Home before the alignment procedure - if (!all_axes_trusted()) home_all_axes(); + home_if_needed(); TERN_(HAS_LEVELING, TEMPORARY_BED_LEVELING_STATE(false)); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 1803933d16..6869962028 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -167,7 +167,7 @@ void GcodeSuite::G34() { )); // Home before the alignment procedure - if (!all_axes_trusted()) home_all_axes(); + home_if_needed(); // Move the Z coordinate realm towards the positive - dirty trick current_position.z += z_probe * 0.5f; diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 2daa7d999a..541fa08350 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -99,7 +99,7 @@ void GcodeSuite::M600() { #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // If needed, home before parking for filament change - if (!all_axes_trusted()) home_all_axes(true); + home_if_needed(true); #endif #if HAS_MULTI_EXTRUDER diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index d465a00356..b540c9a938 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -294,6 +294,10 @@ void report_current_position_projected() { #endif +void home_if_needed(const bool keeplev/*=false*/) { + if (!all_axes_trusted()) gcode.home_all_axes(keeplev); +} + /** * Run out the planner buffer and re-sync the current * position from the last-updated stepper positions. diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index d099246f17..c41738a5ab 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -392,33 +392,35 @@ void set_axis_is_at_home(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits); bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits); - FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } - FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } - FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; } - FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } - FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } - FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = linear_bits; } + inline void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } + inline void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } + inline void set_all_unhomed() { axis_homed = axis_trusted = 0; } + inline void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } + inline void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } + inline void set_all_homed() { axis_homed = axis_trusted = linear_bits; } #else constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted - FORCE_INLINE void homeaxis(const AxisEnum axis) {} - FORCE_INLINE void set_axis_never_homed(const AxisEnum) {} - FORCE_INLINE linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } - FORCE_INLINE bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } - FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) {} - FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) {} - FORCE_INLINE void set_all_unhomed() {} - FORCE_INLINE void set_axis_homed(const AxisEnum axis) {} - FORCE_INLINE void set_axis_trusted(const AxisEnum axis) {} - FORCE_INLINE void set_all_homed() {} + inline void homeaxis(const AxisEnum axis) {} + inline void set_axis_never_homed(const AxisEnum) {} + inline linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } + inline bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } + inline void set_axis_unhomed(const AxisEnum axis) {} + inline void set_axis_untrusted(const AxisEnum axis) {} + inline void set_all_unhomed() {} + inline void set_axis_homed(const AxisEnum axis) {} + inline void set_axis_trusted(const AxisEnum axis) {} + inline void set_all_homed() {} #endif -FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } -FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } -FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } -FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } -FORCE_INLINE bool homing_needed() { return !all_axes_homed(); } -FORCE_INLINE bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } +inline bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } +inline bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } +inline bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } +inline bool no_axes_homed() { return !axis_homed; } +inline bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } +inline bool homing_needed() { return !all_axes_homed(); } +inline bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } + +void home_if_needed(const bool keeplev=false); #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) From 6b3dc80b551e2a46776f157060e92cc7727d3bc9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 14 Jun 2021 18:44:27 -0500 Subject: [PATCH 0273/2168] =?UTF-8?q?=F0=9F=90=9B=20Prevent=20stepper=20sl?= =?UTF-8?q?eep=20during=20long=20UBL=20idle=20(#22137)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 15 +++++++-------- Marlin/src/MarlinCore.h | 4 ++-- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- 3 files changed, 10 insertions(+), 11 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 78c97cf3a3..404f36c79f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -421,19 +421,18 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ -inline void manage_inactivity(const bool ignore_stepper_queue=false) { +inline void manage_inactivity(const bool no_stepper_sleep=false) { queue.get_available_commands(); const millis_t ms = millis(); - // Prevent steppers timing-out in the middle of M600 - // unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled - const bool parked_or_ignoring = ignore_stepper_queue + // Prevent steppers timing-out + const bool do_reset_timeout = no_stepper_sleep || TERN0(PAUSE_PARK_NO_STEPPER_TIMEOUT, did_pause_print); // Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout - if (parked_or_ignoring) gcode.reset_stepper_timeout(ms); + if (do_reset_timeout) gcode.reset_stepper_timeout(ms); if (gcode.stepper_max_timed_out(ms)) { SERIAL_ERROR_MSG(STR_KILL_INACTIVE_TIME, parser.command_ptr); @@ -449,7 +448,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { // activity timeout and the M85 max 'kill' timeout if (planner.has_blocks_queued()) gcode.reset_stepper_timeout(ms); - else if (!parked_or_ignoring && gcode.stepper_inactive_timeout()) { + else if (!do_reset_timeout && gcode.stepper_inactive_timeout()) { if (!already_shutdown_steppers) { already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this @@ -732,14 +731,14 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { * - Update the Průša MMU2 * - Handle Joystick jogging */ -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { +void idle(bool no_stepper_sleep/*=false*/) { #if ENABLED(MARLIN_DEV_MODE) static uint16_t idle_depth = 0; if (++idle_depth > 5) SERIAL_ECHOLNPAIR("idle() call depth: ", idle_depth); #endif // Core Marlin activities - manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep)); + manage_inactivity(no_stepper_sleep); // Manage Heaters (and Watchdog) thermalManager.manage_heater(); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index ce1b106bfa..01a1be4d59 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -34,8 +34,8 @@ void stop(); // Pass true to keep steppers from timing out -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); -inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } +void idle(bool no_stepper_sleep=false); +inline void idle_no_sleep() { idle(true); } #if ENABLED(G38_PROBE_TARGET) extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 11c05f6054..e144390c8d 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1025,7 +1025,7 @@ void set_message_with_feedback(PGM_P const msg_P) { SET_SOFT_ENDSTOP_LOOSE(true); do { - idle(); + idle_no_sleep(); new_z = ui.ubl_mesh_value(); TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited SERIAL_FLUSH(); // Prevent host M105 buffer overrun. From d436c93f371336df31287be4fefe7b87876bcdb8 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 15 Jun 2021 11:45:54 +1200 Subject: [PATCH 0274/2168] =?UTF-8?q?=E2=9C=A8=20Redundant=20Part=20Coolin?= =?UTF-8?q?g=20Fan=20(#21888)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 5 +++ Marlin/src/gcode/temp/M106_M107.cpp | 52 +++++++++++++----------- Marlin/src/inc/SanityCheck.h | 8 ++++ Marlin/src/lcd/menu/menu_temperature.cpp | 24 +++++++---- Marlin/src/module/temperature.cpp | 3 ++ buildroot/tests/mega2560 | 3 +- 6 files changed, 61 insertions(+), 34 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b56ebbb538..7b642cc355 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -532,6 +532,11 @@ //#define USE_OCR2A_AS_TOP #endif +/** + * Use one of the PWM fans as a redundant part-cooling fan + */ +//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. + // @section extruder /** diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index dcb0d34ffe..3f85c53d78 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -60,39 +60,40 @@ */ void GcodeSuite::M106() { const uint8_t pfan = parser.byteval('P', _ALT_P); + if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif - if (pfan < _CNT_P) { + #if ENABLED(EXTRA_FAN_SPEED) + const uint16_t t = parser.intval('T'); + if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); + #endif - #if ENABLED(EXTRA_FAN_SPEED) - const uint16_t t = parser.intval('T'); - if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); - #endif + const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; - const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; + uint16_t speed = dspeed; - uint16_t speed = dspeed; + // Accept 'I' if temperature presets are defined + #if PREHEAT_COUNT + const bool got_preset = parser.seenval('I'); + if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; + #else + constexpr bool got_preset = false; + #endif - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - const bool got_preset = parser.seenval('I'); - if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; - #else - constexpr bool got_preset = false; - #endif + if (!got_preset && parser.seenval('S')) + speed = parser.value_ushort(); - if (!got_preset && parser.seenval('S')) - speed = parser.value_ushort(); + TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat - TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat + // Set speed, with constraint + thermalManager.set_fan_speed(pfan, speed); - // Set speed, with constraint - thermalManager.set_fan_speed(pfan, speed); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); - TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); - - if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating - thermalManager.set_fan_speed(1 - pfan, speed); - } + if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating + thermalManager.set_fan_speed(1 - pfan, speed); } /** @@ -101,6 +102,9 @@ void GcodeSuite::M106() { void GcodeSuite::M107() { const uint8_t pfan = parser.byteval('P', _ALT_P); if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif thermalManager.set_fan_speed(pfan, 0); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ae3d639957..7a178db3aa 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1890,6 +1890,14 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif +#ifdef REDUNDANT_PART_COOLING_FAN + #if FAN_COUNT < 2 + #error "REDUNDANT_PART_COOLING_FAN requires a board with at least two PWM fans." + #else + static_assert(WITHIN(REDUNDANT_PART_COOLING_FAN, 1, FAN_COUNT - 1), "REDUNDANT_PART_COOLING_FAN must be between 1 and " STRINGIFY(DECREMENT(FAN_COUNT)) "."); + #endif +#endif + /** * Case Light requirements */ diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 33a3d2f445..96e6ee5f8e 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -57,8 +57,14 @@ void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t i if (indb >= 0 && ui.material_preset[indb].bed_temp > 0) setTargetBed(ui.material_preset[indb].bed_temp); #endif #if HAS_FAN - if (indh >= 0) - set_fan_speed(active_extruder < (FAN_COUNT) ? active_extruder : 0, ui.material_preset[indh].fan_speed); + if (indh >= 0) { + const uint8_t fan_index = active_extruder < (FAN_COUNT) ? active_extruder : 0; + if (true + #if REDUNDANT_PART_COOLING_FAN + && fan_index != REDUNDANT_PART_COOLING_FAN + #endif + ) set_fan_speed(fan_index, ui.material_preset[indh].fan_speed); + } #endif ui.return_to_status(); } @@ -215,37 +221,37 @@ void menu_temperature() { #if HAS_FAN0 _FAN_EDIT_ITEMS(0,FIRST_FAN_SPEED); #endif - #if HAS_FAN1 + #if HAS_FAN1 && REDUNDANT_PART_COOLING_FAN != 1 FAN_EDIT_ITEMS(1); #elif SNFAN(1) singlenozzle_item(1); #endif - #if HAS_FAN2 + #if HAS_FAN2 && REDUNDANT_PART_COOLING_FAN != 2 FAN_EDIT_ITEMS(2); #elif SNFAN(2) singlenozzle_item(2); #endif - #if HAS_FAN3 + #if HAS_FAN3 && REDUNDANT_PART_COOLING_FAN != 3 FAN_EDIT_ITEMS(3); #elif SNFAN(3) singlenozzle_item(3); #endif - #if HAS_FAN4 + #if HAS_FAN4 && REDUNDANT_PART_COOLING_FAN != 4 FAN_EDIT_ITEMS(4); #elif SNFAN(4) singlenozzle_item(4); #endif - #if HAS_FAN5 + #if HAS_FAN5 && REDUNDANT_PART_COOLING_FAN != 5 FAN_EDIT_ITEMS(5); #elif SNFAN(5) singlenozzle_item(5); #endif - #if HAS_FAN6 + #if HAS_FAN6 && REDUNDANT_PART_COOLING_FAN != 6 FAN_EDIT_ITEMS(6); #elif SNFAN(6) singlenozzle_item(6); #endif - #if HAS_FAN7 + #if HAS_FAN7 && REDUNDANT_PART_COOLING_FAN != 7 FAN_EDIT_ITEMS(7); #elif SNFAN(7) singlenozzle_item(7); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e7d4ece721..9274d0631e 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -333,6 +333,9 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, if (fan >= FAN_COUNT) return; fan_speed[fan] = speed; + #if REDUNDANT_PART_COOLING_FAN + if (fan == 0) fan_speed[REDUNDANT_PART_COOLING_FAN] = speed; + #endif TERN_(REPORT_FAN_CHANGE, report_fan_speed(fan)); } diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 3ddb68fe88..0932388969 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -68,7 +68,8 @@ exec_test $1 $2 "Multiple runout sensors (x5) | Distinct runout states" "$3" # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ - NUM_RUNOUT_SENSORS E_STEPPERS FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 + NUM_RUNOUT_SENSORS E_STEPPERS REDUNDANT_PART_COOLING_FAN 1 \ + FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE From 8e06e9ca40ffad4a37b7f4a43dec36b63868b92f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 15 Jun 2021 00:59:53 +0000 Subject: [PATCH 0275/2168] [cron] Bump distribution date (2021-06-15) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cf6586f3f0..597ec2d553 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 "2021-06-14" + #define STRING_DISTRIBUTION_DATE "2021-06-15" #endif /** From 9d1e370534ef96f39ff3be4695021859e6b8548d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 16 Jun 2021 00:57:35 +0000 Subject: [PATCH 0276/2168] [cron] Bump distribution date (2021-06-16) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 597ec2d553..5bfedbd0bb 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 "2021-06-15" + #define STRING_DISTRIBUTION_DATE "2021-06-16" #endif /** From 43771842d65139223550df228cdc34105c7918b0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 17 Jun 2021 00:55:23 +0000 Subject: [PATCH 0277/2168] [cron] Bump distribution date (2021-06-17) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5bfedbd0bb..f9448486e7 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 "2021-06-16" + #define STRING_DISTRIBUTION_DATE "2021-06-17" #endif /** From d4943a607e24e5c379c5fcb3f763171f95cb30ee Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Thu, 17 Jun 2021 02:49:42 -0300 Subject: [PATCH 0278/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20Robin=20E3?= =?UTF-8?q?=20build=20(#22149)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index dca640cd50..3f09a45c7b 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -135,7 +135,7 @@ board_build.offset = 0x5000 board_build.encrypt = Robin_e3.bin board_upload.offset_address = 0x08005000 debug_tool = stlink -extra_scripts = ${env:STM32F103RC.extra_scripts} +extra_scripts = ${common_STM32F103RC.extra_scripts} buildroot/share/PlatformIO/scripts/mks_encrypt.py # From dd9f91f0f0e069aa2b86cd67205fb85c1b160a32 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Thu, 17 Jun 2021 02:58:48 -0300 Subject: [PATCH 0279/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20env=20validation?= =?UTF-8?q?=20for=201280/2560=20boards=20(#22150)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/pins/mega/env_validate.h | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/Marlin/src/pins/mega/env_validate.h b/Marlin/src/pins/mega/env_validate.h index fe4a39a612..97c52d4e5e 100644 --- a/Marlin/src/pins/mega/env_validate.h +++ b/Marlin/src/pins/mega/env_validate.h @@ -21,10 +21,12 @@ */ #pragma once -#if ENABLED(ALLOW_MEGA1280) && NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" -#elif NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" +#if NOT_TARGET(__AVR_ATmega2560__) + #if DISABLED(ALLOW_MEGA1280) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" + #elif NOT_TARGET(__AVR_ATmega1280__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" + #endif #endif #undef ALLOW_MEGA1280 From d0df8bc3cbd39d23cb52ffcd3b26629a185c18a6 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Wed, 16 Jun 2021 23:15:16 -0700 Subject: [PATCH 0280/2168] =?UTF-8?q?=F0=9F=92=A1=20Add=20G28=20L=20descri?= =?UTF-8?q?ption=20(#22144)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G28.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 61e7ab4233..69cdd02d16 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -195,9 +195,9 @@ * None Home to all axes with no parameters. * With QUICK_HOME enabled XY will home together, then Z. * - * O Home only if position is unknown - * - * Rn Raise by n mm/inches before homing + * L Force leveling state ON (if possible) or OFF after homing (Requires RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28) + * O Home only if the position is not known and trusted + * R Raise by n mm/inches before homing * * Cartesian/SCARA parameters * @@ -229,7 +229,7 @@ void GcodeSuite::G28() { #endif // Home (O)nly if position is unknown - if (!axes_should_home() && parser.boolval('O')) { + if (!axes_should_home() && parser.seen_test('O')) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip"); return; } From aeb21a3516e4adf49c18df5344c79e49447c26a3 Mon Sep 17 00:00:00 2001 From: Ari-SSO <85907917+Ari-SSO@users.noreply.github.com> Date: Thu, 17 Jun 2021 21:34:40 -0300 Subject: [PATCH 0281/2168] =?UTF-8?q?=F0=9F=9A=B8=20Include=20'H'=20value?= =?UTF-8?q?=20in=20M412=20report=20(#22138)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/feature/runout/M412.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 540a160623..9a06357132 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -54,10 +54,15 @@ void GcodeSuite::M412() { else { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Filament runout "); - serialprintln_onoff(runout.enabled); + serialprint_onoff(runout.enabled); #if HAS_FILAMENT_RUNOUT_DISTANCE - SERIAL_ECHOLNPAIR("Filament runout distance (mm): ", runout.runout_distance()); + SERIAL_ECHOPAIR(" ; Distance ", runout.runout_distance(), "mm"); #endif + #if ENABLED(HOST_ACTION_COMMANDS) + SERIAL_ECHOPGM(" ; Host handling "); + serialprint_onoff(runout.host_handling); + #endif + SERIAL_EOL(); } } From a2be93c54189c7a513f1ef7f42e7033de6e9a6e9 Mon Sep 17 00:00:00 2001 From: gjdodd <31553294+gjdodd@users.noreply.github.com> Date: Fri, 18 Jun 2021 01:37:27 +0100 Subject: [PATCH 0282/2168] =?UTF-8?q?=F0=9F=A9=B9=20Extruders=200=20patch?= =?UTF-8?q?=20for=20PWM=20Motor=20Current=20(#22163)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/digipot/M907-M910.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index ee9801eda9..118ad21564 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -67,8 +67,10 @@ void GcodeSuite::M907() { LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); // Additional extruders use B,C,D for channels 4,5,6. // TODO: Change these parameters because 'E' is used. B? - for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) - if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #if HAS_EXTRUDERS + for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) + if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #endif #endif #if ENABLED(HAS_MOTOR_CURRENT_DAC) From 34c7b6ddae9faddccafe08fd55a7bf8c2f3d1942 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 17 Jun 2021 17:39:48 -0700 Subject: [PATCH 0283/2168] =?UTF-8?q?=F0=9F=90=9B=20TFT=20encoder=20pin=20?= =?UTF-8?q?for=20BTT=20GTR=20(#22162)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 850b23db66..4438ed63ac 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -411,6 +411,7 @@ #define TOUCH_MOSI_PIN EXP1_08_PIN #define TOUCH_SCK_PIN EXP1_06_PIN #define TOUCH_CS_PIN EXP1_07_PIN + #define BTN_ENC EXP1_09_PIN #define BTN_EN1 EXP2_08_PIN #define BTN_EN2 EXP2_06_PIN From ab7e622e4abbde174e4b03dfe9ec8cb824b5afce Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 18 Jun 2021 01:08:37 +0000 Subject: [PATCH 0284/2168] [cron] Bump distribution date (2021-06-18) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f9448486e7..da6f10991a 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 "2021-06-17" + #define STRING_DISTRIBUTION_DATE "2021-06-18" #endif /** From 135801d9a614a2dd1ba7bea60bc8dcad523b9d59 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Thu, 17 Jun 2021 22:46:59 -0500 Subject: [PATCH 0285/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Air=20Assist=20(?= =?UTF-8?q?#22159)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/control/M7-M9.cpp | 60 +++++++++++++----------------- Marlin/src/gcode/gcode.cpp | 27 ++++++++------ Marlin/src/gcode/gcode.h | 25 +++++++------ ini/features.ini | 2 +- 4 files changed, 55 insertions(+), 59 deletions(-) diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index ae112fc372..ccde4f552c 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -20,9 +20,9 @@ * */ -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" -#if ENABLED(COOLANT_CONTROL) +#if ANY(COOLANT_MIST, COOLANT_FLOOD, AIR_ASSIST) #include "../gcode.h" #include "../../module/planner.h" @@ -37,51 +37,41 @@ } #endif -#if ENABLED(COOLANT_FLOOD) +#if EITHER(COOLANT_FLOOD, AIR_ASSIST) + + #if ENABLED(AIR_ASSIST) + #include "../../feature/spindle_laser.h" + #endif + /** - * M8: Flood Coolant On + * M8: Flood Coolant / Air Assist ON */ void GcodeSuite::M8() { - planner.synchronize(); // Wait for move to arrive - WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + planner.synchronize(); // Wait for move to arrive + #if ENABLED(COOLANT_FLOOD) + WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_enable(); // Turn on Air Assist + #endif } + #endif /** - * M9: Coolant OFF + * M9: Coolant / Air Assist OFF */ void GcodeSuite::M9() { - planner.synchronize(); // Wait for move to arrive + planner.synchronize(); // Wait for move to arrive #if ENABLED(COOLANT_MIST) - WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant + WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant #endif #if ENABLED(COOLANT_FLOOD) - WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_disable(); // Turn off Air Assist #endif } -#endif // COOLANT_CONTROL - -#if ENABLED(AIR_ASSIST) - -#include "../gcode.h" -#include "../../module/planner.h" -#include "../../feature/spindle_laser.h" - -/** - * M8: Air Assist On - */ -void GcodeSuite::M8() { - planner.synchronize(); - cutter.air_assist_enable(); // Turn on Air Assist pin -} - -/** - * M9: Air Assist Off - */ -void GcodeSuite::M9() { - planner.synchronize(); - cutter.air_assist_disable(); // Turn off Air Assist pin -} - -#endif // AIR_ASSIST +#endif // COOLANT_MIST | COOLANT_FLOOD | AIR_ASSIST diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index eb650851f8..ac3b5010b9 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -441,20 +441,23 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 3: M3_M4(false); break; // M3: Turn ON Laser | Spindle (clockwise), set Power | Speed case 4: M3_M4(true ); break; // M4: Turn ON Laser | Spindle (counter-clockwise), set Power | Speed case 5: M5(); break; // M5: Turn OFF Laser | Spindle - #if ENABLED(AIR_EVACUATION) - case 10: M10(); break; // M10: Vacuum or Blower motor ON - case 11: M11(); break; // M11: Vacuum or Blower motor OFF - #endif #endif - #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - case 7: M7(); break; // M7: Mist coolant ON - #endif - #if ENABLED(COOLANT_FLOOD) - case 8: M8(); break; // M8: Flood coolant ON - #endif - case 9: M9(); break; // M9: Coolant OFF + #if ENABLED(COOLANT_MIST) + case 7: M7(); break; // M7: Coolant Mist ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + case 8: M8(); break; // M8: Air Assist / Coolant Flood ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + case 9: M9(); break; // M9: Air Assist / Coolant OFF + #endif + + #if ENABLED(AIR_EVACUATION) + case 10: M10(); break; // M10: Vacuum or Blower motor ON + case 11: M11(); break; // M11: Vacuum or Blower motor OFF #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 89605ee25b..752a3da9dc 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -564,22 +564,25 @@ private: #if HAS_CUTTER static void M3_M4(const bool is_M4); static void M5(); - #if ENABLED(AIR_EVACUATION) - static void M10(); - static void M11(); - #endif #endif - #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - static void M7(); - #endif - #if ENABLED(COOLANT_FLOOD) - static void M8(); - #endif + #if ENABLED(COOLANT_MIST) + static void M7(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + static void M8(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) static void M9(); #endif + #if ENABLED(AIR_EVACUATION) + static void M10(); + static void M11(); + #endif + #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) static void M12(); #endif diff --git a/ini/features.ini b/ini/features.ini index 15f6c2a138..a1e9688447 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -166,7 +166,7 @@ HAS_USER_THERMISTORS = src_filter=+ SD_ABORT_ON_ENDSTOP_HIT = src_filter=+ BAUD_RATE_GCODE = src_filter=+ HAS_SMART_EFF_MOD = src_filter=+ -COOLANT_CONTROL = src_filter=+ +COOLANT_CONTROL|AIR_ASSIST = src_filter=+ AIR_EVACUATION = src_filter=+ HAS_SOFTWARE_ENDSTOPS = src_filter=+ HAS_DUPLICATION_MODE = src_filter=+ From 55feb8ac8dda15e58ea4e2d2f0d06560b40d8f93 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 18 Jun 2021 13:12:55 -0500 Subject: [PATCH 0286/2168] =?UTF-8?q?=F0=9F=90=9B=20Define=20'HEAD'=20axes?= =?UTF-8?q?=20for=20Markforged?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22167 --- Marlin/src/core/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index f8b5cef77b..833167a7a1 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -83,7 +83,7 @@ enum AxisEnum : uint8_t { #undef _EN_ITEM // Core also keeps toolhead directions - #if IS_CORE + #if EITHER(IS_CORE, MARKFORGED_XY) , X_HEAD, Y_HEAD, Z_HEAD #endif From ad1ad93ea942f20bab169524ef6f88b0fc1a681a Mon Sep 17 00:00:00 2001 From: ellensp Date: Sat, 19 Jun 2021 07:59:44 +1200 Subject: [PATCH 0287/2168] =?UTF-8?q?=F0=9F=9A=B8=20Manual=20Move=20coordi?= =?UTF-8?q?nates=20>=3D=201000=20(#22165)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_en.h | 2 ++ Marlin/src/lcd/menu/menu_motion.cpp | 7 +++++-- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 9a3f9b6e9f..5a0562de53 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -281,9 +281,11 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); + PROGMEM Language_Str MSG_MOVE_10IN = _UxGT("Move 1.0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 076ece33b0..16f40af241 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -28,6 +28,8 @@ #if HAS_LCD_MENU +#define LARGE_BED_TEST ((X_BED_SIZE) >= 1000 || (Y_BED_SIZE) >= 1000) + #include "menu_item.h" #include "menu_addon.h" @@ -85,7 +87,7 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { MenuEditItemBase::draw_edit_screen(name, ftostr63(imp_pos)); } else - MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr63(pos)); + MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? (LARGE_BED_TEST ? ftostr51sign(pos) : ftostr41sign(pos)) : ftostr63(pos)); } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } @@ -165,11 +167,13 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int BACK_ITEM(MSG_MOVE_AXIS); if (parser.using_inch_units()) { + if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_10IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); } else { + if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_100MM, []{ _goto_manual_move(100); }); SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); @@ -180,7 +184,6 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int PGM_P const label = GET_TEXT(MSG_MOVE_N_MM); char tmp[strlen_P(label) + 10 + 1], numstr[10]; sprintf_P(tmp, label, dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); - #if DISABLED(HAS_GRAPHICAL_TFT) SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(FINE_MANUAL_MOVE)); }); MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); From 758d495d08327dd28e8e6b0880f77da0b140def2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 19 Jun 2021 00:57:37 +0000 Subject: [PATCH 0288/2168] [cron] Bump distribution date (2021-06-19) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index da6f10991a..0b1ea59c35 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 "2021-06-18" + #define STRING_DISTRIBUTION_DATE "2021-06-19" #endif /** From f944ec3ac6d0f4c4b394e11fe1af7416d52d6b68 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sat, 19 Jun 2021 11:44:28 -0700 Subject: [PATCH 0289/2168] =?UTF-8?q?=F0=9F=90=9B=20Redundant=20Temp=20Sen?= =?UTF-8?q?sor=20followup=20(#22173)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 159 +++++++++++++++-------------- Marlin/src/module/temperature.cpp | 26 +++-- 2 files changed, 103 insertions(+), 82 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index a5a1070b03..eb215c34eb 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -526,83 +526,90 @@ #undef ANY_TEMP_SENSOR_IS // Usurp a sensor to do redundant readings -#if TEMP_SENSOR_REDUNDANT && !PIN_EXISTS(TEMP_REDUNDANT) - #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 - #if !PIN_EXISTS(TEMP_COOLER) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 - #if !PIN_EXISTS(TEMP_PROBE) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 - #if !PIN_EXISTS(TEMP_CHAMBER) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 - #if !PIN_EXISTS(TEMP_BED) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_BED_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 - #if !PIN_EXISTS(TEMP_0) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_0_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 - #if !PIN_EXISTS(TEMP_1) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_1_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 - #if !PIN_EXISTS(TEMP_2) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_2_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 - #if !PIN_EXISTS(TEMP_3) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_3_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 - #if !PIN_EXISTS(TEMP_4) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_4_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 - #if !PIN_EXISTS(TEMP_5) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_5_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 - #if !PIN_EXISTS(TEMP_6) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_6_PIN - #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 - #if !PIN_EXISTS(TEMP_7) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." - #else - #define TEMP_REDUNDANT_PIN TEMP_7_PIN - #endif +#if TEMP_SENSOR_REDUNDANT + #ifndef TEMP_SENSOR_REDUNDANT_SOURCE + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 #endif - - #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF - #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 + #ifndef TEMP_SENSOR_REDUNDANT_TARGET + #define TEMP_SENSOR_REDUNDANT_TARGET 0 + #endif + #if !PIN_EXISTS(TEMP_REDUNDANT) + #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 + #endif + #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 + #if !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 + #if !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_BED_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #if !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_0_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #if !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_1_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 + #if !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_2_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 + #if !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_3_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 + #if !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_4_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 + #if !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_5_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 + #if !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_6_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 + #if !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_7_PIN + #endif + #endif #endif #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9274d0631e..9f32ce933b 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2090,16 +2090,30 @@ void Temperature::init() { #endif #if HAS_MAX31865_TEMP - TERN_(TEMP_SENSOR_IS_MAX(0, MAX31865), max31865_0.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - TERN_(TEMP_SENSOR_IS_MAX(1, MAX31865), max31865_1.begin(MAX31865_2WIRE)); + #if TEMP_SENSOR_IS_MAX(0, MAX31865) + max31865_0.begin(MAX31865_2WIRE); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX31865) + max31865_1.begin(MAX31865_2WIRE); + #endif #endif + #if HAS_MAX31855_TEMP - TERN_(TEMP_SENSOR_IS_MAX(0, MAX31855), max31855_0.begin()); - TERN_(TEMP_SENSOR_IS_MAX(1, MAX31855), max31855_1.begin()); + #if TEMP_SENSOR_IS_MAX(0, MAX31855) + max31855_0.begin(MAX31855); + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX31855) + max31855_1.begin(MAX31855); + #endif #endif + #if HAS_MAX6675_TEMP - TERN_(TEMP_SENSOR_IS_MAX(0, MAX6675), max6675_0.begin()); - TERN_(TEMP_SENSOR_IS_MAX(1, MAX6675), max6675_1.begin()); + #if TEMP_SENSOR_IS_MAX(0, MAX6675) + max6675_0.begin(MAX6675); + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX6675) + max6675_1.begin(MAX6675); + #endif #endif #if MB(RUMBA) From 5ce6d8aa1f81178fc25a12abff63ca1a6c88e42c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 19 Jun 2021 14:09:09 -0500 Subject: [PATCH 0290/2168] Cosmetic changes for G28 --- Marlin/src/feature/tmc_util.h | 4 ++-- Marlin/src/gcode/calibrate/G28.cpp | 30 ++++++++++++++++-------------- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 3a856b3af8..741b840ec7 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -361,10 +361,10 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); extern millis_t sg_guard_period; constexpr uint16_t default_sg_guard_duration = 400; - struct slow_homing_t { + struct motion_state_t { xy_ulong_t acceleration; #if ENABLED(HAS_CLASSIC_JERK) - xy_float_t jerk_xy; + xy_float_t jerk_state; #endif }; #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 69cdd02d16..7cd1f65fbf 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -164,24 +164,24 @@ #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing_t begin_slow_homing() { - slow_homing_t slow_homing{0}; - slow_homing.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], + motion_state_t begin_slow_homing() { + motion_state_t motion_state{0}; + motion_state.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); planner.settings.max_acceleration_mm_per_s2[X_AXIS] = 100; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; #if HAS_CLASSIC_JERK - slow_homing.jerk_xy = planner.max_jerk; + motion_state.jerk_state = planner.max_jerk; planner.max_jerk.set(0, 0); #endif planner.reset_acceleration_rates(); - return slow_homing; + return motion_state; } - void end_slow_homing(const slow_homing_t &slow_homing) { - planner.settings.max_acceleration_mm_per_s2[X_AXIS] = slow_homing.acceleration.x; - planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = slow_homing.acceleration.y; - TERN_(HAS_CLASSIC_JERK, planner.max_jerk = slow_homing.jerk_xy); + void end_slow_homing(const motion_state_t &motion_state) { + planner.settings.max_acceleration_mm_per_s2[X_AXIS] = motion_state.acceleration.x; + planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y; + TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); planner.reset_acceleration_rates(); } @@ -289,7 +289,9 @@ void GcodeSuite::G28() { #endif #endif - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing_t slow_homing = begin_slow_homing()); + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + motion_state_t saved_motion_state = begin_slow_homing(); + #endif // Always home with tool 0 active #if HAS_MULTI_HOTEND @@ -315,7 +317,7 @@ void GcodeSuite::G28() { home_delta(); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); #elif ENABLED(AXEL_TPARA) @@ -401,7 +403,7 @@ void GcodeSuite::G28() { if (DISABLED(HOME_Y_BEFORE_X) && doY) homeaxis(Y_AXIS); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); // Home Z last if homing towards the bed #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) @@ -440,7 +442,7 @@ void GcodeSuite::G28() { if (idex_is_duplicating()) { - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing = begin_slow_homing()); + TERN_(IMPROVE_HOMING_RELIABILITY, saved_motion_state = begin_slow_homing()); // Always home the 2nd (right) extruder first active_extruder = 1; @@ -459,7 +461,7 @@ void GcodeSuite::G28() { dual_x_carriage_mode = IDEX_saved_mode; set_duplication_enabled(IDEX_saved_duplication_state); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); } #endif // DUAL_X_CARRIAGE From 84e50f5fdac4cf8835b37155e08cd4ce9b36efeb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 20 Jun 2021 00:59:38 +0000 Subject: [PATCH 0291/2168] [cron] Bump distribution date (2021-06-20) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0b1ea59c35..e7309ae4e9 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 "2021-06-19" + #define STRING_DISTRIBUTION_DATE "2021-06-20" #endif /** From a006752fc2fde7a1f13a57eea190e2959fa19094 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 20 Jun 2021 01:19:09 -0500 Subject: [PATCH 0292/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LCD=20define=20t?= =?UTF-8?q?ypos?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h | 2 +- Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h | 2 +- Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 2 +- Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h index 910f5f7791..79aee9a576 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h @@ -51,7 +51,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h index d18989a48b..0c3a6aa352 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h @@ -51,7 +51,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index cd86ec5105..5c9ff02bfe 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -238,7 +238,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h index c1890c7c28..7885621d0b 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -46,7 +46,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) From 4d386fdeb5ee24d72fcedcd976b5b3c652c67f52 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 21 Jun 2021 01:01:00 +0000 Subject: [PATCH 0293/2168] [cron] Bump distribution date (2021-06-21) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e7309ae4e9..3bf472f7c0 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 "2021-06-20" + #define STRING_DISTRIBUTION_DATE "2021-06-21" #endif /** From 071386271923146349e4841d564778fd98cf7c5d Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Mon, 21 Jun 2021 05:45:26 +0200 Subject: [PATCH 0294/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Italian=20lan?= =?UTF-8?q?guage=20(#22182)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_en.h | 2 +- Marlin/src/lcd/language/language_it.h | 73 +++++++++++++++++++++------ Marlin/src/lcd/menu/menu_motion.cpp | 2 +- 3 files changed, 59 insertions(+), 18 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 5a0562de53..c60c357ecc 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -285,7 +285,7 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); - PROGMEM Language_Str MSG_MOVE_10IN = _UxGT("Move 1.0in"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Move 1.0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index d359354932..9e9cdd2acc 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -67,9 +67,12 @@ namespace Language_it { PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu di debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home asse X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home asse Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home asse Z"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterazione G34: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); @@ -80,6 +83,12 @@ namespace Language_it { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Livel. terminato!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Imp. offset home"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Offset home X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Imposta Origine"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Tramming assistito"); @@ -112,10 +121,13 @@ namespace Language_it { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potenza laser"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potenza mandrino"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Alterna Laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Alterna soffiatore"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Alterna aria supp."); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("ms impulso di test"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Spara impulso"); PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Err.flusso refrig."); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Alterna mandrino"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Alterna vuoto"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Mandrino in avanti"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); @@ -158,6 +170,7 @@ namespace Language_it { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Misura"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Rimuovi e mis.piatto"); @@ -258,6 +271,9 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Muovi X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Muovi Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Muovi Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusore"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusore *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); @@ -265,9 +281,11 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001in"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01in"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1in"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Muovi di 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001\""); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01\""); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Muovi di 1\""); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocità"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Piatto Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ugello"); @@ -312,12 +330,18 @@ namespace Language_it { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocità"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -326,6 +350,9 @@ namespace Language_it { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); @@ -333,11 +360,14 @@ namespace Language_it { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passi/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("passi/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("passi/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("passi/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Epassi/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*passi/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passi/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passi/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); @@ -469,6 +499,9 @@ namespace Language_it { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Finecorsa annullati"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 caratteri @@ -545,10 +578,13 @@ namespace Language_it { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alimentatore"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver I %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver J %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver K %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); @@ -681,10 +717,15 @@ namespace Language_it { PROGMEM Language_Str MSG_SOUND = _UxGT("Suoni"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Alto destra"); PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver invertito"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("Scheda SD"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("Disco USB"); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 16f40af241..ea85a55660 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -167,7 +167,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int BACK_ITEM(MSG_MOVE_AXIS); if (parser.using_inch_units()) { - if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_10IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); + if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_1IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); From fb97e43ca3c583a191376817d18365e33de53508 Mon Sep 17 00:00:00 2001 From: Serhiy-K <52166448+Serhiy-K@users.noreply.github.com> Date: Mon, 21 Jun 2021 06:48:06 +0300 Subject: [PATCH 0295/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Ukrainian=20l?= =?UTF-8?q?anguage=20(#22183)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_uk.h | 174 ++++++++++++++++++-------- 1 file changed, 125 insertions(+), 49 deletions(-) diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index be0e420a42..27dfc1fcda 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -71,6 +71,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Паркування X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ітерація: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); @@ -82,11 +85,29 @@ namespace Language_uk { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; #else - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщ. дому"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Встановити нуль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Нагрів ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрів ") PREHEAT_1_LABEL " ~"; @@ -106,22 +127,29 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрів свого"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Вимкнути нагрів"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Керування лазером"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужність лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #else PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потуж.лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керув. шпінделем"); #endif PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкнути шпіндель"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінделя"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); #else PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінд."); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп. мс"); #endif + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); @@ -134,11 +162,14 @@ namespace Language_uk { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Вирівняти кути"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрацювання зонду"); // not sure about this one - #else PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрацюв. зонду"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); + #else + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрац.зонду"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирівн"); #endif - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирівнювання столу"); // Too long? + PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хороші точки: "); + PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Остання Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Наступний кут"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); @@ -181,24 +212,25 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введ. сітки"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розм. шайбу і вимір."); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + #else + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); + #endif PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Рух до наступної"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активувати UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивувати UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Температура столу"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура свого столу"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Температура свого сопла"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); #else - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редаг. сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою"); @@ -206,10 +238,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редагування сітки"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Сітка побудована"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Будувати сітку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Буд. холодну сітку"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Встан.висоту сітки"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Висота"); @@ -219,7 +249,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрів столу"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрів сопла"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ручне грунтування"); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); // ґ is not supported + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Грунтув. виконане"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 скасовано"); PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Вийти з G26"); @@ -240,7 +270,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнювача"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); #else PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); #endif @@ -251,12 +281,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); - #else - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); - #endif - #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); #else + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно найближчу"); #endif PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Збереження сітки"); @@ -300,7 +327,7 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); #else - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустан. світла #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); #endif PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яскравість"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Своє світло"); @@ -315,6 +342,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Рух по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Рух по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Рух по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); @@ -322,6 +352,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Рух 0.1мм"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Рух 1мм"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Рух 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Рух 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Швидкість"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Столу"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; @@ -330,6 +361,14 @@ namespace Language_uk { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); PROGMEM Language_Str MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодження"); + #else + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодж."); + #endif + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Швидк. вент."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); #if LCD_WIDTH > 21 @@ -339,8 +378,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.вент. ~"); #endif - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Дод. швидк. вент."); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холості оберти"); PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Авто-режим"); PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); @@ -369,6 +408,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); @@ -379,6 +421,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Швидк.макс *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк.мін"); @@ -387,6 +432,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Приск.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Приск.втягув."); @@ -397,6 +445,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E кроків/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* кроків/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); @@ -426,7 +477,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметри збережені"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Оновити SD-картку"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Зкинути принтер"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Головний екран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Підготувати"); PROGMEM Language_Str MSG_TUNE = _UxGT("Підлаштування"); @@ -472,8 +523,6 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягування, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втягув.,мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Ретракт V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Стрибок, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Повернення, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Поверн.зміни, мм"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягування"); @@ -556,6 +605,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); @@ -563,7 +615,13 @@ namespace Language_uk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); + #if LCD_WIDTH >= 20 + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); + #else + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); + #endif + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); @@ -573,18 +631,20 @@ namespace Language_uk { PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрівання..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Охолодження..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрів столу..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодження столу..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодження лазеру..."); #else - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охол. столу..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охол. камери..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охол. зонду..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодж. столу..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодж. зонду..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодж. камери..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодж. лазеру..."); #endif + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калібрувати X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калібрувати Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калібрувати Z"); @@ -611,6 +671,11 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування виконано"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Про плату"); @@ -651,6 +716,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Драйвер X, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Драйвер Y, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Драйвер Z, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер I, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер J, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер K, %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); @@ -687,19 +755,19 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); #else - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантаж. в сопло"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); #endif PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Звільнити"); PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Звільнити ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Вивантажити"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("MMU Завантаж. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("MMU Звільнення..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("MMU Вивантаження..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("MMU Все"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("MMU Пруток ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU Перезапуск"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаж. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Викидання прутка..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження..."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Все"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Пруток ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("MMU Видаліть, натисніть"); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MIX = _UxGT("Змішування"); @@ -710,7 +778,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_MIXER = _UxGT("Змішувач"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градієнт"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Змішування переключ."); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); + #else + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); + #endif PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Циклічне змішування"); PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); @@ -721,14 +793,13 @@ namespace Language_uk { PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); #else PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив. В-інструм."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм."); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм"); PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм."); #endif PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Початок В-інструменту"); PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Початок Z:"); PROGMEM Language_Str MSG_END_Z = _UxGT(" Кінець Z:"); @@ -756,12 +827,12 @@ namespace Language_uk { PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Натисніть кнопку", "для продовження", "друку")); @@ -828,6 +899,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижній правий"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калібрування успішне"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Збій калібрування"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Картка"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 From 44c41ce54f2c8f8c89464e570b91dd6bbddce125 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 20 Jun 2021 22:49:57 -0500 Subject: [PATCH 0296/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20compact=20sensit?= =?UTF-8?q?ive=20pins=20array=20(#22184)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 21 ++++++++++++--------- Marlin/src/pins/sensitive_pins.h | 2 +- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 404f36c79f..f77f3b2f0b 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -282,19 +282,22 @@ bool wait_for_heatup = true; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wnarrowing" -#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL - static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; -#else +#ifndef RUNTIME_ONLY_ANALOG_TO_DIGITAL template - constexpr pin_t OnlyPins<-2, D...>::table[sizeof...(D)]; - #define sensitive_pins OnlyPins::table + constexpr pin_t OnlyPins<_SP_END, D...>::table[sizeof...(D)]; #endif bool pin_is_protected(const pin_t pin) { - 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; + #ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; + const size_t pincount = COUNT(sensitive_pins); + #else + static constexpr size_t pincount = OnlyPins::size; + static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; + #endif + LOOP_L_N(i, pincount) { + const pin_t * const pptr = &sensitive_pins[i]; + if (pin == (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(pptr) : (pin_t)pgm_read_byte(pptr))) return true; } return false; } diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 9102bbab7b..7ccb0339b2 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -882,7 +882,7 @@ // Remove -2 from the front, emit the rest, cease propagation template - struct OnlyPins<_SP_END, D...> { static constexpr pin_t table[sizeof...(D)] PROGMEM = { D... }; }; + struct OnlyPins<_SP_END, D...> { static constexpr size_t size = sizeof...(D); static constexpr pin_t table[sizeof...(D)] PROGMEM = { D... }; }; #endif #define SENSITIVE_PINS \ From 6bf6973e9d02caab4dab8190e1191b7675cd8549 Mon Sep 17 00:00:00 2001 From: ellensp Date: Tue, 22 Jun 2021 08:09:21 +1200 Subject: [PATCH 0297/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20heater=20display?= =?UTF-8?q?=20options/compile=20(#22185)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +++ Marlin/src/lcd/dogm/status/hotend.h | 35 +++++++++++++------ Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 40 +++++++++------------- 4 files changed, 45 insertions(+), 36 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7b642cc355..ed1a672e48 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1594,7 +1594,7 @@ */ //#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones //#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends) - #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM) + #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM for numbered hotends) #define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating #define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating #define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 7a178db3aa..dd71364ee7 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1039,6 +1039,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "EXTRUDERS must be 1 with HEATERS_PARALLEL." #endif + #if ENABLED(STATUS_HOTEND_INVERTED) && NONE(STATUS_HOTEND_NUMBERLESS, STATUS_HOTEND_ANIM) + #error "With multiple hotends STATUS_HOTEND_INVERTED requires STATUS_HOTEND_ANIM or STATUS_HOTEND_NUMBERLESS." + #endif + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) #ifndef TOOLCHANGE_FS_LENGTH #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH." diff --git a/Marlin/src/lcd/dogm/status/hotend.h b/Marlin/src/lcd/dogm/status/hotend.h index 3a6e02acb6..aac29da451 100644 --- a/Marlin/src/lcd/dogm/status/hotend.h +++ b/Marlin/src/lcd/dogm/status/hotend.h @@ -39,20 +39,33 @@ #define STATUS_HOTEND1_WIDTH 16 -#if STATUS_HOTEND_BITMAPS == 1 || ENABLED(STATUS_HOTEND_NUMBERLESS) +#if STATUS_HOTEND_BITMAPS == 1 || defined(STATUS_HOTEND_NUMBERLESS) const unsigned char status_hotend_a_bmp[] PROGMEM = { B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00011111,B11100000, - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, + #if defined(STATUS_HOTEND_INVERTED) && !defined(STATUS_HOTEND_ANIM) + B00100000,B00010000, + B00100000,B00010000, + B00100000,B00010000, + B00010000,B00100000, + B00010000,B00100000, + B00100000,B00010000, + B00100000,B00010000, + B00110000,B00110000, + B00001000,B01000000, + B00000100,B10000000, + #else + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00011111,B11100000, + B00011111,B11100000, + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + #endif B00000011,B00000000 }; diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 8309c3a00e..d58be4dbaf 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -236,18 +236,12 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #define HOTEND_DOT false #endif - #if ANIM_HOTEND && BOTH(STATUS_HOTEND_INVERTED, STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_b_bmp - #define ON_BMP(N) status_hotend_a_bmp - #elif ANIM_HOTEND && DISABLED(STATUS_HOTEND_INVERTED) && ENABLED(STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_a_bmp - #define ON_BMP(N) status_hotend_b_bmp - #elif BOTH(ANIM_HOTEND, STATUS_HOTEND_INVERTED) - #define OFF_BMP(N) status_hotend##N##_b_bmp - #define ON_BMP(N) status_hotend##N##_a_bmp + #if ENABLED(STATUS_HOTEND_NUMBERLESS) + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_b_bmp, status_hotend_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_a_bmp, status_hotend_b_bmp) #else - #define OFF_BMP(N) status_hotend##N##_a_bmp - #define ON_BMP(N) status_hotend##N##_b_bmp + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_b_bmp, status_hotend##N##_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_a_bmp, status_hotend##N##_b_bmp) #endif #if STATUS_HOTEND_BITMAPS > 1 @@ -275,20 +269,18 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); NOMORE(tall, BAR_TALL); - #if ANIM_HOTEND - // Draw hotend bitmap, either whole or split by the heating percent - const uint8_t hx = STATUS_HOTEND_X(heater_id), - bw = STATUS_HOTEND_BYTEWIDTH(heater_id); - #if ENABLED(STATUS_HEAT_PERCENT) - if (isHeat && tall <= BAR_TALL) { - const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); - } - else - #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); + // Draw hotend bitmap, either whole or split by the heating percent + const uint8_t hx = STATUS_HOTEND_X(heater_id), + bw = STATUS_HOTEND_BYTEWIDTH(heater_id); + #if ENABLED(STATUS_HEAT_PERCENT) + if (isHeat && tall <= BAR_TALL) { + const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); + } + else #endif + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); } // PAGE_CONTAINS From 59f01b417ad4b2a6a2f56758cf1ac797edaa4a6f Mon Sep 17 00:00:00 2001 From: Grumpy Date: Tue, 22 Jun 2021 08:12:39 +1200 Subject: [PATCH 0298/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20dual=20Neopixels?= =?UTF-8?q?=20(#22174)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/leds/neopixel.h | 1 - Marlin/src/gcode/feature/leds/M150.cpp | 19 +++++++++++++------ 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index e577948cd8..b2c16459f5 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -114,7 +114,6 @@ public: #if CONJOINED_NEOPIXEL adaneo2.show(); #else - IF_DISABLED(NEOPIXEL2_SEPARATE, adaneo1.setPin(NEOPIXEL2_PIN)); adaneo1.show(); adaneo1.setPin(NEOPIXEL_PIN); #endif diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index 5d175ea8f7..4d271007e5 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -52,14 +52,16 @@ * M150 I1 R ; Set NEOPIXEL index 1 to red * M150 S1 I1 R ; Set SEPARATE index 1 to red */ - void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) - const uint8_t index = parser.intval('I', -1); + const int8_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) - const uint8_t unit = parser.intval('S'), - brightness = unit ? neo2.brightness() : neo.brightness(); - *(unit ? &neo2.neoindex : &neo.neoindex) = index; + int8_t brightness, unit = parser.intval('S', -1); + switch (unit) { + case -1: neo2.neoindex = index; // fall-thru + case 0: neo.neoindex = index; brightness = neo.brightness(); break; + case 1: neo2.neoindex = index; brightness = neo2.brightness(); break; + } #else const uint8_t brightness = neo.brightness(); neo.neoindex = index; @@ -75,10 +77,15 @@ void GcodeSuite::M150() { ); #if ENABLED(NEOPIXEL2_SEPARATE) - if (unit == 1) { leds2.set_color(color); return; } + switch (unit) { + case 0: leds.set_color(color); return; + case 1: leds2.set_color(color); return; + } #endif + // If 'S' is not specified use both leds.set_color(color); + TERN_(NEOPIXEL2_SEPARATE, leds2.set_color(color)); } #endif // HAS_COLOR_LEDS From de4b3498c71c5666477b15544d1561fabee3d499 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Mon, 21 Jun 2021 13:36:06 -0700 Subject: [PATCH 0299/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20IJK=20axis=20ref?= =?UTF-8?q?erences,=20E=20stepper=20indices=20(#22176)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/feature/dac/stepper_dac.cpp | 14 +++-- Marlin/src/gcode/feature/L6470/M906.cpp | 55 +++++++++---------- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 26 +++++---- Marlin/src/gcode/feature/trinamic/M906.cpp | 8 +-- .../src/gcode/feature/trinamic/M911-M914.cpp | 30 +++++----- Marlin/src/gcode/host/M114.cpp | 10 ++-- Marlin/src/gcode/parser.h | 8 ++- Marlin/src/module/motion.cpp | 17 +++++- 9 files changed, 98 insertions(+), 72 deletions(-) diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 1cb0813daa..3abaece443 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -85,10 +85,16 @@ void StepperDAC::print_values() { if (!dac_present) return; SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR_P( SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); - SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + SERIAL_ECHOPAIR_P(SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); + #if HAS_Y_AXIS + SERIAL_ECHOPAIR_P(SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); + #endif + #if HAS_Z_AXIS + SERIAL_ECHOPAIR_P(SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); + #endif + #if HAS_EXTRUDERS + SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + #endif } void StepperDAC::commit_eeprom() { diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 90fd6c487e..dddf7f8aee 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -32,31 +32,6 @@ #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../../core/debug_out.h" -/** - * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the - * PWMs to the steppers - * - * On L6474 this sets the TVAL register (same address). - * - * I - select which driver(s) to change on multi-driver axis - * 0 - (default) all drivers on the axis or E0 - * 1 - monitor only X, Y, Z or E1 - * 2 - monitor only X2, Y2, Z2 or E2 - * 3 - monitor only Z3 or E3 - * 4 - monitor only Z4 or E4 - * 5 - monitor only E5 - * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) - * L6474 - current in mA (4A max) - * All others - 0-255 - */ - -/** - * Sets KVAL_HOLD wich affects the current being driven through the stepper. - * - * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx - * that affects the effective voltage seen by the stepper. - */ - /** * MACRO to fetch information on the items associated with current limiting * and maximum voltage output. @@ -220,6 +195,28 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { } } +/** + * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the + * PWMs to the steppers + * + * On L6474 this sets the TVAL register (same address). + * + * I - select which driver(s) to change on multi-driver axis + * 0 - (default) all drivers on the axis or E0 + * 1 - monitor only X, Y, Z or E1 + * 2 - monitor only X2, Y2, Z2 or E2 + * 3 - monitor only Z3 or E3 + * 4 - monitor only Z4 or E4 + * 5 - monitor only E5 + * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) + * L6474 - current in mA (4A max) + * All others - 0-255 + * + * Sets KVAL_HOLD wich affects the current being driven through the stepper. + * + * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx + * that affects the effective voltage seen by the stepper. + */ void GcodeSuite::M906() { L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status @@ -281,11 +278,11 @@ void GcodeSuite::M906() { break; #endif - #if HAS_EXTRUDERS + #if E_STEPPERS case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { #if AXIS_IS_L64XX(E0) case 0: L6470_SET_KVAL_HOLD(E0); break; #endif diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 2eb4ceea41..bc31e1225d 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -56,7 +56,7 @@ */ void GcodeSuite::M125() { // Initial retract before move to filament change position - const float retract = -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH)); + const float retract = TERN0(HAS_EXTRUDERS, -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH))); xyz_pos_t park_point = NOZZLE_PARK_POINT; diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index a3fb07df13..9a7f1fbce9 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -40,7 +40,7 @@ void tmc_set_stealthChop(TMC &st, const bool enable) { st.refresh_stepping_mode(); } -static void set_stealth_status(const bool enable, const int8_t target_extruder) { +static void set_stealth_status(const bool enable, const int8_t target_e_stepper) { #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable) #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \ @@ -82,17 +82,19 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder) case K_AXIS: TMC_SET_STEALTH(K); break; #endif - #if HAS_EXTRUDERS + #if E_STEPPERS case E_AXIS: { - if (target_extruder < 0) return; - OPTCODE(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_STEALTH(E0)) - OPTCODE(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_STEALTH(E1)) - OPTCODE(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_STEALTH(E2)) - OPTCODE(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_STEALTH(E3)) - OPTCODE(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_STEALTH(E4)) - OPTCODE(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_STEALTH(E5)) - OPTCODE(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_STEALTH(E6)) - OPTCODE(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_STEALTH(E7)) + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_STEALTH(E0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_STEALTH(E1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_STEALTH(E2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_STEALTH(E3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_STEALTH(E4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_STEALTH(E5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_STEALTH(E6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_STEALTH(E7); break;) + } } break; #endif } @@ -131,7 +133,7 @@ static void say_stealth_status() { */ void GcodeSuite::M569() { if (parser.seen('S')) - set_stealth_status(parser.value_bool(), get_target_extruder_from_command()); + set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command()); else say_stealth_status(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 70e6a00b36..9e56e51358 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -102,11 +102,11 @@ void GcodeSuite::M906() { case K_AXIS: TMC_SET_CURRENT(K); break; #endif - #if HAS_EXTRUDERS + #if E_STEPPERS case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { #if AXIS_IS_TMC(E0) case 0: TMC_SET_CURRENT(E0); break; #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 747f1c9516..f90a30aab2 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -265,20 +265,22 @@ TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); break; - case E_AXIS: { - #if E_STEPPERS - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - TERN_(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_PWMTHRS_E(0)); - TERN_(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_PWMTHRS_E(1)); - TERN_(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_PWMTHRS_E(2)); - TERN_(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_PWMTHRS_E(3)); - TERN_(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_PWMTHRS_E(4)); - TERN_(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_PWMTHRS_E(5)); - TERN_(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_PWMTHRS_E(6)); - TERN_(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_PWMTHRS_E(7)); - #endif // E_STEPPERS - } break; + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_PWMTHRS_E(0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_PWMTHRS_E(1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_PWMTHRS_E(2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_PWMTHRS_E(3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_PWMTHRS_E(4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_PWMTHRS_E(5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_PWMTHRS_E(6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_PWMTHRS_E(7); break;) + } + } break; + #endif // E_STEPPERS } } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 2fdce1edfd..7d69033319 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -216,10 +216,12 @@ void GcodeSuite::M114() { report_current_position_detail(); return; } - if (parser.seen_test('E')) { - SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); - return; - } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); + return; + } + #endif #endif #if ENABLED(M114_REALTIME) diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 5a1748cc4d..08cf10004a 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -311,7 +311,13 @@ public: } static inline float axis_unit_factor(const AxisEnum axis) { - return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); + return ( + #if HAS_EXTRUDERS + axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor + #else + linear_unit_factor + #endif + ); } static inline float linear_value_to_mm(const_float_t v) { return v * linear_unit_factor; } diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index b540c9a938..63fdd5afc3 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -266,7 +266,18 @@ void report_current_position_projected() { get_cartesian_from_steppers(); const xyz_pos_t lpos = cartes.asLogical(); - SERIAL_ECHOPAIR("X:", lpos.x, " Y:", lpos.y, " Z:", lpos.z, " E:", current_position.e); + SERIAL_ECHOPAIR( + "X:", lpos.x + #if HAS_Y_AXIS + , " Y:", lpos.y + #endif + #if HAS_Z_AXIS + , " Z:", lpos.z + #endif + #if HAS_EXTRUDERS + , " E:", current_position.e + #endif + ); stepper.report_positions(); #if IS_SCARA @@ -929,7 +940,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { float cartesian_mm = diff.magnitude(); // If the move is very short, check the E move distance - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); // No E move either? Game over. if (UNEAR_ZERO(cartesian_mm)) return true; @@ -1008,7 +1019,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is very short, check the E move distance // No E move either? Game over. float cartesian_mm = diff.magnitude(); - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); if (UNEAR_ZERO(cartesian_mm)) return; // The length divided by the segment size From e5991f786f538919f389d7fd00b9ea2b21c20e05 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 21 Jun 2021 16:24:50 -0500 Subject: [PATCH 0300/2168] =?UTF-8?q?=F0=9F=8E=A8=20Cosmetic=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/G26.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 616f16a58a..882197139e 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -291,7 +291,7 @@ typedef struct { if (p2.x < 0 || p2.x >= (GRID_MAX_POINTS_X)) return; if (p2.y < 0 || p2.y >= (GRID_MAX_POINTS_Y)) return; - if(circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) { + if (circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) { xyz_pos_t s, e; s.x = _GET_MESH_X(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; e.x = _GET_MESH_X(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; From b6d8fec6ccb681a0e78e26842e52dd4bba70dbbb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 21 Jun 2021 16:31:41 -0500 Subject: [PATCH 0301/2168] =?UTF-8?q?=F0=9F=90=9B=F0=9F=8C=90=20Fix=20extr?= =?UTF-8?q?a=20axis=20translations?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_en.h | 6 +++--- Marlin/src/lcd/language/language_it.h | 6 +++--- Marlin/src/lcd/language/language_uk.h | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index c60c357ecc..6920f00d36 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -592,9 +592,9 @@ namespace Language_en { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("I Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("J Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("K Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 9e9cdd2acc..85b9d3f399 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -581,9 +581,9 @@ namespace Language_it { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver I %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver J %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver K %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") AXIS4_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") AXIS5_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") AXIS6_STR _UxGT(" %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 27dfc1fcda..86d0e01fe6 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -716,9 +716,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Драйвер X, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Драйвер Y, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Драйвер Z, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер I, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер J, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер K, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") AXIS4_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") AXIS5_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") AXIS6_STR _UxGT(", %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); From 0f5126acb23a9a363c97a3c6a387c6842f2c55cd Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 21 Jun 2021 15:38:28 -0600 Subject: [PATCH 0302/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20and=20enhance=20?= =?UTF-8?q?FTDI=20Eve=20Touch=20UI=20(#22189)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../cocoa_press/leveling_menu.cpp | 91 +++++++++++++++++++ .../cocoa_press/leveling_menu.h | 32 +++++++ .../cocoa_press/main_menu.cpp | 2 +- .../generic/leveling_menu.cpp | 1 - .../generic/string_format.cpp | 33 ++++++- .../generic/z_offset_screen.cpp | 26 ++++-- .../generic/z_offset_screen.h | 3 + .../lcd/extui/ftdi_eve_touch_ui/screens.cpp | 1 + .../src/lcd/extui/ftdi_eve_touch_ui/screens.h | 5 +- .../extui/ftdi_eve_touch_ui/theme/colors.h | 1 + Marlin/src/lcd/extui/ui_api.cpp | 4 +- 11 files changed, 182 insertions(+), 17 deletions(-) create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp new file mode 100644 index 0000000000..57c8a7505c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -0,0 +1,91 @@ +/********************************* + * cocoa_press/leveling_menu.cpp * + *********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_LEVELING_MENU + +#if BOTH(HAS_BED_PROBE,BLTOUCH) + #include "../../../../feature/bltouch.h" +#endif + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_ROWS 5 +#define GRID_COLS 3 +#define BED_MESH_TITLE_POS BTN_POS(1,1), BTN_SIZE(3,1) +#define PROBE_BED_POS BTN_POS(1,2), BTN_SIZE(1,1) +#define SHOW_MESH_POS BTN_POS(2,2), BTN_SIZE(1,1) +#define EDIT_MESH_POS BTN_POS(3,2), BTN_SIZE(1,1) +#define BLTOUCH_TITLE_POS BTN_POS(1,3), BTN_SIZE(3,1) +#define BLTOUCH_RESET_POS BTN_POS(1,4), BTN_SIZE(1,1) +#define BLTOUCH_TEST_POS BTN_POS(2,4), BTN_SIZE(1,1) +#define BACK_POS BTN_POS(1,5), BTN_SIZE(3,1) + +void LevelingMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(BED_MESH_TITLE_POS, GET_TEXT_F(MSG_BED_LEVELING)) + .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) + .font(font_medium).colors(normal_btn) + .tag(2).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) + .enabled(ENABLED(HAS_MESH)) + .tag(3).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) + .enabled(ENABLED(HAS_MESH)) + .tag(4).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) + #undef GRID_COLS + #define GRID_COLS 2 + .tag(5).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(6).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) + #undef GRID_COLS + #define GRID_COLS 3 + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + } +} + +bool LevelingMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: BedMeshViewScreen::doProbe(); break; + case 3: BedMeshViewScreen::show(); break; + case 4: BedMeshEditScreen::show(); break; + case 5: injectCommands_P(PSTR("M280 P0 S60")); break; + case 6: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + default: return false; + } + return true; +} + +#endif // COCOA_LEVELING_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h new file mode 100644 index 0000000000..8275380249 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h @@ -0,0 +1,32 @@ +/******************************* + * cocoa_press/leveling_menu.h * + ******************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_LEVELING_MENU +#define COCOA_LEVELING_MENU_CLASS LevelingMenu + +class LevelingMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index 28dad42b13..a990717fb3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -88,7 +88,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; case 9: injectCommands_P(PSTR("M84")); break; #if HAS_LEVELING - case 10: GOTO_SCREEN(LevelingMenu); break; + case 10: GOTO_SCREEN(LevelingMenu); break; #endif case 11: GOTO_SCREEN(AboutScreen); break; default: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 93f9c4c228..826e01a9cf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -132,4 +132,3 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { } #endif // FTDI_LEVELING_MENU - diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp index 09f0bb6089..1f3640e3a1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp @@ -34,28 +34,53 @@ * Formats a temperature string (e.g. "100°C") */ void format_temp(char *str, const_celsius_float_t t1) { - sprintf_P(str, PSTR("%3d" S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C)); + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT), num1, GET_TEXT(MSG_UNITS_C)); + #else + sprintf_P(str, PSTR("%3d" S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C)); + #endif } /** * Formats a temperature string for an idle heater (e.g. "100 °C / idle") */ void format_temp_and_idle(char *str, const_celsius_float_t t1) { - sprintf_P(str, PSTR("%3d" S_FMT " / " S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT " / " S_FMT), num1, GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); + #else + sprintf_P(str, PSTR("%3d" S_FMT " / " S_FMT), ROUND(t1), GET_TEXT(MSG_UNITS_C), GET_TEXT(MSG_IDLE)); + #endif } /** * Formats a temperature string for an active heater (e.g. "100 / 200°C") */ void format_temp_and_temp(char *str, const_celsius_float_t t1, const_celsius_float_t t2) { - sprintf_P(str, PSTR("%3d / %3d" S_FMT), ROUND(t1), ROUND(t2), GET_TEXT(MSG_UNITS_C)); + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7], num2[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + dtostrf(t2, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num2); + sprintf_P(str, PSTR("%s / %s" S_FMT), num1, num2, GET_TEXT(MSG_UNITS_C)); + #else + sprintf_P(str, PSTR("%3d / %3d" S_FMT), ROUND(t1), ROUND(t2), GET_TEXT(MSG_UNITS_C)); + #endif } /** * Formats a temperature string for a material (e.g. "100°C (PLA)") */ void format_temp_and_material(char *str, const_celsius_float_t t1, const char *material) { - sprintf_P(str, PSTR("%3d" S_FMT " (" S_FMT ")"), ROUND(t1), GET_TEXT(MSG_UNITS_C), material); + #ifdef TOUCH_UI_LCD_TEMP_PRECISION + char num1[7]; + dtostrf(t1, 4 + TOUCH_UI_LCD_TEMP_PRECISION, TOUCH_UI_LCD_TEMP_PRECISION, num1); + sprintf_P(str, PSTR("%s" S_FMT " (" S_FMT ")"), num1, GET_TEXT(MSG_UNITS_C), material); + #else + sprintf_P(str, PSTR("%3d" S_FMT " (" S_FMT ")"), ROUND(t1), GET_TEXT(MSG_UNITS_C), material); + #endif } /** diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp index 8d886c704a..073665e586 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -36,7 +36,14 @@ constexpr static ZOffsetScreenData &mydata = screen_data.ZOffsetScreen; void ZOffsetScreen::onEntry() { mydata.z = SHEET_THICKNESS; + mydata.softEndstopState = getSoftEndstopState(); BaseNumericAdjustmentScreen::onEntry(); + if (wizardRunning()) + setSoftEndstopState(false); +} + +void ZOffsetScreen::onExit() { + setSoftEndstopState(mydata.softEndstopState); } void ZOffsetScreen::onRedraw(draw_mode_t what) { @@ -50,17 +57,13 @@ void ZOffsetScreen::onRedraw(draw_mode_t what) { } void ZOffsetScreen::move(float mm, int16_t steps) { - // We can't store state after the call to the AlertBox, so - // check whether the current position equal mydata.z in order - // to know whether the user started the wizard. - if (getAxisPosition_mm(Z) == mydata.z) { - // In the wizard + if (wizardRunning()) { mydata.z += mm; setAxisPosition_mm(mydata.z, Z); } else { // Otherwise doing a manual adjustment, possibly during a print. - babystepAxis_steps(steps, Z); + TERN(BABYSTEPPING, babystepAxis_steps(steps, Z), UNUSED(steps)); } } @@ -84,9 +87,16 @@ void ZOffsetScreen::runWizard() { AlertDialogBox::show(PSTR("After the printer finishes homing, adjust the Z Offset so that a sheet of paper can pass between the nozzle and bed with slight resistance.")); } +bool ZOffsetScreen::wizardRunning() { + // We can't store state after the call to the AlertBox, so + // check whether the current Z position equals mydata.z in order + // to know whether the user started the wizard. + return getAxisPosition_mm(Z) == mydata.z; +} + bool ZOffsetScreen::onTouchHeld(uint8_t tag) { - const int16_t steps = mmToWholeSteps(getIncrement(), Z); - const float increment = mmFromWholeSteps(steps, Z); + const int16_t steps = TERN(BABYSTEPPING, mmToWholeSteps(getIncrement(), Z), 0); + const float increment = TERN(BABYSTEPPING, mmFromWholeSteps(steps, Z), getIncrement()); switch (tag) { case 2: runWizard(); break; case 4: UI_DECREMENT(ZOffset_mm); move(-increment, -steps); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h index 067687f315..0df9209b1f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.h @@ -27,14 +27,17 @@ struct ZOffsetScreenData : public BaseNumericAdjustmentScreenData { float z; + bool softEndstopState; }; class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { private: static void move(float mm, int16_t steps); static void runWizard(); + static bool wizardRunning(); public: static void onEntry(); + static void onExit(); static void onRedraw(draw_mode_t); static bool onTouchHeld(uint8_t tag); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp index e1900ac793..ec627e313b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -113,6 +113,7 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_MENU) DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_SCREEN) DECL_SCREEN_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LEVELING_MENU) DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_XYZ_SCREEN) DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_E_SCREEN) }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h index f5e2160d10..51e472496a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -157,6 +157,7 @@ enum { #include "cocoa_press/load_chocolate.h" #include "cocoa_press/move_xyz_screen.h" #include "cocoa_press/move_e_screen.h" + #include "cocoa_press/leveling_menu.h" #else #include "generic/status_screen.h" @@ -206,7 +207,9 @@ enum { #endif #if HAS_LEVELING - #include "generic/leveling_menu.h" + #if DISABLED(TOUCH_UI_COCOA_PRESS) + #include "generic/leveling_menu.h" + #endif #if HAS_BED_PROBE #include "generic/z_offset_screen.h" #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h index 1649675122..995379fcda 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h @@ -108,6 +108,7 @@ namespace Theme { constexpr uint32_t bed_mesh_lines_rgb = accent_color_6; constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; + #define BED_MESH_POINTS_GRAY #else constexpr uint32_t theme_darkest = gray_color_1; constexpr uint32_t theme_dark = gray_color_2; diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index ddeb02e3be..53eb6d399e 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1033,10 +1033,10 @@ namespace ExtUI { } bool isPrintingFromMediaPaused() { - return TERN0(SDSUPPORT, isPrintingFromMedia() && printingIsPaused()); + return TERN0(SDSUPPORT, IS_SD_PAUSED()); } - bool isPrintingFromMedia() { return IS_SD_PRINTING(); } + bool isPrintingFromMedia() { return TERN0(SDSUPPORT, IS_SD_PRINTING() || IS_SD_PAUSED()); } bool isPrinting() { return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); From 5326fdc382033f4af084d8885be56265e2f10af1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 22 Jun 2021 00:54:36 +0000 Subject: [PATCH 0303/2168] [cron] Bump distribution date (2021-06-22) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3bf472f7c0..81ff49192e 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 "2021-06-21" + #define STRING_DISTRIBUTION_DATE "2021-06-22" #endif /** From 41daf6376885c9cf44886fd07761b9cbfc423139 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 23 Jun 2021 06:42:24 +1200 Subject: [PATCH 0304/2168] =?UTF-8?q?=F0=9F=9A=B8=20MarlinUI=20Move=20Z=20?= =?UTF-8?q?>=3D=201000=20(#22192)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_motion.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index ea85a55660..70f7acd547 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -28,7 +28,7 @@ #if HAS_LCD_MENU -#define LARGE_BED_TEST ((X_BED_SIZE) >= 1000 || (Y_BED_SIZE) >= 1000) +#define LARGE_AREA_TEST ((X_BED_SIZE) >= 1000 || (Y_BED_SIZE) >= 1000 || (Z_MAX_POS) >= 1000) #include "menu_item.h" #include "menu_addon.h" @@ -87,7 +87,7 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { MenuEditItemBase::draw_edit_screen(name, ftostr63(imp_pos)); } else - MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? (LARGE_BED_TEST ? ftostr51sign(pos) : ftostr41sign(pos)) : ftostr63(pos)); + MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? (LARGE_AREA_TEST ? ftostr51sign(pos) : ftostr41sign(pos)) : ftostr63(pos)); } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } @@ -167,13 +167,13 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int BACK_ITEM(MSG_MOVE_AXIS); if (parser.using_inch_units()) { - if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_1IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_1IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); } else { - if (LARGE_BED_TEST) SUBMENU(MSG_MOVE_100MM, []{ _goto_manual_move(100); }); + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_100MM, []{ _goto_manual_move(100); }); SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); From b5085bbd1d1cf39ca34e3891ba774f9408da2449 Mon Sep 17 00:00:00 2001 From: Serhiy-K <52166448+Serhiy-K@users.noreply.github.com> Date: Tue, 22 Jun 2021 21:48:56 +0300 Subject: [PATCH 0305/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Russian=20lan?= =?UTF-8?q?guage=20(#22193)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_ru.h | 138 ++++++++++++++++++++------ 1 file changed, 110 insertions(+), 28 deletions(-) diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index a10f47ef8e..4240ecbec3 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -69,6 +69,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Парковка X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Итерация: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); @@ -80,11 +83,29 @@ namespace Language_ru { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; #else PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Установить ноль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Преднагрев ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрев ") PREHEAT_1_LABEL " ~"; @@ -107,14 +128,22 @@ namespace Language_ru { PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Управление лазером"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключить шпиндель"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); #else PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощн. лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); #endif + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); @@ -127,6 +156,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Выровнять стол"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Выровнять углы"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Следующий угол"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до срабатыв. зонда"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); + #else + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до сраб. зонда"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав."); + #endif + PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хорошие точки: "); + PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Последняя Z: "); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение по Z"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); @@ -164,12 +202,13 @@ namespace Language_ru { PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу и измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); #else - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу,измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу, измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать, измер. стол"); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Мастер сеток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Измерение"); PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Двигаемся дальше"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активировать UBL"); @@ -185,17 +224,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка сетки завершена"); #else PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" стола,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка завершена"); #endif PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); #else @@ -205,14 +242,10 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); #if LCD_WIDTH > 21 - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); #else - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Провер. свою сетку"); #endif PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрев стола"); @@ -239,11 +272,12 @@ namespace Language_ru { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); #else PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Информация UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполн."); #endif - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ручное заполнение"); PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Умное заполнение"); PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заполнить сетку"); @@ -303,6 +337,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Движение по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Движение по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Экструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Экструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); @@ -310,6 +347,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Движение 0.1мм"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Движение 1мм"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Движение 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Движение 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорость"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z стола"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; @@ -318,6 +356,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); PROGMEM Language_Str MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлаждение"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасность потока"); + #else + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлажд."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); + #endif + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Кулер"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Сохранённый кулер ~"); @@ -352,6 +399,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); @@ -362,6 +412,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Скор.макс *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Скор.мин"); @@ -370,6 +423,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Ускор.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ускор.втягив."); @@ -380,6 +436,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E шаг/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* шаг/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); @@ -402,10 +461,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_CONTRAST = _UxGT("Контраст экрана"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); #else + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые парам."); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализ. EEPROM"); #endif PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Сбой EEPROM: CRC"); @@ -414,7 +474,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметры сохранены"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Обновление прошивки"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Сброс принтера"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Главный экран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Подготовить"); PROGMEM Language_Str MSG_TUNE = _UxGT("Настроить"); @@ -541,10 +601,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + #else + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); + #endif PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Микрошаг X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); @@ -552,6 +619,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("УТЕЧКА ОХЛАЖДЕНИЯ"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХЛАДИТЬ НЕ УДАЛОСЬ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); @@ -567,6 +636,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охлаждение зонда..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охладжение камеры..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охлаждение лазера..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калибровка Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калибровать X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровать Y"); @@ -575,13 +645,12 @@ namespace Language_ru { PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); - #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещение"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диагонали"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); #else PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); #endif + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Высота"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радиус"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("О принтере"); @@ -597,6 +666,11 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Управление UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондирование выполнено"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Данные платы"); @@ -617,14 +691,14 @@ namespace Language_ru { PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Длина филамента"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Отпечатков"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Всего"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Напечатано"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Выдавлено"); #endif @@ -637,6 +711,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); @@ -749,11 +826,11 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль удалён"); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Нажмите кнопку", "для продолжения", "печати")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Ожидайте начала", "смены филамента")); @@ -803,8 +880,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контрольной точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондирования"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); #else PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондир.контр.точки Z"); PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движ. к точке зондир."); @@ -818,6 +895,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижний правый"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Карта"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 From 48161cf091027421b886e2a99847a60913af457f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 23 Jun 2021 00:50:45 +0000 Subject: [PATCH 0306/2168] [cron] Bump distribution date (2021-06-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 81ff49192e..ab0d84deb2 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 "2021-06-22" + #define STRING_DISTRIBUTION_DATE "2021-06-23" #endif /** From 0bd113b944d041192146692de50e33fe4d6c0fd8 Mon Sep 17 00:00:00 2001 From: Cytown Date: Thu, 24 Jun 2021 00:40:32 +0800 Subject: [PATCH 0307/2168] =?UTF-8?q?=E2=9C=A8=20Power-off=20confirm=20/?= =?UTF-8?q?=20beep=20options=20(#22191)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 ++ Marlin/src/gcode/control/M80_M81.cpp | 4 ++++ Marlin/src/lcd/marlinui.cpp | 7 +++++++ Marlin/src/lcd/marlinui.h | 4 ++++ Marlin/src/lcd/menu/menu_main.cpp | 10 +++++++++- buildroot/tests/rambo | 3 ++- 6 files changed, 28 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 717cdd9236..5b7f439fe5 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -366,6 +366,8 @@ //#define PSU_NAME "Power Supply" #if ENABLED(PSU_CONTROL) + //#define PS_OFF_CONFIRM // Confirm dialog when power off + //#define PS_OFF_SOUND // Beep 1s when power off #define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 1b5ea2f7ef..00a0a31026 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -101,6 +101,10 @@ void GcodeSuite::M81() { #endif #endif + #if ENABLED(PS_OFF_SOUND) + BUZZ(1000, 659); + #endif + safe_delay(1000); // Wait 1 second before switching off #if HAS_SUICIDE diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index d2e26afedf..9de8941ad9 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1494,6 +1494,13 @@ void MarlinUI::update() { TERN_(HAS_LCD_MENU, return_to_status()); } + #if BOTH(PSU_CONTROL, PS_OFF_CONFIRM) + void MarlinUI::poweroff() { + queue.inject_P(PSTR("M81")); + goto_previous_screen(); + } + #endif + void MarlinUI::flow_fault() { LCD_ALERTMESSAGEPGM(MSG_FLOWMETER_FAULT); TERN_(HAS_BUZZER, buzz(1000, 440)); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 14514e2a65..fa2b09b873 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -334,6 +334,10 @@ public: static void resume_print(); static void flow_fault(); + #if BOTH(PSU_CONTROL, PS_OFF_CONFIRM) + static void poweroff(); + #endif + #if HAS_WIRED_LCD static millis_t next_button_update_ms; diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 921c2435b5..1e79edb864 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -387,7 +387,15 @@ void menu_main() { // #if ENABLED(PSU_CONTROL) if (powersupply_on) - GCODES_ITEM(MSG_SWITCH_PS_OFF, PSTR("M81")); + #if ENABLED(PS_OFF_CONFIRM) + CONFIRM_ITEM(MSG_SWITCH_PS_OFF, + MSG_YES, MSG_NO, + ui.poweroff, ui.goto_previous_screen, + GET_TEXT(MSG_SWITCH_PS_OFF), (const char *)nullptr, PSTR("?") + ); + #else + GCODES_ITEM(MSG_SWITCH_PS_OFF, PSTR("M81")); + #endif else GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index df2717c715..9c56a689b0 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -32,7 +32,8 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ + PSU_CONTROL PS_OFF_CONFIRM PS_OFF_SOUND AUTO_POWER_CONTROL \ + POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL opt_add DEBUG_POWER_LOSS_RECOVERY From b3b1dbaceb1e17d1532eaa5c04ee738306127bb5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 24 Jun 2021 00:44:58 +0000 Subject: [PATCH 0308/2168] [cron] Bump distribution date (2021-06-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ab0d84deb2..b83e6061e1 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 "2021-06-23" + #define STRING_DISTRIBUTION_DATE "2021-06-24" #endif /** From ba26e902b20b19c269c11c2bf535a170c28907bc Mon Sep 17 00:00:00 2001 From: bwspath Date: Thu, 24 Jun 2021 22:27:54 +0200 Subject: [PATCH 0309/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Octopus=20build?= =?UTF-8?q?=20on=20case-sensitive=20FS=20(#22206)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f4.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index dec7fea568..ee88135eca 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -238,7 +238,7 @@ build_flags = ${stm_flash_drive.build_flags} [env:BIGTREE_OCTOPUS_V1] platform = ${common_stm32.platform} extends = common_stm32 -board = marlin_BigTree_octopus_v1 +board = marlin_BigTree_Octopus_v1 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common_stm32.build_flags} From 8eee94dbca85919e110b11682fde4df62a102255 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 25 Jun 2021 01:02:43 +0000 Subject: [PATCH 0310/2168] [cron] Bump distribution date (2021-06-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b83e6061e1..4d346a3a87 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 "2021-06-24" + #define STRING_DISTRIBUTION_DATE "2021-06-25" #endif /** From 500b7872fb92d35dd0d1a690f4e5cf1aadea2f46 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 25 Jun 2021 14:44:51 -0500 Subject: [PATCH 0311/2168] =?UTF-8?q?=F0=9F=90=9B=20Trigger=20existing=20e?= =?UTF-8?q?ndstops=20on=20G38=20hit?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/endstops.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index c750d56713..8f6827de27 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -932,9 +932,13 @@ void Endstops::update() { #endif // If G38 command is active check Z_MIN_PROBE for ALL movement if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE)) != _G38_OPEN_STATE) { - if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, MIN); planner.endstop_triggered(X_AXIS); } - else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, MIN); planner.endstop_triggered(Y_AXIS); } - else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, MIN); planner.endstop_triggered(Z_AXIS); } + if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, TERN(X_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(X_AXIS); } + #if HAS_Y_AXIS + else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, TERN(Y_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Y_AXIS); } + #endif + #if HAS_Z_AXIS + else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, TERN(Z_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Z_AXIS); } + #endif G38_did_trigger = true; } #endif From f399706911ac26bee8af5535f6714be100af73a0 Mon Sep 17 00:00:00 2001 From: Cytown Date: Sat, 26 Jun 2021 03:50:09 +0800 Subject: [PATCH 0312/2168] =?UTF-8?q?=F0=9F=8E=A8=20Power-off=20tone=20fol?= =?UTF-8?q?lowup=20(#22222)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/power.cpp | 9 +++++++++ Marlin/src/gcode/control/M80_M81.cpp | 4 ---- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index fb2f1312e0..e7d33bec49 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -33,6 +33,10 @@ #include "../module/stepper/indirection.h" #include "../MarlinCore.h" +#if ENABLED(PS_OFF_SOUND) + #include "../libs/buzzer.h" +#endif + #if defined(PSU_POWERUP_GCODE) || defined(PSU_POWEROFF_GCODE) #include "../gcode/gcode.h" #endif @@ -133,6 +137,11 @@ void Power::power_off() { #ifdef PSU_POWEROFF_GCODE GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWEROFF_GCODE)); #endif + + #if ENABLED(PS_OFF_SOUND) + BUZZ(1000, 659); + #endif + PSU_PIN_OFF(); } } diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 00a0a31026..1b5ea2f7ef 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -101,10 +101,6 @@ void GcodeSuite::M81() { #endif #endif - #if ENABLED(PS_OFF_SOUND) - BUZZ(1000, 659); - #endif - safe_delay(1000); // Wait 1 second before switching off #if HAS_SUICIDE From e5f06c814b7d50ef66e02170a502869dacdd32f9 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Fri, 25 Jun 2021 14:12:21 -0700 Subject: [PATCH 0313/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20TMC=20SPI=20e?= =?UTF-8?q?ndstops=20comment=20(#22221)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ed1a672e48..a13df514b0 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2892,7 +2892,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** + * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * From 696d878b5e180cf8ff66fd3cdcb295f91a2339f3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 26 Jun 2021 00:55:17 +0000 Subject: [PATCH 0314/2168] [cron] Bump distribution date (2021-06-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4d346a3a87..82ae1fafa8 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 "2021-06-25" + #define STRING_DISTRIBUTION_DATE "2021-06-26" #endif /** From a37cc76cb93c4e8c1337ec8ecd8f966b0c33d555 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Fri, 25 Jun 2021 22:38:27 -0600 Subject: [PATCH 0315/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20and=20improve=20?= =?UTF-8?q?FTDI=20Eve=20Touch=20UI=20(#22223)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_touch_ui/bioprinter/screens.h | 105 ++++++++ .../cocoa_press/preheat_screen.cpp | 10 - .../ftdi_eve_touch_ui/cocoa_press/screens.h | 135 ++++++++++ .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 27 +- .../generic/about_screen.cpp | 14 +- .../generic/change_filament_screen.cpp | 2 +- .../generic/change_filament_screen.h | 2 +- .../generic/files_screen.cpp | 4 + .../ftdi_eve_touch_ui/generic/files_screen.h | 1 + .../generic/interface_settings_screen.cpp | 40 ++- .../extui/ftdi_eve_touch_ui/generic/screens.h | 224 +++++++++++++++++ .../generic/status_screen.cpp | 10 + .../ftdi_eve_touch_ui/generic/status_screen.h | 2 + .../src/lcd/extui/ftdi_eve_touch_ui/screens.h | 236 +----------------- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 10 +- 16 files changed, 543 insertions(+), 281 deletions(-) create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h new file mode 100644 index 0000000000..7294c4aa0b --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h @@ -0,0 +1,105 @@ +/************* + * screens.h * + *************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, + PRINTING_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#include "../generic/base_numeric_adjustment_screen.h" +#include "../generic/dialog_box_base_class.h" +#include "../generic/boot_screen.h" +#include "../generic/about_screen.h" +#include "../generic/kill_screen.h" +#include "../generic/alert_dialog_box.h" +#include "../generic/spinner_dialog_box.h" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#include "../generic/lock_screen.h" +#include "../generic/endstop_state_screen.h" +#include "../generic/display_tuning_screen.h" +#include "../generic/media_player_screen.h" +#include "../generic/statistics_screen.h" +#include "../generic/stepper_current_screen.h" +#include "../generic/stepper_bump_sensitivity_screen.h" +#include "../generic/leveling_menu.h" +#include "../generic/z_offset_screen.h" +#include "../generic/files_screen.h" + +#include "bio_status_screen.h" +#include "bio_main_menu.h" +#include "bio_tune_menu.h" +#include "bio_advanced_settings.h" +#include "bio_printing_dialog_box.h" +#include "bio_confirm_home_xyz.h" +#include "bio_confirm_home_e.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index 3bcc64fd93..75b1fcc9c1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -84,16 +84,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, progmem_str label, float value, int16_t x, int16_t y, int16_t w, int16_t h) { #define SUB_COLS 9 #define SUB_ROWS 2 - #define SUB_GRID_W(W) ((W)*w/SUB_COLS) - #define SUB_GRID_H(H) ((H)*h/SUB_ROWS) - #define SUB_GRID_X(X) (SUB_GRID_W((X)-1) + x) - #define SUB_GRID_Y(Y) (SUB_GRID_H((Y)-1) + y) - #define SUB_X(X) (SUB_GRID_X(X) + MARGIN_L) - #define SUB_Y(Y) (SUB_GRID_Y(Y) + MARGIN_T) - #define SUB_W(W) (SUB_GRID_W(W) - MARGIN_L - MARGIN_R) - #define SUB_H(H) (SUB_GRID_H(H) - MARGIN_T - MARGIN_B) - #define SUB_POS(X,Y) SUB_X(X), SUB_Y(Y) - #define SUB_SIZE(W,H) SUB_W(W), SUB_H(H) CommandProcessor cmd; cmd.tag(0) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h new file mode 100644 index 0000000000..3a47d6bee4 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -0,0 +1,135 @@ +/************* + * screens.h * + *************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + MOVE_AXIS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + LEVELING_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + BED_MESH_VIEW_SCREEN_CACHE, + BED_MESH_EDIT_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + #if HAS_JUNCTION_DEVIATION + JUNC_DEV_SCREEN_CACHE, + #else + JERK_SCREEN_CACHE, + #endif + CASE_LIGHT_SCREEN_CACHE, + FILAMENT_MENU_CACHE, + LINEAR_ADVANCE_SCREEN_CACHE, + PREHEAT_MENU_CACHE, + PREHEAT_TIMER_SCREEN_CACHE, + LOAD_CHOCOLATE_SCREEN_CACHE, + MOVE_XYZ_SCREEN_CACHE, + MOVE_E_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#include "../generic/base_numeric_adjustment_screen.h" +#include "../generic/dialog_box_base_class.h" +#include "../generic/boot_screen.h" +#include "../generic/about_screen.h" +#include "../generic/kill_screen.h" +#include "../generic/alert_dialog_box.h" +#include "../generic/spinner_dialog_box.h" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#include "../generic/lock_screen.h" +#include "../generic/endstop_state_screen.h" +#include "../generic/display_tuning_screen.h" +#include "../generic/statistics_screen.h" +#include "../generic/stepper_current_screen.h" +#include "../generic/leveling_menu.h" +#include "../generic/z_offset_screen.h" +#include "../generic/bed_mesh_base.h" +#include "../generic/bed_mesh_view_screen.h" +#include "../generic/bed_mesh_edit_screen.h" +#include "../generic/case_light_screen.h" +#include "../generic/linear_advance_screen.h" +#include "../generic/files_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/flow_percent_screen.h" +#include "../generic/tune_menu.h" +#if HAS_JUNCTION_DEVIATION + #include "../generic/junction_deviation_screen.h" +#else + #include "../generic/jerk_screen.h" +#endif + +#include "status_screen.h" +#include "main_menu.h" +#include "advanced_settings_menu.h" +#include "preheat_menu.h" +#include "preheat_screen.h" +#include "load_chocolate.h" +#include "move_xyz_screen.h" +#include "move_e_screen.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index e15f61be00..9faedae711 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -45,24 +45,23 @@ namespace ExtUI { } void onMediaInserted() { - if (AT_SCREEN(StatusScreen)) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); - sound.play(media_inserted, PLAY_ASYNCHRONOUS); + #if ENABLED(SDSUPPORT) + sound.play(media_inserted, PLAY_ASYNCHRONOUS); + StatusScreen::onMediaInserted(); + #endif } void onMediaRemoved() { - if (isPrintingFromMedia()) { - stopPrint(); - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); - } - else - sound.play(media_removed, PLAY_ASYNCHRONOUS); - - if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - #if ENABLED(SDSUPPORT) - if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); + if (isPrintingFromMedia()) { + stopPrint(); + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); + } + else + sound.play(media_removed, PLAY_ASYNCHRONOUS); + + StatusScreen::onMediaRemoved(); + FilesScreen::onMediaRemoved(); #endif } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 3d2c6a9e44..4e90e71e8a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -91,20 +91,22 @@ void AboutScreen::onRedraw(draw_mode_t) { draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); - cmd.font(font_medium) - .colors(normal_btn) - .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) - .colors(action_btn) + cmd.font(font_medium); + #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) + cmd.colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); + #endif + cmd.colors(action_btn) .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if ENABLED(PRINTCOUNTER) + #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) && defined(FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index a3cb91af5d..46d3a4ea1c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -76,7 +76,7 @@ constexpr static ChangeFilamentScreenData &mydata = screen_data.ChangeFilamentSc /****************** COLOR SCALE ***********************/ -uint32_t getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { +uint32_t ChangeFilamentScreen::getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { rgb_t R0, R1, mix; float t; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h index 43a4bae6e0..42eaf25f4a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h @@ -38,9 +38,9 @@ class ChangeFilamentScreen : public BaseScreen, public CachedScreen. * + ****************************************************************************/ + +#pragma once + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + MOVE_AXIS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + #if HAS_LEVELING + LEVELING_SCREEN_CACHE, + #if HAS_BED_PROBE + ZOFFSET_SCREEN_CACHE, + #endif + #if HAS_MESH + BED_MESH_VIEW_SCREEN_CACHE, + BED_MESH_EDIT_SCREEN_CACHE, + #endif + #endif + #if ENABLED(BABYSTEPPING) + ADJUST_OFFSETS_SCREEN_CACHE, + #endif + #if HAS_TRINAMIC_CONFIG + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, + #endif + #if HAS_MULTI_HOTEND + NOZZLE_OFFSET_SCREEN_CACHE, + #endif + #if ENABLED(BACKLASH_GCODE) + BACKLASH_COMPENSATION_SCREEN_CACHE, + #endif + #if HAS_JUNCTION_DEVIATION + JUNC_DEV_SCREEN_CACHE, + #else + JERK_SCREEN_CACHE, + #endif + #if ENABLED(CASE_LIGHT_ENABLE) + CASE_LIGHT_SCREEN_CACHE, + #endif + #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + FILAMENT_MENU_CACHE, + #endif + #if ENABLED(LIN_ADVANCE) + LINEAR_ADVANCE_SCREEN_CACHE, + #endif + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + FILAMENT_RUNOUT_SCREEN_CACHE, + #endif + #if ENABLED(SDSUPPORT) + FILES_SCREEN_CACHE, + #endif + #if ENABLED(CUSTOM_MENU_MAIN) + CUSTOM_USER_MENUS_SCREEN_CACHE, + #endif + CHANGE_FILAMENT_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "base_screen.h" +#include "base_numeric_adjustment_screen.h" +#include "dialog_box_base_class.h" +#include "status_screen.h" +#include "main_menu.h" +#include "advanced_settings_menu.h" +#include "tune_menu.h" +#include "boot_screen.h" +#include "about_screen.h" +#include "kill_screen.h" +#include "alert_dialog_box.h" +#include "spinner_dialog_box.h" +#include "restore_failsafe_dialog_box.h" +#include "save_settings_dialog_box.h" +#include "confirm_start_print_dialog_box.h" +#include "confirm_abort_print_dialog_box.h" +#include "confirm_user_request_alert_box.h" +#include "touch_calibration_screen.h" +#include "touch_registers_screen.h" +#include "change_filament_screen.h" +#include "move_axis_screen.h" +#include "steps_screen.h" +#include "feedrate_percent_screen.h" +#include "max_velocity_screen.h" +#include "max_acceleration_screen.h" +#include "default_acceleration_screen.h" +#include "temperature_screen.h" +#include "interface_sounds_screen.h" +#include "interface_settings_screen.h" +#include "lock_screen.h" +#include "endstop_state_screen.h" +#include "display_tuning_screen.h" +#include "media_player_screen.h" + +#if ENABLED(PRINTCOUNTER) + #include "statistics_screen.h" +#endif + +#if HAS_TRINAMIC_CONFIG + #include "stepper_current_screen.h" + #include "stepper_bump_sensitivity_screen.h" +#endif + +#if HAS_MULTI_HOTEND + #include "nozzle_offsets_screen.h" +#endif + +#if HAS_LEVELING + #if ENABLED(TOUCH_UI_SYNDAVER_LEVEL) + #include "syndaver_level/leveling_menu.h" + #else + #include "leveling_menu.h" + #endif + #if HAS_BED_PROBE + #include "z_offset_screen.h" + #endif + #if HAS_MESH + #include "bed_mesh_base.h" + #include "bed_mesh_view_screen.h" + #include "bed_mesh_edit_screen.h" + #endif +#endif + +#if ENABLED(CALIBRATION_GCODE) + #include "confirm_auto_calibration_dialog_box.h" +#endif + +#if ENABLED(BABYSTEPPING) + #include "nudge_nozzle_screen.h" +#endif + +#if ENABLED(BACKLASH_GCODE) + #include "backlash_compensation_screen.h" +#endif + +#if HAS_JUNCTION_DEVIATION + #include "junction_deviation_screen.h" +#else + #include "jerk_screen.h" +#endif + +#if ENABLED(CASE_LIGHT_ENABLE) + #include "case_light_screen.h" +#endif + +#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #include "filament_menu.h" +#endif + +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #include "filament_runout_screen.h" +#endif + +#if ENABLED(LIN_ADVANCE) + #include "linear_advance_screen.h" +#endif + +#if ENABLED(SDSUPPORT) + #include "files_screen.h" +#endif + +#if ENABLED(CUSTOM_MENU_MAIN) + #include "custom_user_menus.h" +#endif + +#if ENABLED(TOUCH_UI_DEVELOPER_MENU) + #include "developer_menu.h" + #include "confirm_erase_flash_dialog_box.h" + #include "widget_demo_screen.h" + #include "stress_test_screen.h" +#endif + +#if NUM_LANGUAGES > 1 + #include "language_menu.h" +#endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index 9ef481d39b..23ac90107b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -461,4 +461,14 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { return true; } +void StatusScreen::onMediaInserted() { + if (AT_SCREEN(StatusScreen)) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); +} + +void StatusScreen::onMediaRemoved() { + if (AT_SCREEN(StatusScreen) || ExtUI::isPrintingFromMedia()) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); +} + #endif // FTDI_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h index 3a2ba1746c..6033ba1ad9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h @@ -42,4 +42,6 @@ class StatusScreen : public BaseScreen, public CachedScreen 1 - #include "generic/language_menu.h" + #include "generic/screens.h" #endif #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 53eb6d399e..00b785e680 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -305,7 +305,7 @@ namespace ExtUI { } float getAxisPosition_mm(const axis_t axis) { - return TERN0(JOYSTICK, flags.jogging) ? destination[axis] : current_position[axis]; + return current_position[axis]; } float getAxisPosition_mm(const extruder_t extruder) { diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 9de8941ad9..08b214ac56 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1616,8 +1616,9 @@ void MarlinUI::update() { if (status) { if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaInserted()); // ExtUI response - #if ENABLED(BROWSE_MEDIA_ON_INSERT) + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); + #elif ENABLED(BROWSE_MEDIA_ON_INSERT) clear_menu_history(); quick_feedback(); goto_screen(MEDIA_MENU_GATEWAY); @@ -1628,8 +1629,9 @@ void MarlinUI::update() { } else { if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response - #if PIN_EXISTS(SD_DETECT) + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); + #elif PIN_EXISTS(SD_DETECT) LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); #if HAS_LCD_MENU if (!defer_return_to_status) return_to_status(); From 5ceeb8b5ffee783461e13c2121595450ca83b6f6 Mon Sep 17 00:00:00 2001 From: Cytown Date: Sun, 27 Jun 2021 00:21:34 +0800 Subject: [PATCH 0316/2168] =?UTF-8?q?=F0=9F=9A=B8=20Expand=20box=20in=20dr?= =?UTF-8?q?aw=5Fboxed=5Fstring=20(#22209)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 1a07b7ab75..97006dac25 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -468,7 +468,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop const pixel_len_t bw = len * prop * (MENU_FONT_WIDTH), bx = x * prop * (MENU_FONT_WIDTH); if (inv) { u8g.setColorIndex(1); - u8g.drawBox(bx / prop - 1, by - (MENU_FONT_ASCENT) + 1, bw / prop + 2, MENU_FONT_HEIGHT - 1); + u8g.drawBox(bx / prop - 1, by - (MENU_FONT_ASCENT), bw + 2, MENU_FONT_HEIGHT); u8g.setColorIndex(0); } lcd_put_u8str_P(bx / prop, by, pstr); From 7328a6e3a78b0aac0c423a58c03bd82e8383272e Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 27 Jun 2021 04:32:51 +1200 Subject: [PATCH 0317/2168] =?UTF-8?q?=F0=9F=94=A7=20Fix=20E.S.T.=20sanity-?= =?UTF-8?q?check=20errors=20(#22224)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 29 +++++++++++++++++------------ 1 file changed, 17 insertions(+), 12 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index dd71364ee7..224729d35f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1249,23 +1249,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * (Electro)magnetic Switching Toolhead requirements + * Magnetic / Electromagnetic Switching Toolhead requirements */ #if EITHER(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) #ifndef SWITCHING_TOOLHEAD_Y_POS - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" #elif !defined(SWITCHING_TOOLHEAD_X_POS) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" - #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" #elif !defined(SWITCHING_TOOLHEAD_Y_CLEAR) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." - #elif ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - #if ENABLED(EXT_SOLENOID) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" - #elif !PIN_EXISTS(SOL0) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." - #endif + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." + #endif +#endif + +/** + * Electromagnetic Switching Toolhead requirements + */ +#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + #if ENABLED(EXT_SOLENOID) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" + #elif !PIN_EXISTS(SOL0) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." + #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." #endif #endif From 33185b090e264a923a8d2fb0687846fe100f5465 Mon Sep 17 00:00:00 2001 From: cr20-123 <66994235+cr20-123@users.noreply.github.com> Date: Sat, 26 Jun 2021 14:17:18 -0400 Subject: [PATCH 0318/2168] =?UTF-8?q?=E2=9C=A8=20Update/extend=20Quiet=20P?= =?UTF-8?q?robing=20(#22205)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 3 ++- Marlin/src/inc/Conditionals_post.h | 19 ++++++++++++++----- Marlin/src/module/probe.cpp | 3 ++- buildroot/tests/rambo | 4 ++-- 4 files changed, 20 insertions(+), 9 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5b7f439fe5..d3221f80de 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1250,7 +1250,8 @@ //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude) #endif //#define PROBING_FANS_OFF // Turn fans off when probing -//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing +//#define PROBING_ESTEPPERS_OFF // Turn all extruder steppers off when probing +//#define PROBING_STEPPERS_OFF // Turn all steppers off (unless needed to hold position) when probing (including extruders) //#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // Require minimum nozzle and/or bed temperature for probing diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index eb215c34eb..32ae0fdef4 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -3099,6 +3099,7 @@ #endif #else #undef NOZZLE_TO_PROBE_OFFSET + #undef PROBING_STEPPERS_OFF #endif /** @@ -3141,18 +3142,26 @@ /** * Heater, Fan, and Probe interactions */ -#if FAN_COUNT == 0 - #undef PROBING_FANS_OFF +#if !HAS_FAN #undef ADAPTIVE_FAN_SLOWING #undef NO_FAN_SLOWING_IN_PID_TUNING #endif - -#if HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) - #define HAS_QUIET_PROBING 1 +#if !BOTH(HAS_BED_PROBE, HAS_FAN) + #undef PROBING_FANS_OFF +#endif +#if !BOTH(HAS_BED_PROBE, HAS_EXTRUDERS) + #undef PROBING_ESTEPPERS_OFF +#endif +#if BOTH(PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF) + #undef PROBING_ESTEPPERS_OFF + #warning "PROBING_STEPPERS_OFF includes PROBING_ESTEPPERS_OFF. Disabling PROBING_ESTEPPERS_OFF." #endif #if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 #endif +#if HAS_BED_PROBE && (ANY(PROBING_HEATERS_OFF, PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) + #define HAS_QUIET_PROBING 1 +#endif /** * Advanced Pause - Filament Change diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 2b3a189884..dae25feea3 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -245,6 +245,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() void Probe::set_probing_paused(const bool dopause) { TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); + TERN_(PROBING_ESTEPPERS_OFF, if (dopause) disable_e_steppers()); #if ENABLED(PROBING_STEPPERS_OFF) IF_DISABLED(DELTA, static uint8_t old_trusted); if (dopause) { @@ -253,7 +254,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() DISABLE_AXIS_X(); DISABLE_AXIS_Y(); #endif - disable_e_steppers(); + IF_DISABLED(PROBING_ESTEPPERS_OFF, disable_e_steppers()); } else { #if DISABLED(DELTA) diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 9c56a689b0..6b87d01a5e 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -115,10 +115,10 @@ opt_set MOTHERBOARD BOARD_RAMBO \ FAN_MIN_PWM 50 FAN_KICKSTART_TIME 100 \ XY_FREQUENCY_LIMIT 15 opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ - BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY \ + BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ - FIX_MOUNTED_PROBE AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE FILAMENT_WIDTH_SENSOR PROBE_OFFSET_WIZARD \ + FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE PROBE_OFFSET_WIZARD \ Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ From d882a16b801078f2741ad1021d8be418fef71764 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 27 Jun 2021 06:28:56 +1200 Subject: [PATCH 0319/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Z=5FMULTI=5FENDS?= =?UTF-8?q?TOPS=20+=20NUM=5FZ=5FSTEPPER=5FDRIVERS=204=20compile=20(#22203)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/M666.cpp | 22 +++++++++----------- Marlin/src/module/stepper.cpp | 32 +++++++++++------------------ buildroot/tests/BIGTREE_GTR_V1_0 | 11 +++++----- 3 files changed, 28 insertions(+), 37 deletions(-) diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index a3a48cd3fc..8ff51f0e3f 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -71,29 +71,27 @@ #endif #if ENABLED(Z_MULTI_ENDSTOPS) if (parser.seenval('Z')) { - #if NUM_Z_STEPPER_DRIVERS >= 3 - const float z_adj = parser.value_linear_units(); - const int ind = parser.intval('S'); - if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj; - if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj; - #if NUM_Z_STEPPER_DRIVERS >= 4 - if (!ind || ind == 4) endstops.z4_endstop_adj = z_adj; - #endif + const float z_adj = parser.value_linear_units(); + #if NUM_Z_STEPPER_DRIVERS == 2 + endstops.z2_endstop_adj = z_adj; #else - endstops.z2_endstop_adj = parser.value_linear_units(); + const int ind = parser.intval('S'); + #define _SET_ZADJ(N) if (!ind || ind == N) endstops.z##N##_endstop_adj = z_adj; + REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _SET_ZADJ) #endif } #endif if (!parser.seen("XYZ")) { + auto echo_adj = [](PGM_P const label, const_float_t value) { SERIAL_ECHOPAIR_P(label, value); }; SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): "); #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" X2:", endstops.x2_endstop_adj); + echo_adj(PSTR(" X2:"), endstops.x2_endstop_adj); #endif #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj); + echo_adj(PSTR(" Y2:"), endstops.y2_endstop_adj); #endif #if ENABLED(Z_MULTI_ENDSTOPS) - #define _ECHO_ZADJ(N) SERIAL_ECHOPAIR(" Z" STRINGIFY(N) ":", endstops.z##N##_endstop_adj); + #define _ECHO_ZADJ(N) echo_adj(PSTR(" Z" STRINGIFY(N) ":"), endstops.z##N##_endstop_adj); REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _ECHO_ZADJ) #endif SERIAL_EOL(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 062049ec77..0ff909d7cc 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -314,26 +314,18 @@ xyze_int8_t Stepper::count_direction{0}; A##3_STEP_WRITE(V); \ } -#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (ENABLED(A##_HOME_TO_MIN)) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ - A##3_STEP_WRITE(V); \ - A##4_STEP_WRITE(V); \ +#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##_MIN, A##_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##2_MIN, A##2_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##3_MIN, A##3_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##4_MIN, A##4_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ + } \ + else { \ + A##_STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ + A##3_STEP_WRITE(V); \ + A##4_STEP_WRITE(V); \ } #define QUAD_SEPARATE_APPLY_STEP(A,V) \ diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 index 24293a4932..58cbe4a142 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0 +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -20,11 +20,12 @@ exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ - EXTRUDERS 6 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 \ - NUM_Z_STEPPER_DRIVERS 3 \ - DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0, 17.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' -opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED PID_PARAMS_PER_HOTEND -exec_test $1 $2 "BigTreeTech GTR | 6 Extruders | Triple Z" "$3" + EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 \ + NUM_Z_STEPPER_DRIVERS 4 \ + DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' +opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED \ + PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS +exec_test $1 $2 "BigTreeTech GTR | 6 Extruders | Quad Z + Endstops" "$3" restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ From ecb727c3efe58f654138147596f831c3ea97befc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 26 Jun 2021 14:01:47 -0500 Subject: [PATCH 0320/2168] =?UTF-8?q?=F0=9F=8E=A8=20Format=20onboard=5Fsd.?= =?UTF-8?q?cpp?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32F1/onboard_sd.cpp | 357 +++++++++++++------------- 1 file changed, 182 insertions(+), 175 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index 6092aea320..e26947145d 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -38,8 +38,8 @@ #define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2 #endif -#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnboardSPI cs low */ -#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnboardSPI cs high */ +#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) // Set OnboardSPI cs low +#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) // Set OnboardSPI cs high #define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX) #define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256) @@ -49,32 +49,32 @@ ---------------------------------------------------------------------------*/ /* MMC/SD command */ -#define CMD0 (0) /* GO_IDLE_STATE */ -#define CMD1 (1) /* SEND_OP_COND (MMC) */ -#define ACMD41 (0x80+41) /* SEND_OP_COND (SDC) */ -#define CMD8 (8) /* SEND_IF_COND */ -#define CMD9 (9) /* SEND_CSD */ -#define CMD10 (10) /* SEND_CID */ -#define CMD12 (12) /* STOP_TRANSMISSION */ -#define ACMD13 (0x80+13) /* SD_STATUS (SDC) */ -#define CMD16 (16) /* SET_BLOCKLEN */ -#define CMD17 (17) /* READ_SINGLE_BLOCK */ -#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ -#define CMD23 (23) /* SET_BLOCK_COUNT (MMC) */ -#define ACMD23 (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */ -#define CMD24 (24) /* WRITE_BLOCK */ -#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ -#define CMD32 (32) /* ERASE_ER_BLK_START */ -#define CMD33 (33) /* ERASE_ER_BLK_END */ -#define CMD38 (38) /* ERASE */ -#define CMD48 (48) /* READ_EXTR_SINGLE */ -#define CMD49 (49) /* WRITE_EXTR_SINGLE */ -#define CMD55 (55) /* APP_CMD */ -#define CMD58 (58) /* READ_OCR */ +#define CMD0 (0) // GO_IDLE_STATE +#define CMD1 (1) // SEND_OP_COND (MMC) +#define ACMD41 (0x80+41) // SEND_OP_COND (SDC) +#define CMD8 (8) // SEND_IF_COND +#define CMD9 (9) // SEND_CSD +#define CMD10 (10) // SEND_CID +#define CMD12 (12) // STOP_TRANSMISSION +#define ACMD13 (0x80+13) // SD_STATUS (SDC) +#define CMD16 (16) // SET_BLOCKLEN +#define CMD17 (17) // READ_SINGLE_BLOCK +#define CMD18 (18) // READ_MULTIPLE_BLOCK +#define CMD23 (23) // SET_BLOCK_COUNT (MMC) +#define ACMD23 (0x80+23) // SET_WR_BLK_ERASE_COUNT (SDC) +#define CMD24 (24) // WRITE_BLOCK +#define CMD25 (25) // WRITE_MULTIPLE_BLOCK +#define CMD32 (32) // ERASE_ER_BLK_START +#define CMD33 (33) // ERASE_ER_BLK_END +#define CMD38 (38) // ERASE +#define CMD48 (48) // READ_EXTR_SINGLE +#define CMD49 (49) // WRITE_EXTR_SINGLE +#define CMD55 (55) // APP_CMD +#define CMD58 (58) // READ_OCR -static volatile DSTATUS Stat = STA_NOINIT; /* Physical drive status */ +static volatile DSTATUS Stat = STA_NOINIT; // Physical drive status static volatile UINT timeout; -static BYTE CardType; /* Card type flags */ +static BYTE CardType; // Card type flags /*-----------------------------------------------------------------------*/ /* Send/Receive data to the MMC (Platform dependent) */ @@ -82,7 +82,7 @@ static BYTE CardType; /* Card type flags */ /* Exchange a byte */ static BYTE xchg_spi ( - BYTE dat /* Data to send */ + BYTE dat // Data to send ) { BYTE returnByte = ONBOARD_SD_SPI.transfer(dat); return returnByte; @@ -90,18 +90,18 @@ static BYTE xchg_spi ( /* Receive multiple byte */ static void rcvr_spi_multi ( - BYTE *buff, /* Pointer to data buffer */ - UINT btr /* Number of bytes to receive (16, 64 or 512) */ + BYTE *buff, // Pointer to data buffer + UINT btr // Number of bytes to receive (16, 64 or 512) ) { ONBOARD_SD_SPI.dmaTransfer(0, const_cast(buff), btr); } #if _DISKIO_WRITE - /* Send multiple bytes */ + // Send multiple bytes static void xmit_spi_multi ( - const BYTE *buff, /* Pointer to the data */ - UINT btx /* Number of bytes to send (multiple of 16) */ + const BYTE *buff, // Pointer to the data + UINT btx // Number of bytes to send (multiple of 16) ) { ONBOARD_SD_SPI.dmaSend(const_cast(buff), btx); } @@ -112,16 +112,15 @@ static void rcvr_spi_multi ( /* Wait for card ready */ /*-----------------------------------------------------------------------*/ -static int wait_ready ( /* 1:Ready, 0:Timeout */ - UINT wt /* Timeout [ms] */ +static int wait_ready ( // 1:Ready, 0:Timeout + UINT wt // Timeout [ms] ) { BYTE d; - timeout = millis() + wt; do { d = xchg_spi(0xFF); - /* This loop takes a while. Insert rot_rdq() here for multitask environment. */ - } while (d != 0xFF && (timeout > millis())); /* Wait for card goes ready or timeout */ + // This loop takes a while. Insert rot_rdq() here for multitask environment. + } while (d != 0xFF && (timeout > millis())); // Wait for card goes ready or timeout return (d == 0xFF) ? 1 : 0; } @@ -131,21 +130,21 @@ static int wait_ready ( /* 1:Ready, 0:Timeout */ /*-----------------------------------------------------------------------*/ static void deselect() { - CS_HIGH(); /* CS = H */ - xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */ + CS_HIGH(); // CS = H + xchg_spi(0xFF); // Dummy clock (force DO hi-z for multiple slave SPI) } /*-----------------------------------------------------------------------*/ /* Select card and wait for ready */ /*-----------------------------------------------------------------------*/ -static int select() { /* 1:OK, 0:Timeout */ - CS_LOW(); /* CS = L */ - xchg_spi(0xFF); /* Dummy clock (force DO enabled) */ +static int select() { // 1:OK, 0:Timeout + CS_LOW(); // CS = L + xchg_spi(0xFF); // Dummy clock (force DO enabled) - if (wait_ready(500)) return 1; /* Leading busy check: Wait for card ready */ + if (wait_ready(500)) return 1; // Leading busy check: Wait for card ready - deselect(); /* Timeout */ + deselect(); // Timeout return 0; } @@ -153,16 +152,18 @@ static int select() { /* 1:OK, 0:Timeout */ /* Control SPI module (Platform dependent) */ /*-----------------------------------------------------------------------*/ -static void power_on() { /* Enable SSP module and attach it to I/O pads */ +// Enable SSP module and attach it to I/O pads +static void sd_power_on() { ONBOARD_SD_SPI.setModule(ONBOARD_SPI_DEVICE); ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setDataMode(SPI_MODE0); - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */ + OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); // Set CS# high } -static void power_off() { /* Disable SPI function */ - select(); /* Wait for card ready */ +// Disable SPI function +static void sd_power_off() { + select(); // Wait for card ready deselect(); } @@ -170,23 +171,23 @@ static void power_off() { /* Disable SPI function */ /* Receive a data packet from the MMC */ /*-----------------------------------------------------------------------*/ -static int rcvr_datablock ( /* 1:OK, 0:Error */ - BYTE *buff, /* Data buffer */ - UINT btr /* Data block length (byte) */ +static int rcvr_datablock ( // 1:OK, 0:Error + BYTE *buff, // Data buffer + UINT btr // Data block length (byte) ) { BYTE token; timeout = millis() + 200; - do { /* Wait for DataStart token in timeout of 200ms */ + do { // Wait for DataStart token in timeout of 200ms token = xchg_spi(0xFF); - /* This loop will take a while. Insert rot_rdq() here for multitask environment. */ + // This loop will take a while. Insert rot_rdq() here for multitask environment. } while ((token == 0xFF) && (timeout > millis())); - if (token != 0xFE) return 0; /* Function fails if invalid DataStart token or timeout */ + if (token != 0xFE) return 0; // Function fails if invalid DataStart token or timeout - rcvr_spi_multi(buff, btr); /* Store trailing data to the buffer */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Discard CRC */ + rcvr_spi_multi(buff, btr); // Store trailing data to the buffer + xchg_spi(0xFF); xchg_spi(0xFF); // Discard CRC - return 1; /* Function succeeded */ + return 1; // Function succeeded } /*-----------------------------------------------------------------------*/ @@ -195,25 +196,25 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ #if _DISKIO_WRITE - static int xmit_datablock ( /* 1:OK, 0:Failed */ - const BYTE *buff, /* Ponter to 512 byte data to be sent */ - BYTE token /* Token */ + static int xmit_datablock( // 1:OK, 0:Failed + const BYTE *buff, // Pointer to 512 byte data to be sent + BYTE token // Token ) { BYTE resp; - if (!wait_ready(500)) return 0; /* Leading busy check: Wait for card ready to accept data block */ + if (!wait_ready(500)) return 0; // Leading busy check: Wait for card ready to accept data block - xchg_spi(token); /* Send token */ - if (token == 0xFD) return 1; /* Do not send data if token is StopTran */ + xchg_spi(token); // Send token + if (token == 0xFD) return 1; // Do not send data if token is StopTran - xmit_spi_multi(buff, 512); /* Data */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Dummy CRC */ + xmit_spi_multi(buff, 512); // Data + xchg_spi(0xFF); xchg_spi(0xFF); // Dummy CRC - resp = xchg_spi(0xFF); /* Receive data resp */ + resp = xchg_spi(0xFF); // Receive data resp - return (resp & 0x1F) == 0x05 ? 1 : 0; /* Data was accepted or not */ + return (resp & 0x1F) == 0x05 ? 1 : 0; // Data was accepted or not - /* Busy check is done at next transmission */ + // Busy check is done at next transmission } #endif // _DISKIO_WRITE @@ -222,43 +223,43 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ /* Send a command packet to the MMC */ /*-----------------------------------------------------------------------*/ -static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ - BYTE cmd, /* Command index */ - DWORD arg /* Argument */ +static BYTE send_cmd( // Return value: R1 resp (bit7==1:Failed to send) + BYTE cmd, // Command index + DWORD arg // Argument ) { BYTE n, res; - if (cmd & 0x80) { /* Send a CMD55 prior to ACMD */ + if (cmd & 0x80) { // Send a CMD55 prior to ACMD cmd &= 0x7F; res = send_cmd(CMD55, 0); if (res > 1) return res; } - /* Select the card and wait for ready except to stop multiple block read */ + // Select the card and wait for ready except to stop multiple block read if (cmd != CMD12) { deselect(); if (!select()) return 0xFF; } - /* Send command packet */ - xchg_spi(0x40 | cmd); /* Start + command index */ - xchg_spi((BYTE)(arg >> 24)); /* Argument[31..24] */ - xchg_spi((BYTE)(arg >> 16)); /* Argument[23..16] */ - xchg_spi((BYTE)(arg >> 8)); /* Argument[15..8] */ - xchg_spi((BYTE)arg); /* Argument[7..0] */ - n = 0x01; /* Dummy CRC + Stop */ - if (cmd == CMD0) n = 0x95; /* Valid CRC for CMD0(0) */ - if (cmd == CMD8) n = 0x87; /* Valid CRC for CMD8(0x1AA) */ + // Send command packet + xchg_spi(0x40 | cmd); // Start + command index + xchg_spi((BYTE)(arg >> 24)); // Argument[31..24] + xchg_spi((BYTE)(arg >> 16)); // Argument[23..16] + xchg_spi((BYTE)(arg >> 8)); // Argument[15..8] + xchg_spi((BYTE)arg); // Argument[7..0] + n = 0x01; // Dummy CRC + Stop + if (cmd == CMD0) n = 0x95; // Valid CRC for CMD0(0) + if (cmd == CMD8) n = 0x87; // Valid CRC for CMD8(0x1AA) xchg_spi(n); - /* Receive command resp */ - if (cmd == CMD12) xchg_spi(0xFF); /* Diacard following one byte when CMD12 */ - n = 10; /* Wait for response (10 bytes max) */ + // Receive command response + if (cmd == CMD12) xchg_spi(0xFF); // Discard the following byte when CMD12 + n = 10; // Wait for response (10 bytes max) do res = xchg_spi(0xFF); while ((res & 0x80) && --n); - return res; /* Return received response */ + return res; // Return received response } /*-------------------------------------------------------------------------- @@ -270,49 +271,52 @@ static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ /*-----------------------------------------------------------------------*/ DSTATUS disk_initialize ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { BYTE n, cmd, ty, ocr[4]; - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - power_on(); /* Initialize SPI */ + if (drv) return STA_NOINIT; // Supports only drive 0 + sd_power_on(); // Initialize SPI - if (Stat & STA_NODISK) return Stat; /* Is a card existing in the soket? */ + if (Stat & STA_NODISK) return Stat; // Is a card existing in the soket? FCLK_SLOW(); - for (n = 10; n; n--) xchg_spi(0xFF); /* Send 80 dummy clocks */ + for (n = 10; n; n--) xchg_spi(0xFF); // Send 80 dummy clocks ty = 0; - if (send_cmd(CMD0, 0) == 1) { /* Put the card SPI state */ - timeout = millis() + 1000; /* Initialization timeout = 1 sec */ - if (send_cmd(CMD8, 0x1AA) == 1) { /* Is the catd SDv2? */ - for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); /* Get 32 bit return value of R7 resp */ - if (ocr[2] == 0x01 && ocr[3] == 0xAA) { /* Does the card support 2.7-3.6V? */ - while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)) ; /* Wait for end of initialization with ACMD41(HCS) */ - if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { /* Check CCS bit in the OCR */ + if (send_cmd(CMD0, 0) == 1) { // Put the card SPI state + timeout = millis() + 1000; // Initialization timeout = 1 sec + if (send_cmd(CMD8, 0x1AA) == 1) { // Is the catd SDv2? + for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); // Get 32 bit return value of R7 resp + if (ocr[2] == 0x01 && ocr[3] == 0xAA) { // Does the card support 2.7-3.6V? + while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)); // Wait for end of initialization with ACMD41(HCS) + if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { // Check CCS bit in the OCR for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); - ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check if the card is SDv2 */ + ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; // Check if the card is SDv2 } } - } else { /* Not an SDv2 card */ - if (send_cmd(ACMD41, 0) <= 1) { /* SDv1 or MMCv3? */ - ty = CT_SD1; cmd = ACMD41; /* SDv1 (ACMD41(0)) */ - } else { - ty = CT_MMC; cmd = CMD1; /* MMCv3 (CMD1(0)) */ + } + else { // Not an SDv2 card + if (send_cmd(ACMD41, 0) <= 1) { // SDv1 or MMCv3? + ty = CT_SD1; cmd = ACMD41; // SDv1 (ACMD41(0)) } - while ((timeout > millis()) && send_cmd(cmd, 0)) ; /* Wait for the card leaves idle state */ - if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) /* Set block length: 512 */ + else { + ty = CT_MMC; cmd = CMD1; // MMCv3 (CMD1(0)) + } + while ((timeout > millis()) && send_cmd(cmd, 0)); // Wait for the card leaves idle state + if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) // Set block length: 512 ty = 0; } } - CardType = ty; /* Card type */ + CardType = ty; // Card type deselect(); - if (ty) { /* OK */ - FCLK_FAST(); /* Set fast clock */ - Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */ - } else { /* Failed */ - power_off(); + if (ty) { // OK + FCLK_FAST(); // Set fast clock + Stat &= ~STA_NOINIT; // Clear STA_NOINIT flag + } + else { // Failed + sd_power_off(); Stat = STA_NOINIT; } @@ -324,10 +328,10 @@ DSTATUS disk_initialize ( /*-----------------------------------------------------------------------*/ DSTATUS disk_status ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - return Stat; /* Return disk status */ + if (drv) return STA_NOINIT; // Supports only drive 0 + return Stat; // Return disk status } /*-----------------------------------------------------------------------*/ @@ -335,28 +339,28 @@ DSTATUS disk_status ( /*-----------------------------------------------------------------------*/ DRESULT disk_read ( - BYTE drv, /* Physical drive number (0) */ - BYTE *buff, /* Pointer to the data buffer to store read data */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to read (1..128) */ + BYTE drv, // Physical drive number (0) + BYTE *buff, // Pointer to the data buffer to store read data + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to read (1..128) ) { BYTE cmd; - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ot BA conversion (byte addressing cards) */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ot BA conversion (byte addressing cards) FCLK_FAST(); - cmd = count > 1 ? CMD18 : CMD17; /* READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK */ + cmd = count > 1 ? CMD18 : CMD17; // READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK if (send_cmd(cmd, sector) == 0) { do { if (!rcvr_datablock(buff, 512)) break; buff += 512; } while (--count); - if (cmd == CMD18) send_cmd(CMD12, 0); /* STOP_TRANSMISSION */ + if (cmd == CMD18) send_cmd(CMD12, 0); // STOP_TRANSMISSION } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } /*-----------------------------------------------------------------------*/ @@ -366,36 +370,36 @@ DRESULT disk_read ( #if _DISKIO_WRITE DRESULT disk_write( - BYTE drv, /* Physical drive number (0) */ - const BYTE *buff, /* Ponter to the data to write */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to write (1..128) */ + BYTE drv, // Physical drive number (0) + const BYTE *buff, // Pointer to the data to write + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to write (1..128) ) { - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check drive status */ - if (Stat & STA_PROTECT) return RES_WRPRT; /* Check write protect */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check drive status + if (Stat & STA_PROTECT) return RES_WRPRT; // Check write protect FCLK_FAST(); - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ==> BA conversion (byte addressing cards) */ + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ==> BA conversion (byte addressing cards) - if (count == 1) { /* Single sector write */ - if ((send_cmd(CMD24, sector) == 0) /* WRITE_BLOCK */ + if (count == 1) { // Single sector write + if ((send_cmd(CMD24, sector) == 0) // WRITE_BLOCK && xmit_datablock(buff, 0xFE)) { count = 0; } } - else { /* Multiple sector write */ - if (CardType & CT_SDC) send_cmd(ACMD23, count); /* Predefine number of sectors */ - if (send_cmd(CMD25, sector) == 0) { /* WRITE_MULTIPLE_BLOCK */ + else { // Multiple sector write + if (CardType & CT_SDC) send_cmd(ACMD23, count); // Predefine number of sectors + if (send_cmd(CMD25, sector) == 0) { // WRITE_MULTIPLE_BLOCK do { if (!xmit_datablock(buff, 0xFC)) break; buff += 512; } while (--count); - if (!xmit_datablock(0, 0xFD)) count = 1; /* STOP_TRAN token */ + if (!xmit_datablock(0, 0xFD)) count = 1; // STOP_TRAN token } } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } #endif // _DISKIO_WRITE @@ -407,9 +411,9 @@ DRESULT disk_read ( #if _DISKIO_IOCTL DRESULT disk_ioctl ( - BYTE drv, /* Physical drive number (0) */ - BYTE cmd, /* Control command code */ - void *buff /* Pointer to the conrtol data */ + BYTE drv, // Physical drive number (0) + BYTE cmd, // Control command code + void *buff // Pointer to the conrtol data ) { DRESULT res; BYTE n, csd[16], *ptr = (BYTE *)buff; @@ -420,22 +424,23 @@ DRESULT disk_read ( UINT dc; #endif - if (drv) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ + if (drv) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready res = RES_ERROR; FCLK_FAST(); switch (cmd) { - case CTRL_SYNC: /* Wait for end of internal write process of the drive */ + case CTRL_SYNC: // Wait for end of internal write process of the drive if (select()) res = RES_OK; break; - case GET_SECTOR_COUNT: /* Get drive capacity in unit of sector (DWORD) */ + case GET_SECTOR_COUNT: // Get drive capacity in unit of sector (DWORD) if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { - if ((csd[0] >> 6) == 1) { /* SDC ver 2.00 */ + if ((csd[0] >> 6) == 1) { // SDC ver 2.00 csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1; *(DWORD*)buff = csize << 10; - } else { /* SDC ver 1.XX or MMC ver 3 */ + } + else { // SDC ver 1.XX or MMC ver 3 n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2; csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1; *(DWORD*)buff = csize << (n - 9); @@ -444,21 +449,23 @@ DRESULT disk_read ( } break; - case GET_BLOCK_SIZE: /* Get erase block size in unit of sector (DWORD) */ - if (CardType & CT_SD2) { /* SDC ver 2.00 */ - if (send_cmd(ACMD13, 0) == 0) { /* Read SD status */ + case GET_BLOCK_SIZE: // Get erase block size in unit of sector (DWORD) + if (CardType & CT_SD2) { // SDC ver 2.00 + if (send_cmd(ACMD13, 0) == 0) { // Read SD status xchg_spi(0xFF); - if (rcvr_datablock(csd, 16)) { /* Read partial block */ - for (n = 64 - 16; n; n--) xchg_spi(0xFF); /* Purge trailing data */ + if (rcvr_datablock(csd, 16)) { // Read partial block + for (n = 64 - 16; n; n--) xchg_spi(0xFF); // Purge trailing data *(DWORD*)buff = 16UL << (csd[10] >> 4); res = RES_OK; } } - } else { /* SDC ver 1.XX or MMC */ - if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { /* Read CSD */ - if (CardType & CT_SD1) { /* SDC ver 1.XX */ + } + else { // SDC ver 1.XX or MMC + if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { // Read CSD + if (CardType & CT_SD1) { // SDC ver 1.XX *(DWORD*)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1); - } else { /* MMC */ + } + else { // MMC *(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1); } res = RES_OK; @@ -466,47 +473,47 @@ DRESULT disk_read ( } break; - case CTRL_TRIM: /* Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) */ - if (!(CardType & CT_SDC)) break; /* Check if the card is SDC */ - if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; /* Get CSD */ - if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; /* Check if sector erase can be applied to the card */ - dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; /* Load sector block */ + case CTRL_TRIM: // Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) + if (!(CardType & CT_SDC)) break; // Check if the card is SDC + if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; // Get CSD + if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; // Check if sector erase can be applied to the card + dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; // Load sector block if (!(CardType & CT_BLOCK)) { st *= 512; ed *= 512; } - if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { /* Erase sector block */ - res = RES_OK; /* FatFs does not check result of this command */ + if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { // Erase sector block + res = RES_OK; // FatFs does not check result of this command } break; - /* Following commands are never used by FatFs module */ + // The following commands are never used by FatFs module - case MMC_GET_TYPE: /* Get MMC/SDC type (BYTE) */ + case MMC_GET_TYPE: // Get MMC/SDC type (BYTE) *ptr = CardType; res = RES_OK; break; - case MMC_GET_CSD: /* Read CSD (16 bytes) */ - if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CSD */ + case MMC_GET_CSD: // Read CSD (16 bytes) + if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_CID: /* Read CID (16 bytes) */ - if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CID */ + case MMC_GET_CID: // Read CID (16 bytes) + if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_OCR: /* Read OCR (4 bytes) */ - if (send_cmd(CMD58, 0) == 0) { /* READ_OCR */ + case MMC_GET_OCR: // Read OCR (4 bytes) + if (send_cmd(CMD58, 0) == 0) { for (n = 4; n; n--) *ptr++ = xchg_spi(0xFF); res = RES_OK; } break; - case MMC_GET_SDSTAT: /* Read SD status (64 bytes) */ - if (send_cmd(ACMD13, 0) == 0) { /* SD_STATUS */ + case MMC_GET_SDSTAT: // Read SD status (64 bytes) + if (send_cmd(ACMD13, 0) == 0) { xchg_spi(0xFF); if (rcvr_datablock(ptr, 64)) res = RES_OK; } From a789cb4fb6302980e24209e040ba92aaf6267fe9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 26 Jun 2021 14:28:50 -0500 Subject: [PATCH 0321/2168] =?UTF-8?q?=F0=9F=8E=A8=20Small=20tweak,=20ms=20?= =?UTF-8?q?=3D>=20now?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/power.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index e7d33bec49..ae85237c54 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -109,12 +109,12 @@ bool Power::is_power_needed() { void Power::check() { static millis_t nextPowerCheck = 0; - millis_t ms = millis(); - if (ELAPSED(ms, nextPowerCheck)) { - nextPowerCheck = ms + 2500UL; + millis_t now = millis(); + if (ELAPSED(now, nextPowerCheck)) { + nextPowerCheck = now + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) power_off(); } } From 761d7b77d85496694bc826f31ced9715e5add8fb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 27 Jun 2021 01:03:53 +0000 Subject: [PATCH 0322/2168] [cron] Bump distribution date (2021-06-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 82ae1fafa8..b6cf60f27f 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 "2021-06-26" + #define STRING_DISTRIBUTION_DATE "2021-06-27" #endif /** From f9051e5469cdd99bcb93bc46124e95984c279984 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 27 Jun 2021 00:33:44 -0500 Subject: [PATCH 0323/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20statu?= =?UTF-8?q?s=20screen=20timeout?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 11 +++++-- .../ftdi_eve_touch_ui/generic/base_screen.cpp | 10 +++--- .../ftdi_eve_touch_ui/generic/base_screen.h | 2 +- Marlin/src/lcd/marlinui.cpp | 24 +++++--------- Marlin/src/lcd/marlinui.h | 33 +++++++++++-------- Marlin/src/lcd/menu/menu.cpp | 20 ++++++----- Marlin/src/lcd/menu/menu_item.h | 4 +-- Marlin/src/lcd/menu/menu_password.cpp | 2 +- Marlin/src/lcd/tft/touch.cpp | 4 +-- 9 files changed, 56 insertions(+), 54 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 32ae0fdef4..45271bca72 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -3397,9 +3397,14 @@ #endif #endif -// LCD timeout to status screen default is 15s -#ifndef LCD_TIMEOUT_TO_STATUS - #define LCD_TIMEOUT_TO_STATUS 15000 +#if HAS_LCD_MENU + // LCD timeout to status screen default is 15s + #ifndef LCD_TIMEOUT_TO_STATUS + #define LCD_TIMEOUT_TO_STATUS 15000 + #endif + #if LCD_TIMEOUT_TO_STATUS + #define SCREENS_CAN_TIME_OUT 1 + #endif #endif // Add commands that need sub-codes to this list diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp index 3981a37042..0a8bebea3c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp @@ -45,7 +45,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -65,7 +65,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -77,12 +77,10 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #if LCD_TIMEOUT_TO_STATUS > 0 - last_interaction = millis(); - #endif + TERN_(SCREENS_CAN_TIME_OUT, last_interaction = millis()); } -#if LCD_TIMEOUT_TO_STATUS > 0 +#if SCREENS_CAN_TIME_OUT uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h index cbeea1f750..030fa51a2a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h @@ -27,7 +27,7 @@ class BaseScreen : public UIScreen { protected: - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT static uint32_t last_interaction; #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 08b214ac56..67e5adc0f0 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -165,8 +165,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif #endif -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 +#if SCREENS_CAN_TIME_OUT bool MarlinUI::defer_return_to_status; + millis_t MarlinUI::return_to_status_ms = 0; #endif uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed @@ -815,9 +816,6 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; millis_t next_lcd_update_ms; -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS - millis_t MarlinUI::return_to_status_ms = 0; -#endif inline bool can_encode() { return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) @@ -828,12 +826,6 @@ void MarlinUI::update() { static uint16_t max_display_update_time = 0; millis_t ms = millis(); - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - #define RESET_STATUS_TIMEOUT() (return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS) - #else - #define RESET_STATUS_TIMEOUT() NOOP - #endif - #ifdef LED_BACKLIGHT_TIMEOUT leds.update_timeout(powersupply_on); #endif @@ -859,7 +851,7 @@ void MarlinUI::update() { #if HAS_TOUCH_BUTTONS if (touch_buttons) { - RESET_STATUS_TIMEOUT(); + reset_status_timeout(ms); if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority if (ELAPSED(ms, next_button_update_ms)) { encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; @@ -914,7 +906,7 @@ void MarlinUI::update() { TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context if (TERN0(IS_RRW_KEYPAD, handle_keypad())) - RESET_STATUS_TIMEOUT(); + reset_status_timeout(ms); uint8_t abs_diff = ABS(encoderDiff); @@ -980,7 +972,7 @@ void MarlinUI::update() { encoderDiff = 0; } - RESET_STATUS_TIMEOUT(); + reset_status_timeout(ms); refresh(LCDVIEW_REDRAW_NOW); @@ -1006,7 +998,7 @@ void MarlinUI::update() { lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; refresh(LCDVIEW_REDRAW_NOW); - RESET_STATUS_TIMEOUT(); + reset_status_timeout(ms); } #endif @@ -1075,10 +1067,10 @@ void MarlinUI::update() { NOLESS(max_display_update_time, millis() - ms); } - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT // Return to Status Screen after a timeout if (on_status_screen() || defer_return_to_status) - RESET_STATUS_TIMEOUT(); + reset_status_timeout(ms); else if (ELAPSED(ms, return_to_status_ms)) return_to_status(); #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index fa2b09b873..87ecc48366 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -449,10 +449,13 @@ public: static PGM_P get_preheat_label(const uint8_t m); #endif + #if SCREENS_CAN_TIME_OUT + static inline void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } + #else + static inline void reset_status_timeout(const millis_t) {} + #endif + #if HAS_LCD_MENU - #if LCD_TIMEOUT_TO_STATUS - static millis_t return_to_status_ms; - #endif #if HAS_TOUCH_BUTTONS static uint8_t touch_buttons; @@ -483,7 +486,7 @@ public: static screenFunc_t currentScreen; static bool screen_changed; static void goto_screen(const screenFunc_t screen, const uint16_t encoder=0, const uint8_t top=0, const uint8_t items=0); - static void save_previous_screen(); + static void push_current_screen(); // goto_previous_screen and go_back may also be used as menu item callbacks static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); @@ -498,12 +501,12 @@ public: static void lcd_in_status(const bool inStatus); #endif + FORCE_INLINE static bool screen_is_sticky() { + return TERN1(SCREENS_CAN_TIME_OUT, defer_return_to_status); + } + FORCE_INLINE static void defer_status_screen(const bool defer=true) { - #if LCD_TIMEOUT_TO_STATUS > 0 - defer_return_to_status = defer; - #else - UNUSED(defer); - #endif + TERN(SCREENS_CAN_TIME_OUT, defer_return_to_status = defer, UNUSED(defer)); } static inline void goto_previous_screen_no_defer() { @@ -655,16 +658,18 @@ public: private: + #if SCREENS_CAN_TIME_OUT + static millis_t return_to_status_ms; + static bool defer_return_to_status; + #else + static constexpr bool defer_return_to_status = false; + #endif + #if HAS_STATUS_MESSAGE static void finish_status(const bool persist); #endif #if HAS_WIRED_LCD - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - static bool defer_return_to_status; - #else - static constexpr bool defer_return_to_status = false; - #endif static void draw_status_screen(); #if HAS_GRAPHICAL_TFT static void tft_idle(); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 6143e8da1e..01c8bb80c0 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -50,9 +50,12 @@ int8_t encoderTopLine, encoderLine, screen_items; typedef struct { - screenFunc_t menu_function; - uint32_t encoder_position; - int8_t top_line, items; + screenFunc_t menu_function; // The screen's function + uint32_t encoder_position; // The position of the encoder + int8_t top_line, items; // The amount of scroll, and the number of items + #if SCREENS_CAN_TIME_OUT + bool sticky; // The screen is sticky + #endif } menuPosition; menuPosition screen_history[6]; uint8_t screen_history_depth = 0; @@ -75,9 +78,9 @@ bool MenuEditItemBase::liveEdit; void MarlinUI::return_to_status() { goto_screen(status_screen); } -void MarlinUI::save_previous_screen() { +void MarlinUI::push_current_screen() { if (screen_history_depth < COUNT(screen_history)) - screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items }; + screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items OPTARG(SCREENS_CAN_TIME_OUT, screen_is_sticky()) }; } void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back/*=false*/)) { @@ -90,6 +93,7 @@ void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_b is_back ? 0 : sh.top_line, sh.items ); + defer_status_screen(TERN_(SCREENS_CAN_TIME_OUT, sh.sticky)); } else return_to_status(); @@ -147,7 +151,7 @@ void MenuEditItemBase::goto_edit_screen( ) { TERN_(HAS_TOUCH_BUTTONS, ui.on_edit_screen = true); ui.screen_changed = true; - ui.save_previous_screen(); + ui.push_current_screen(); ui.refresh(); editLabel = el; editValue = ev; @@ -237,7 +241,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { static PGM_P sync_message = msg ?: GET_TEXT(MSG_MOVING); - save_previous_screen(); + push_current_screen(); goto_screen([]{ if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); }); @@ -371,6 +375,7 @@ void MenuItem_confirm::select_screen( selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ ) { + ui.defer_status_screen(); const bool ui_selection = ui.update_selection(), got_click = ui.use_click(); if (got_click || ui.should_draw()) { draw_select_screen(yes, no, ui_selection, pref, string, suff); @@ -378,7 +383,6 @@ void MenuItem_confirm::select_screen( selectFunc_t callFunc = ui_selection ? yesFunc : noFunc; if (callFunc) callFunc(); else ui.goto_previous_screen(); } - ui.defer_status_screen(); } } diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index bcd93e11f8..0f2bd3cb1f 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -39,7 +39,7 @@ class MenuItem_submenu : public MenuItemBase { FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]); } - static inline void action(PGM_P const, const screenFunc_t func) { ui.save_previous_screen(); ui.goto_screen(func); } + static inline void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } }; // Any menu item that invokes an immediate action @@ -406,7 +406,7 @@ class MenuItem_bool : public MenuEditItemBase { #define _CONFIRM_ITEM_INNER_P(PLABEL, V...) do { \ if (encoderLine == _thisItemNr && ui.use_click()) { \ - ui.save_previous_screen(); \ + ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index 590ce48d59..d3a35abff2 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -177,7 +177,7 @@ void Password::menu_password() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_CHANGE_PASSWORD, screen_set_password); - ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.save_previous_screen(); remove_password(); } ); + ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.push_current_screen(); remove_password(); } ); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 3d4e0a40e1..64dfaa5755 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -93,9 +93,7 @@ void Touch::idle() { } #endif - #if LCD_TIMEOUT_TO_STATUS - ui.return_to_status_ms = last_touch_ms + LCD_TIMEOUT_TO_STATUS; - #endif + ui.reset_status_timeout(last_touch_ms); if (touch_time) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) From d32feb7cd50a2805d32ddf8f2fa3fcc4f981fdbc Mon Sep 17 00:00:00 2001 From: Cytown Date: Mon, 28 Jun 2021 01:39:09 +0800 Subject: [PATCH 0324/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20wide=20glyph=20c?= =?UTF-8?q?haracters=20display=20(#22237)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 24 ++++++++++++------------ Marlin/src/lcd/lcdprint.cpp | 20 +++++++++++++++++++- Marlin/src/lcd/lcdprint.h | 2 ++ 3 files changed, 33 insertions(+), 13 deletions(-) diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 97006dac25..726eb2cc39 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -369,13 +369,12 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { if (mark_as_selected(row, style & SS_INVERT)) { - pixel_len_t n = LCD_PIXEL_WIDTH; // pixel width of string allowed - - const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, - vlen = vstr ? utf8_strlen(vstr) : 0; + + const int plen = pstr ? calculateWidth(pstr) : 0, + vlen = vstr ? utf8_strlen(vstr) : 0; if (style & SS_CENTER) { - int8_t pad = (LCD_WIDTH - plen - vlen) / 2; + int pad = (LCD_PIXEL_WIDTH - plen - vlen * MENU_FONT_WIDTH) / MENU_FONT_WIDTH / 2; while (--pad >= 0) n -= lcd_put_wchar(' '); } @@ -400,8 +399,9 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (mark_as_selected(row, sel)) { const uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen((char*)inStr)), pixelwidth = (pgm ? uxg_GetUtf8StrPixelWidthP(u8g.getU8g(), inStr) : uxg_GetUtf8StrPixelWidth(u8g.getU8g(), (char*)inStr)); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; - pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen) * (MENU_FONT_WIDTH); + pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen * prop) * (MENU_FONT_WIDTH); if (vallen) { lcd_put_wchar(':'); while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); @@ -414,15 +414,16 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { ui.encoder_direction_normal(); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; const u8g_uint_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); - bool extra_row = labellen > LCD_WIDTH - 2 - vallen; + bool extra_row = labellen * prop > LCD_WIDTH - 2 - vallen * prop; #if ENABLED(USE_BIG_EDIT_FONT) // Use the menu font if the label won't fit on a single line constexpr u8g_uint_t lcd_edit_width = (LCD_PIXEL_WIDTH) / (EDIT_FONT_WIDTH); u8g_uint_t lcd_chr_fit, one_chr_width; - if (labellen <= lcd_edit_width - 1) { - if (labellen + vallen + 1 > lcd_edit_width) extra_row = true; + if (labellen * prop <= lcd_edit_width - 1) { + if (labellen * prop + vallen * prop + 1 > lcd_edit_width) extra_row = true; lcd_chr_fit = lcd_edit_width + 1; one_chr_width = EDIT_FONT_WIDTH; ui.set_font(FONT_EDIT); @@ -454,7 +455,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline); } if (onpage) { - lcd_put_wchar(((lcd_chr_fit - 1) - (vallen + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space + lcd_put_wchar(((lcd_chr_fit - 1) - (vallen * prop + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space lcd_put_u8str(value); } } @@ -478,8 +479,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { ui.draw_select_screen_prompt(pref, string, suff); draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno); - const u8g_uint_t xpos = (LCD_WIDTH) / (USE_WIDE_GLYPH ? 2 : 1); - draw_boxed_string(xpos - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno); + draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) * (USE_WIDE_GLYPH ? 2 : 1) + 1), LCD_HEIGHT - 1, yes, yesno); } #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 32f425168f..c421ef1a03 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -41,6 +41,7 @@ * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) */ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { + const uint8_t prop = USE_WIDE_GLYPH ? 2 : 1; uint8_t *p = (uint8_t*)pstr; int8_t n = maxlen; while (n > 0) { @@ -73,10 +74,27 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i } else { lcd_put_wchar(ch); - n--; + n -= ch > 255 ? prop : 1; } } return n; } +// Calculate UTF8 width with a simple check +int calculateWidth(PGM_P const pstr) { + if (!USE_WIDE_GLYPH) return utf8_strlen_P(pstr) * MENU_FONT_WIDTH; + const uint8_t prop = 2; + uint8_t *p = (uint8_t*)pstr; + int n = 0; + + do { + wchar_t ch; + p = get_utf8_value_cb(p, read_byte_rom, &ch); + if (!ch) break; + n += (ch > 255) ? prop : 1; + } while (1); + + return n * MENU_FONT_WIDTH; +} + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index fe856535b0..105a66085f 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -172,3 +172,5 @@ inline int lcd_put_wchar(const lcd_uint_t col, const lcd_uint_t row, const wchar lcd_moveto(col, row); return lcd_put_wchar(c); } + +int calculateWidth(PGM_P const pstr); From 81ca2dd273358a0cfc0f65d5b4900d83abc96d69 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9bastien=20Gari=C3=A9py?= <46988275+BeePerNet@users.noreply.github.com> Date: Sun, 27 Jun 2021 17:44:49 -0400 Subject: [PATCH 0325/2168] =?UTF-8?q?=F0=9F=8C=90=20MSG=5FMOVE=5F100MM=20(?= =?UTF-8?q?#22242)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_an.h | 1 + Marlin/src/lcd/language/language_bg.h | 1 + Marlin/src/lcd/language/language_ca.h | 1 + Marlin/src/lcd/language/language_cz.h | 1 + Marlin/src/lcd/language/language_da.h | 1 + Marlin/src/lcd/language/language_de.h | 7 ++++--- Marlin/src/lcd/language/language_el.h | 1 + Marlin/src/lcd/language/language_el_gr.h | 1 + Marlin/src/lcd/language/language_es.h | 1 + Marlin/src/lcd/language/language_eu.h | 1 + Marlin/src/lcd/language/language_fi.h | 1 + Marlin/src/lcd/language/language_fr.h | 1 + Marlin/src/lcd/language/language_gl.h | 1 + Marlin/src/lcd/language/language_hr.h | 1 + Marlin/src/lcd/language/language_hu.h | 1 + Marlin/src/lcd/language/language_jp_kana.h | 1 + Marlin/src/lcd/language/language_nl.h | 1 + Marlin/src/lcd/language/language_pl.h | 1 + Marlin/src/lcd/language/language_pt.h | 1 + Marlin/src/lcd/language/language_pt_br.h | 1 + Marlin/src/lcd/language/language_ro.h | 1 + Marlin/src/lcd/language/language_sk.h | 1 + Marlin/src/lcd/language/language_sv.h | 1 + Marlin/src/lcd/language/language_tr.h | 1 + Marlin/src/lcd/language/language_vi.h | 1 + Marlin/src/lcd/language/language_zh_CN.h | 1 + Marlin/src/lcd/language/language_zh_TW.h | 7 ++++--- 27 files changed, 33 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 0513de7f7d..787096994f 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -89,6 +89,7 @@ namespace Language_an { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 5964652156..0d4291b835 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -79,6 +79,7 @@ namespace Language_bg { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Премести с 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Премести с 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Премести с 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорост"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Дюза"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 6709a0ce55..f97a783d01 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -89,6 +89,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mou 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mou 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mou 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocitat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Llit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index c434f5493b..ab2aaa943f 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -241,6 +241,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunout o 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Rychlost"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 9258812843..95c2573ae1 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -79,6 +79,7 @@ namespace Language_da { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flyt 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flyt 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flyt 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Plade Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dyse"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index ebc2445b11..7e40d42665 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -231,9 +231,10 @@ namespace Language_de { PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Bewege Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT(" %s mm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10,0 mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10,0 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100,0 mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Geschw."); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bett Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index ebe27fecbd..b69b4695d3 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -87,6 +87,7 @@ namespace Language_el { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Επ. Εκτύπωσης Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index e6909ad5bf..208d7c2363 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -88,6 +88,7 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Κλίνη Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index b2d83aa05b..f342732161 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -236,6 +236,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidad"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 1c1c9e423d..2be6f399d8 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -143,6 +143,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mugitu 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Abiadura"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Ohea"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Pita"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 9954f1dd8a..0d3b97cc44 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -76,6 +76,7 @@ namespace Language_fi { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Liikuta 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Nopeus"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Suutin"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Suutin ~"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index bdd91d3b29..5dbec298d4 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -235,6 +235,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Vitesse"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Lit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Buse"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 5745ce1eb8..3eec75e138 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -233,6 +233,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 1684ad0e1b..e4cbdaed6c 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -83,6 +83,7 @@ namespace Language_hr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Miči 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Miči 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Miči 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Brzina"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dizna"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index f29a7b76b9..0c73d9a85a 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -266,6 +266,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.001mm"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.01mm"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 0.1mm"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index e0028e22a2..61740e3b40 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -98,6 +98,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT(" 100mm イドウ"); // "Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("ソクド"); // "Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("Zオフセット"); // "Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("ノズル"); // "Nozzle" diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 82e5c292c6..1eef4ca424 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -91,6 +91,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Verplaats 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Snelheid"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 7b4733b7ba..fee627b2fe 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -270,6 +270,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Przesuń co 100 mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 60b0c55056..4bec74558e 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -85,6 +85,7 @@ namespace Language_pt { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Bico"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 642a7d9203..88135f5e28 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -218,6 +218,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bocal"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index a34717acb5..9313adf3f6 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -232,6 +232,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 4b3ce5aa96..96f1bc7ee5 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -272,6 +272,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunúť o 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 722443fb21..f7b0f06769 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -260,6 +260,7 @@ namespace Language_sv { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flytta 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flytta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flytta 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Flytta 0.001tum"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Flytta 0.01tum"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Flytta 0.1tum"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 9d711ff376..6858616b4d 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -235,6 +235,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hız"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Mesafesi"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozul"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index f0b7f732ed..825666d1e1 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -205,6 +205,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Di chuyển 10mm"); // Move 10mm + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Di chuyển 100mm"); // Move 100mm PROGMEM Language_Str MSG_SPEED = _UxGT("Tốc độ"); // Speed PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Bàn"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 98f7704efc..39093a7c6c 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -230,6 +230,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移动 0.1 mm"); //"Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移动 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); //"Nozzle" 噴嘴 diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 0ada34a476..2061a66ad8 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -223,11 +223,12 @@ namespace Language_zh_TW { 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("擠出機 *"); //"Extruder *" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" PROGMEM Language_Str MSG_MOVE_N_MM = _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" + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); //"Nozzle" 噴嘴 From f66a771e718378f056b1ea2d9eeb3438fa07af66 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 28 Jun 2021 00:58:55 +0000 Subject: [PATCH 0326/2168] [cron] Bump distribution date (2021-06-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b6cf60f27f..77330b82e2 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 "2021-06-27" + #define STRING_DISTRIBUTION_DATE "2021-06-28" #endif /** From 1f6768a87e70d24464cc365413e47111b291914e Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 27 Jun 2021 21:02:11 -0700 Subject: [PATCH 0327/2168] =?UTF-8?q?=F0=9F=90=9B=20No=20HOTEND=5FLOOP=20w?= =?UTF-8?q?ith=20EXTRUDERS=200=20(#22245)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/power.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index ae85237c54..519b2308d0 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -85,7 +85,10 @@ bool Power::is_power_needed() { #endif ) return true; - HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #if HAS_HOTEND + HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #endif + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; #if HAS_HOTEND && AUTO_POWER_E_TEMP From 7888584fecf0a2827d9f3af10ccd5cc642784674 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 27 Jun 2021 22:30:11 -0700 Subject: [PATCH 0328/2168] =?UTF-8?q?=F0=9F=90=9B=20Use=20setTargetHotend?= =?UTF-8?q?=20in=20menus=20(#22247)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu.h | 17 +++++++++-------- Marlin/src/lcd/menu/menu_temperature.cpp | 9 ++++++--- 2 files changed, 15 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 290832c49c..28d377da0c 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -132,14 +132,15 @@ class MenuItem_confirm : public MenuItemBase { // The Menu Edit shadow value typedef union { - bool state; - float decimal; - int8_t int8; - int16_t int16; - int32_t int32; - uint8_t uint8; - uint16_t uint16; - uint32_t uint32; + bool state; + float decimal; + int8_t int8; + int16_t int16; + int32_t int32; + uint8_t uint8; + uint16_t uint16; + uint32_t uint32; + celsius_t celsius; } chimera_t; extern chimera_t editable; diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 96e6ee5f8e..65cef5b76d 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -169,10 +169,13 @@ void menu_temperature() { // Nozzle [1-5]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); + editable.celsius = thermalManager.temp_hotend[0].target; + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &editable.celsius, 0, thermalManager.hotend_max_target(0), []{ thermalManager.setTargetHotend(editable.celsius, 0); }); #elif HAS_MULTI_HOTEND - HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.hotend_max_target(e), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + HOTEND_LOOP() { + editable.celsius = thermalManager.temp_hotend[e].target; + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &editable.celsius, 0, thermalManager.hotend_max_target(e), []{ thermalManager.setTargetHotend(editable.celsius, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) From ff12ea4ab1e4e25bfd17c96e8e6843bd13c4ef3b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 28 Jun 2021 01:36:55 -0500 Subject: [PATCH 0329/2168] =?UTF-8?q?=F0=9F=94=96=20Update=20configuration?= =?UTF-8?q?s=20version?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/Version.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d3221f80de..6fc4a7cd4c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,7 +35,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02000900 +#define CONFIGURATION_H_VERSION 02000901 //=========================================================================== //============================= Getting Started ============================= diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index a13df514b0..818edecea2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -30,7 +30,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 02000900 +#define CONFIGURATION_ADV_H_VERSION 02000901 //=========================================================================== //============================= Thermal Settings ============================ diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 77330b82e2..196236d71a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02000900 +#define MARLIN_HEX_VERSION 02000901 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif From e00407d820be5e14c3546a992e07bac7fbb0c048 Mon Sep 17 00:00:00 2001 From: tome9111991 <57866234+tome9111991@users.noreply.github.com> Date: Mon, 28 Jun 2021 19:08:37 +0200 Subject: [PATCH 0330/2168] =?UTF-8?q?=E2=9C=A8=20Ender-3=20V2=20Display=20?= =?UTF-8?q?for=20SKR=20E3=20Turbo=20(#22229)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 1e7b3f02a2..4719dd8111 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -201,7 +201,15 @@ #define EXP1_09_PIN P0_16 #define EXP1_10_PIN P2_08 -#if HAS_WIRED_LCD +#if ENABLED(DWIN_CREALITY_LCD) + #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16, and LCD_SERIAL_PORT 1. Comment out this line to continue." + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_06_PIN + +#elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) From 93c2f9607e08443dca8ebbe19e8ca59f8de6d17a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 29 Jun 2021 00:54:53 +0000 Subject: [PATCH 0331/2168] [cron] Bump distribution date (2021-06-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 196236d71a..fdd672ec0e 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 "2021-06-28" + #define STRING_DISTRIBUTION_DATE "2021-06-29" #endif /** From c15d9e5b423cc35f2737439c2a08aba9d0a09108 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Mon, 28 Jun 2021 18:43:05 -0700 Subject: [PATCH 0332/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20PTC/BTC=20whole?= =?UTF-8?q?=20number=20tests=20(#22255)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 224729d35f..7524259f60 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -593,24 +593,29 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #ifdef PTC_SAMPLE_START - constexpr int _ptc_sample_start = PTC_SAMPLE_START; - static_assert(_test_ptc_sample_start != PTC_SAMPLE_START, "PTC_SAMPLE_START must be a whole number."); + constexpr auto _ptc_sample_start = PTC_SAMPLE_START; + constexpr decltype(_ptc_sample_start) _test_ptc_sample_start = 12.3f; + static_assert(_test_ptc_sample_start != 12.3f, "PTC_SAMPLE_START must be a whole number."); #endif #ifdef PTC_SAMPLE_RES - constexpr int _ptc_sample_res = PTC_SAMPLE_END; - static_assert(_test_ptc_sample_res != PTC_SAMPLE_END, "PTC_SAMPLE_RES must be a whole number."); + constexpr auto _ptc_sample_res = PTC_SAMPLE_RES; + constexpr decltype(_ptc_sample_res) _test_ptc_sample_res = 12.3f; + static_assert(_test_ptc_sample_res != 12.3f, "PTC_SAMPLE_RES must be a whole number."); #endif #ifdef BTC_SAMPLE_START - constexpr int _btc_sample_start = BTC_SAMPLE_START; - static_assert(_test_btc_sample_start != BTC_SAMPLE_START, "BTC_SAMPLE_START must be a whole number."); + constexpr auto _btc_sample_start = BTC_SAMPLE_START; + constexpr decltype(_btc_sample_start) _test_btc_sample_start = 12.3f; + static_assert(_test_btc_sample_start != 12.3f, "BTC_SAMPLE_START must be a whole number."); #endif #ifdef BTC_SAMPLE_RES - constexpr int _btc_sample_res = BTC_SAMPLE_END; - static_assert(_test_btc_sample_res != BTC_SAMPLE_END, "BTC_SAMPLE_RES must be a whole number."); + constexpr _btc_sample_res = BTC_SAMPLE_RES; + constexpr decltype(_btc_sample_res) _test_btc_sample_res = 12.3f; + static_assert(_test_btc_sample_res != 12.3f, "BTC_SAMPLE_RES must be a whole number."); #endif #ifdef BTC_PROBE_TEMP - constexpr int _btc_probe_temp = BTC_PROBE_TEMP; - static_assert(_test_btc_probe_temp != BTC_PROBE_TEMP, "BTC_PROBE_TEMP must be a whole number."); + constexpr auto _btc_probe_temp = BTC_PROBE_TEMP; + constexpr decltype(_btc_probe_temp) _test_btc_probe_temp = 12.3f; + static_assert(_test_btc_probe_temp != 12.3f, "BTC_PROBE_TEMP must be a whole number."); #endif #endif From a5b2498de9590a19aeeea4cebc46bc204195012e Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Tue, 29 Jun 2021 10:30:55 -0700 Subject: [PATCH 0333/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20ExtUI=20'lcd=5Fc?= =?UTF-8?q?licked'=20definition=20(#22257)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 2142 +++++++++++++++++------------------ 1 file changed, 1071 insertions(+), 1071 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 67e5adc0f0..6741de3e40 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -120,1169 +120,1169 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif -#if HAS_WIRED_LCD - -#if HAS_MARLINUI_U8GLIB - #include "dogm/marlinui_DOGM.h" -#endif - -#include "lcdprint.h" - -#include "../sd/cardreader.h" - -#include "../module/temperature.h" -#include "../module/planner.h" -#include "../module/motion.h" - -#if HAS_LCD_MENU - #include "../module/settings.h" -#endif - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../feature/bedlevel/bedlevel.h" -#endif - -#if HAS_TRINAMIC_CONFIG - #include "../feature/tmc_util.h" -#endif - -#if HAS_ADC_BUTTONS - #include "../module/thermistor/thermistors.h" -#endif - -#if HAS_POWER_MONITOR - #include "../feature/power_monitor.h" -#endif - -#if HAS_ENCODER_ACTION - volatile uint8_t MarlinUI::buttons; - #if HAS_SLOW_BUTTONS - volatile uint8_t MarlinUI::slow_buttons; - #endif - #if HAS_TOUCH_BUTTONS - #include "touch/touch_buttons.h" - bool MarlinUI::on_edit_screen = false; - #endif -#endif - -#if SCREENS_CAN_TIME_OUT - bool MarlinUI::defer_return_to_status; - millis_t MarlinUI::return_to_status_ms = 0; -#endif - -uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed - -#if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - millis_t MarlinUI::next_filament_display; // = 0 -#endif - -millis_t MarlinUI::next_button_update_ms; // = 0 - -#if HAS_MARLINUI_U8GLIB - bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false -#endif - -// Encoder Handling -#if HAS_ENCODER_ACTION - uint32_t MarlinUI::encoderPosition; - volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update -#endif - -#if ENABLED(SDSUPPORT) - - #include "../sd/cardreader.h" - - #if MARLINUI_SCROLL_NAME - uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; - #endif - - const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { - const char *outstr = theCard.longest_filename(); - if (theCard.longFilename[0]) { - #if MARLINUI_SCROLL_NAME - if (doScroll) { - for (uint8_t l = FILENAME_LENGTH; l--;) - hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor - static uint8_t filename_scroll_hash; - if (filename_scroll_hash != hash) { // If the hash changed... - filename_scroll_hash = hash; // Save the new hash - filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit - filename_scroll_pos = 0; // Reset scroll to the start - lcd_status_update_delay = 8; // Don't scroll right away - } - // Advance byte position corresponding to filename_scroll_pos char position - outstr += TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(outstr, filename_scroll_pos), filename_scroll_pos); - } - #else - theCard.longFilename[ - TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(theCard.longFilename, maxlen), maxlen) - ] = '\0'; // cutoff at screen edge - #endif - } - return outstr; - } - -#endif - #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) bool MarlinUI::lcd_clicked; #endif -#if HAS_LCD_MENU - #include "menu/menu.h" +#if HAS_WIRED_LCD - screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR - bool MarlinUI::screen_changed; - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - bool MarlinUI::encoderRateMultiplierEnabled; - millis_t MarlinUI::lastEncoderMovementMillis = 0; - void MarlinUI::enable_encoder_multiplier(const bool onoff) { - encoderRateMultiplierEnabled = onoff; - lastEncoderMovementMillis = 0; - } + #if HAS_MARLINUI_U8GLIB + #include "dogm/marlinui_DOGM.h" #endif - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) - int8_t MarlinUI::encoderDirection = ENCODERBASE; + #include "lcdprint.h" + + #include "../sd/cardreader.h" + + #include "../module/temperature.h" + #include "../module/planner.h" + #include "../module/motion.h" + + #if HAS_LCD_MENU + #include "../module/settings.h" #endif - #if HAS_TOUCH_BUTTONS - uint8_t MarlinUI::touch_buttons; - uint8_t MarlinUI::repeat_delay; + #if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../feature/bedlevel/bedlevel.h" #endif - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) - - bool MarlinUI::external_control; // = false - - void MarlinUI::wait_for_release() { - while (button_pressed()) safe_delay(50); - safe_delay(50); - } - + #if HAS_TRINAMIC_CONFIG + #include "../feature/tmc_util.h" #endif - #if !HAS_GRAPHICAL_TFT + #if HAS_ADC_BUTTONS + #include "../module/thermistor/thermistors.h" + #endif - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { - SETCURSOR(col, row); - if (!string) return; + #if HAS_POWER_MONITOR + #include "../feature/power_monitor.h" + #endif - auto _newline = [&col, &row]{ - col = 0; row++; // Move col to string len (plus space) - SETCURSOR(0, row); // Simulate carriage return - }; + #if HAS_ENCODER_ACTION + volatile uint8_t MarlinUI::buttons; + #if HAS_SLOW_BUTTONS + volatile uint8_t MarlinUI::slow_buttons; + #endif + #if HAS_TOUCH_BUTTONS + #include "touch/touch_buttons.h" + bool MarlinUI::on_edit_screen = false; + #endif + #endif - uint8_t *p = (uint8_t*)string; - wchar_t ch; - if (wordwrap) { - uint8_t *wrd = nullptr, c = 0; - // find the end of the part - for (;;) { - if (!wrd) wrd = p; // Get word start /before/ advancing - p = get_utf8_value_cb(p, cb_read_byte, &ch); - const bool eol = !ch; // zero ends the string - // End or a break between phrases? - if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { - if (!c && ch == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces - // Past the right and the word is not too long? - if (col + c > LCD_WIDTH && col >= (LCD_WIDTH) / 4) _newline(); // should it wrap? - c += !eol; // +1 so the space will be printed - col += c; // advance col to new position - while (c) { // character countdown - --c; // count down to zero - wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again - lcd_put_wchar(ch); // character to the LCD + #if SCREENS_CAN_TIME_OUT + bool MarlinUI::defer_return_to_status; + millis_t MarlinUI::return_to_status_ms = 0; + #endif + + uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed + + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + millis_t MarlinUI::next_filament_display; // = 0 + #endif + + millis_t MarlinUI::next_button_update_ms; // = 0 + + #if HAS_MARLINUI_U8GLIB + bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false + #endif + + // Encoder Handling + #if HAS_ENCODER_ACTION + uint32_t MarlinUI::encoderPosition; + volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update + #endif + + #if ENABLED(SDSUPPORT) + + #include "../sd/cardreader.h" + + #if MARLINUI_SCROLL_NAME + uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; + #endif + + const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { + const char *outstr = theCard.longest_filename(); + if (theCard.longFilename[0]) { + #if MARLINUI_SCROLL_NAME + if (doScroll) { + for (uint8_t l = FILENAME_LENGTH; l--;) + hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor + static uint8_t filename_scroll_hash; + if (filename_scroll_hash != hash) { // If the hash changed... + filename_scroll_hash = hash; // Save the new hash + filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit + filename_scroll_pos = 0; // Reset scroll to the start + lcd_status_update_delay = 8; // Don't scroll right away } - if (eol) break; // all done! - wrd = nullptr; // set up for next word - } - else c++; // count word characters - } - } - else { - for (;;) { - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - lcd_put_wchar(ch); - col++; - if (col >= LCD_WIDTH) _newline(); - } - } - } - - void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { - const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 0; - uint8_t col = 0, row = 0; - if (!string && plen + slen <= LCD_WIDTH) { - col = (LCD_WIDTH - plen - slen) / 2; - row = LCD_HEIGHT > 3 ? 1 : 0; - } - wrap_string_P(col, row, pref, true); - if (string) { - if (col) { col = 0; row++; } // Move to the start of the next line - wrap_string(col, row, string); - } - if (suff) wrap_string_P(col, row, suff); - } - - #endif // !HAS_GRAPHICAL_TFT - -#endif // HAS_LCD_MENU - -void MarlinUI::init() { - - init_lcd(); - - #if HAS_DIGITAL_BUTTONS - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - #if BUTTON_EXISTS(ENC_EN) - SET_INPUT_PULLUP(BTN_ENC_EN); - #endif - #if BUTTON_EXISTS(BACK) - SET_INPUT_PULLUP(BTN_BACK); - #endif - #if BUTTON_EXISTS(UP) - SET_INPUT(BTN_UP); - #endif - #if BUTTON_EXISTS(DWN) - SET_INPUT(BTN_DWN); - #endif - #if BUTTON_EXISTS(LFT) - SET_INPUT(BTN_LFT); - #endif - #if BUTTON_EXISTS(RT) - SET_INPUT(BTN_RT); - #endif - #endif - - #if HAS_SHIFT_ENCODER - - #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register - - SET_OUTPUT(SR_DATA_PIN); - SET_OUTPUT(SR_CLK_PIN); - - #elif PIN_EXISTS(SHIFT_CLK) - - SET_OUTPUT(SHIFT_CLK_PIN); - OUT_WRITE(SHIFT_LD_PIN, HIGH); - #if PIN_EXISTS(SHIFT_EN) - OUT_WRITE(SHIFT_EN_PIN, LOW); - #endif - SET_INPUT_PULLUP(SHIFT_OUT_PIN); - - #endif - - #endif // HAS_SHIFT_ENCODER - - #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) - slow_buttons = 0; - #endif - - update_buttons(); - - TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); -} - -bool MarlinUI::get_blink() { - static uint8_t blink = 0; - static millis_t next_blink_ms = 0; - millis_t ms = millis(); - if (ELAPSED(ms, next_blink_ms)) { - blink ^= 0xFF; - next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; - } - return blink != 0; -} - -//////////////////////////////////////////// -///////////// Keypad Handling ////////////// -//////////////////////////////////////////// - -#if IS_RRW_KEYPAD && HAS_ENCODER_ACTION - - volatile uint8_t MarlinUI::keypad_buttons; - - #if HAS_LCD_MENU && !HAS_ADC_BUTTONS - - void lcd_move_x(); - void lcd_move_y(); - void lcd_move_z(); - - void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { - ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; - ui.encoderPosition = dir; - switch (axis) { - case X_AXIS: lcd_move_x(); break; - case Y_AXIS: lcd_move_y(); break; - case Z_AXIS: lcd_move_z(); - default: break; - } - } - - #endif - - bool MarlinUI::handle_keypad() { - - #if HAS_ADC_BUTTONS - - #define ADC_MIN_KEY_DELAY 100 - if (keypad_buttons) { - #if HAS_ENCODER_ACTION - refresh(LCDVIEW_REDRAW_NOW); - #if HAS_LCD_MENU - if (encoderDirection == -(ENCODERBASE)) { // HAS_ADC_BUTTONS forces REVERSE_MENU_DIRECTION, so this indicates menu navigation - if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } - } - else - #endif - { - #if HAS_LCD_MENU - if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; - #else - if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; - #endif + // Advance byte position corresponding to filename_scroll_pos char position + outstr += TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(outstr, filename_scroll_pos), filename_scroll_pos); } + #else + theCard.longFilename[ + TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(theCard.longFilename, maxlen), maxlen) + ] = '\0'; // cutoff at screen edge #endif - next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; - return true; } + return outstr; + } - #else // !HAS_ADC_BUTTONS - - static uint8_t keypad_debounce = 0; - - if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 - | EN_KEYPAD_F3 | EN_KEYPAD_DOWN - | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE - | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) - ) { - if (keypad_debounce > 0) keypad_debounce--; - } - else if (!keypad_debounce) { - keypad_debounce = 2; - - const bool homed = all_axes_homed(); - - #if HAS_LCD_MENU - - if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); - - #if NONE(DELTA, Z_HOME_TO_MAX) - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); - #endif - - if (homed) { - #if EITHER(DELTA, Z_HOME_TO_MAX) - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); - #endif - if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); - if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); - if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); - if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); - if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); - } - - #endif // HAS_LCD_MENU - - if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); - return true; - } - - #endif // !HAS_ADC_BUTTONS - - return false; - } - -#endif // IS_RRW_KEYPAD && HAS_ENCODER_ACTION - -/** - * Status Screen - * - * This is very display-dependent, so the lcd implementation draws this. - */ - -#if BASIC_PROGRESS_BAR - millis_t MarlinUI::progress_bar_ms; // = 0 - #if PROGRESS_MSG_EXPIRE > 0 - millis_t MarlinUI::expire_status_ms; // = 0 #endif -#endif -void MarlinUI::status_screen() { + #if HAS_LCD_MENU + #include "menu/menu.h" - TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); + screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR + bool MarlinUI::screen_changed; - #if BASIC_PROGRESS_BAR - - // - // HD44780 implements the following message blinking and - // message expiration because Status Line and Progress Bar - // share the same line on the display. - // - - #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) - #define GOT_MS - const millis_t ms = millis(); + #if ENABLED(ENCODER_RATE_MULTIPLIER) + bool MarlinUI::encoderRateMultiplierEnabled; + millis_t MarlinUI::lastEncoderMovementMillis = 0; + void MarlinUI::enable_encoder_multiplier(const bool onoff) { + encoderRateMultiplierEnabled = onoff; + lastEncoderMovementMillis = 0; + } #endif - // If the message will blink rather than expire... - #if DISABLED(PROGRESS_MSG_ONCE) - if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) - progress_bar_ms = ms; + #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + int8_t MarlinUI::encoderDirection = ENCODERBASE; #endif - #if PROGRESS_MSG_EXPIRE > 0 + #if HAS_TOUCH_BUTTONS + uint8_t MarlinUI::touch_buttons; + uint8_t MarlinUI::repeat_delay; + #endif - // Handle message expire - if (expire_status_ms) { + #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) - // Expire the message if a job is active and the bar has ticks - if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { - if (ELAPSED(ms, expire_status_ms)) { - status_message[0] = '\0'; - expire_status_ms = 0; + bool MarlinUI::external_control; // = false + + void MarlinUI::wait_for_release() { + while (button_pressed()) safe_delay(50); + safe_delay(50); + } + + #endif + + #if !HAS_GRAPHICAL_TFT + + void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { + SETCURSOR(col, row); + if (!string) return; + + auto _newline = [&col, &row]{ + col = 0; row++; // Move col to string len (plus space) + SETCURSOR(0, row); // Simulate carriage return + }; + + uint8_t *p = (uint8_t*)string; + wchar_t ch; + if (wordwrap) { + uint8_t *wrd = nullptr, c = 0; + // find the end of the part + for (;;) { + if (!wrd) wrd = p; // Get word start /before/ advancing + p = get_utf8_value_cb(p, cb_read_byte, &ch); + const bool eol = !ch; // zero ends the string + // End or a break between phrases? + if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { + if (!c && ch == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces + // Past the right and the word is not too long? + if (col + c > LCD_WIDTH && col >= (LCD_WIDTH) / 4) _newline(); // should it wrap? + c += !eol; // +1 so the space will be printed + col += c; // advance col to new position + while (c) { // character countdown + --c; // count down to zero + wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again + lcd_put_wchar(ch); // character to the LCD + } + if (eol) break; // all done! + wrd = nullptr; // set up for next word + } + else c++; // count word characters } } else { - // Defer message expiration before bar appears - // and during any pause (not just SD) - expire_status_ms += LCD_UPDATE_INTERVAL; - } - } - - #endif // PROGRESS_MSG_EXPIRE - - #endif // BASIC_PROGRESS_BAR - - #if HAS_LCD_MENU - if (use_click()) { - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = millis() + 5000UL; // Show status message for 5s - #endif - goto_screen(menu_main); - #if DISABLED(NO_LCD_REINIT) - init_lcd(); // May revive the LCD if static electricity killed it - #endif - return; - } - - #endif - - #if ENABLED(ULTIPANEL_FEEDMULTIPLY) - - const int16_t old_frm = feedrate_percentage; - int16_t new_frm = old_frm + int16_t(encoderPosition); - - // Dead zone at 100% feedrate - if (old_frm == 100) { - if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) - new_frm -= ENCODER_FEEDRATE_DEADZONE; - else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) - new_frm += ENCODER_FEEDRATE_DEADZONE; - else - new_frm = old_frm; - } - else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) - new_frm = 100; - - LIMIT(new_frm, 10, 999); - - if (old_frm != new_frm) { - feedrate_percentage = new_frm; - encoderPosition = 0; - #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) - static millis_t next_beep; - #ifndef GOT_MS - const millis_t ms = millis(); - #endif - if (ELAPSED(ms, next_beep)) { - buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); - next_beep = ms + 500UL; - } - #endif - } - - #endif // ULTIPANEL_FEEDMULTIPLY - - draw_status_screen(); -} - -void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { - init(); - status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); - TERN_(HAS_LCD_MENU, return_to_status()); - - // RED ALERT. RED ALERT. - #ifdef LED_BACKLIGHT_TIMEOUT - leds.set_color(LEDColorRed()); - #ifdef NEOPIXEL_BKGD_INDEX_FIRST - neo.set_background_color(255, 0, 0, 0); - neo.show(); - #endif - #endif - - draw_kill_screen(); -} - -void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { - - TERN_(HAS_LCD_MENU, refresh()); - - #if HAS_ENCODER_ACTION - if (clear_buttons) buttons = 0; - next_button_update_ms = millis() + 500; - #else - UNUSED(clear_buttons); - #endif - - #if HAS_CHIRP - chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_LCD_MENU, USE_BEEPER) - for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } - #elif HAS_LCD_MENU - delay(10); - #endif - #endif -} - -//////////////////////////////////////////// -/////////////// Manual Move //////////////// -//////////////////////////////////////////// - -#if HAS_LCD_MENU - - ManualMove MarlinUI::manual_move{}; - - millis_t ManualMove::start_time = 0; - float ManualMove::menu_scale = 1; - #if IS_KINEMATIC - float ManualMove::offset = 0; - xyze_pos_t ManualMove::all_axes_destination = { 0 }; - bool ManualMove::processing = false; - #endif - #if MULTI_E_MANUAL - int8_t ManualMove::e_index = 0; - #endif - AxisEnum ManualMove::axis = NO_AXIS_ENUM; - - /** - * If a manual move has been posted and its time has arrived, and if the planner - * has a space for it, then add a linear move to current_position the planner. - * - * If any manual move needs to be interrupted, make sure to force a manual move - * by setting manual_move.start_time to millis() after updating current_position. - * - * To post a manual move: - * - Update current_position to the new place you want to go. - * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. - * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. - * - * For kinematic machines: - * - Set manual_move.offset to modify one axis and post the move. - * This is used to achieve more rapid stepping on kinematic machines. - * - * Currently used by the _lcd_move_xyz function in menu_motion.cpp - * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. - */ - void ManualMove::task() { - - if (processing) return; // Prevent re-entry from idle() calls - - // Add a manual move to the queue? - if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { - - const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; - - #if IS_KINEMATIC - - #if HAS_MULTI_EXTRUDER - REMEMBER(ae, active_extruder); - #if MULTI_E_MANUAL - if (axis == E_AXIS) active_extruder = e_index; - #endif - #endif - - // Apply a linear offset to a single axis - if (axis == ALL_AXES_ENUM) - destination = all_axes_destination; - else if (axis <= XYZE) { - destination = current_position; - destination[axis] += offset; - } - - // Reset for the next move - offset = 0; - axis = NO_AXIS_ENUM; - - // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to - // move_to_destination. This will cause idle() to be called, which can then call this function while the - // previous invocation is being blocked. Modifications to offset shouldn't be made while - // processing is true or the planner will get out of sync. - processing = true; - prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination - processing = false; - - #else - - // For Cartesian / Core motion simply move to the current_position - planner.buffer_line(current_position, fr_mm_s, - TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder - ); - - //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); - - axis = NO_AXIS_ENUM; - - #endif - } - } - - // - // Tell ui.update() to start a move to current_position after a short delay. - // - void ManualMove::soon(const AxisEnum move_axis - OPTARG(MULTI_E_MANUAL, const int8_t eindex/*=active_extruder*/) - ) { - TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); - start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves - axis = move_axis; - //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); - } - - #if ENABLED(AUTO_BED_LEVELING_UBL) - - void MarlinUI::external_encoder() { - if (external_control && encoderDiff) { - ubl.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing - encoderDiff = 0; // Hide encoder events from the screen handler - refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. - } - } - - #endif - -#endif // HAS_LCD_MENU - -/** - * Update the LCD, read encoder buttons, etc. - * - Read button states - * - Check the SD Card slot state - * - Act on RepRap World keypad input - * - Update the encoder position - * - Apply acceleration to the encoder position - * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events - * - Reset the Info Screen timeout if there's any input - * - Update status indicators, if any - * - * Run the current LCD menu handler callback function: - * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE - * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE - * - Call the menu handler. Menu handlers should do the following: - * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value - * (Encoder events automatically set lcdDrawUpdate for you.) - * - if (should_draw()) { redraw } - * - Before exiting the handler set lcdDrawUpdate to: - * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. - * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). - * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. - * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. - * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, - * so don't change lcdDrawUpdate without considering this. - * - * After the menu handler callback runs (or not): - * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW - * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) - * - * This function is only called from the main thread. - */ - -LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; -millis_t next_lcd_update_ms; - -inline bool can_encode() { - return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) -} - -void MarlinUI::update() { - - static uint16_t max_display_update_time = 0; - millis_t ms = millis(); - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.update_timeout(powersupply_on); - #endif - - #if HAS_LCD_MENU - - // Handle any queued Move Axis motion - manual_move.task(); - - // Update button states for button_pressed(), etc. - // If the state changes the next update may be delayed 300-500ms. - update_buttons(); - - // If the action button is pressed... - static bool wait_for_unclick; // = false - - auto do_click = [&]{ - wait_for_unclick = true; // - Set debounce flag to ignore continuous clicks - lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - }; - - #if HAS_TOUCH_BUTTONS - if (touch_buttons) { - reset_status_timeout(ms); - if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority - if (ELAPSED(ms, next_button_update_ms)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; - if (touch_buttons & EN_A) encoderDiff *= -1; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - next_button_update_ms = ms + repeat_delay; // Assume the repeat delay - if (!wait_for_unclick) { - next_button_update_ms += 250; // Longer delay on first press - wait_for_unclick = true; // Avoid Back/Select click while repeating - chirp(); - } + for (;;) { + p = get_utf8_value_cb(p, cb_read_byte, &ch); + if (!ch) break; + lcd_put_wchar(ch); + col++; + if (col >= LCD_WIDTH) _newline(); } } - else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: - do_click(); } - // keep wait_for_unclick value - #endif - if (!touch_buttons) { - // Integrated LCD click handling via button_pressed - if (!external_control && button_pressed()) { - if (!wait_for_unclick) do_click(); // Handle the click + void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 0; + uint8_t col = 0, row = 0; + if (!string && plen + slen <= LCD_WIDTH) { + col = (LCD_WIDTH - plen - slen) / 2; + row = LCD_HEIGHT > 3 ? 1 : 0; + } + wrap_string_P(col, row, pref, true); + if (string) { + if (col) { col = 0; row++; } // Move to the start of the next line + wrap_string(col, row, string); + } + if (suff) wrap_string_P(col, row, suff); } - else - wait_for_unclick = false; - } - if (LCD_BACK_CLICKED()) { - quick_feedback(); - goto_previous_screen(); - } + #endif // !HAS_GRAPHICAL_TFT #endif // HAS_LCD_MENU - if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { + void MarlinUI::init() { - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; + init_lcd(); - #if HAS_TOUCH_BUTTONS + #if HAS_DIGITAL_BUTTONS + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if BUTTON_EXISTS(ENC_EN) + SET_INPUT_PULLUP(BTN_ENC_EN); + #endif + #if BUTTON_EXISTS(BACK) + SET_INPUT_PULLUP(BTN_BACK); + #endif + #if BUTTON_EXISTS(UP) + SET_INPUT(BTN_UP); + #endif + #if BUTTON_EXISTS(DWN) + SET_INPUT(BTN_DWN); + #endif + #if BUTTON_EXISTS(LFT) + SET_INPUT(BTN_LFT); + #endif + #if BUTTON_EXISTS(RT) + SET_INPUT(BTN_RT); + #endif + #endif - if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; + #if HAS_SHIFT_ENCODER - TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); + #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register + + SET_OUTPUT(SR_DATA_PIN); + SET_OUTPUT(SR_CLK_PIN); + + #elif PIN_EXISTS(SHIFT_CLK) + + SET_OUTPUT(SHIFT_CLK_PIN); + OUT_WRITE(SHIFT_LD_PIN, HIGH); + #if PIN_EXISTS(SHIFT_EN) + OUT_WRITE(SHIFT_EN_PIN, LOW); + #endif + SET_INPUT_PULLUP(SHIFT_OUT_PIN); + + #endif + + #endif // HAS_SHIFT_ENCODER + + #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) + slow_buttons = 0; + #endif + + update_buttons(); + + TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); + } + + bool MarlinUI::get_blink() { + static uint8_t blink = 0; + static millis_t next_blink_ms = 0; + millis_t ms = millis(); + if (ELAPSED(ms, next_blink_ms)) { + blink ^= 0xFF; + next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; + } + return blink != 0; + } + + //////////////////////////////////////////// + ///////////// Keypad Handling ////////////// + //////////////////////////////////////////// + + #if IS_RRW_KEYPAD && HAS_ENCODER_ACTION + + volatile uint8_t MarlinUI::keypad_buttons; + + #if HAS_LCD_MENU && !HAS_ADC_BUTTONS + + void lcd_move_x(); + void lcd_move_y(); + void lcd_move_z(); + + void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { + ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; + ui.encoderPosition = dir; + switch (axis) { + case X_AXIS: lcd_move_x(); break; + case Y_AXIS: lcd_move_y(); break; + case Z_AXIS: lcd_move_z(); + default: break; + } + } #endif - TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); + bool MarlinUI::handle_keypad() { - #if HAS_ENCODER_ACTION + #if HAS_ADC_BUTTONS - TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context - - if (TERN0(IS_RRW_KEYPAD, handle_keypad())) - reset_status_timeout(ms); - - uint8_t abs_diff = ABS(encoderDiff); - - #if ENCODER_PULSES_PER_STEP > 1 - // When reversing the encoder direction, a movement step can be missed because - // encoderDiff has a non-zero residual value, making the controller unresponsive. - // The fix clears the residual value when the encoder is idle. - // Also check if past half the threshold to compensate for missed single steps. - static int8_t lastEncoderDiff; - - // Timeout? No decoder change since last check. 10 or 20 times per second. - if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? - encoderDiff = 0; // Clear residual pulses. - else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? - abs_diff = epps; // Treat as a full step size - encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. + #define ADC_MIN_KEY_DELAY 100 + if (keypad_buttons) { + #if HAS_ENCODER_ACTION + refresh(LCDVIEW_REDRAW_NOW); + #if HAS_LCD_MENU + if (encoderDirection == -(ENCODERBASE)) { // HAS_ADC_BUTTONS forces REVERSE_MENU_DIRECTION, so this indicates menu navigation + if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } + } + else + #endif + { + #if HAS_LCD_MENU + if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; + #else + if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; + #endif + } + #endif + next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; + return true; } - lastEncoderDiff = encoderDiff; + + #else // !HAS_ADC_BUTTONS + + static uint8_t keypad_debounce = 0; + + if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 + | EN_KEYPAD_F3 | EN_KEYPAD_DOWN + | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE + | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) + ) { + if (keypad_debounce > 0) keypad_debounce--; + } + else if (!keypad_debounce) { + keypad_debounce = 2; + + const bool homed = all_axes_homed(); + + #if HAS_LCD_MENU + + if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); + + #if NONE(DELTA, Z_HOME_TO_MAX) + if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); + #endif + + if (homed) { + #if EITHER(DELTA, Z_HOME_TO_MAX) + if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); + #endif + if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); + if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); + if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); + if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); + if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); + } + + #endif // HAS_LCD_MENU + + if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); + return true; + } + + #endif // !HAS_ADC_BUTTONS + + return false; + } + + #endif // IS_RRW_KEYPAD && HAS_ENCODER_ACTION + + /** + * Status Screen + * + * This is very display-dependent, so the lcd implementation draws this. + */ + + #if BASIC_PROGRESS_BAR + millis_t MarlinUI::progress_bar_ms; // = 0 + #if PROGRESS_MSG_EXPIRE > 0 + millis_t MarlinUI::expire_status_ms; // = 0 + #endif + #endif + + void MarlinUI::status_screen() { + + TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); + + #if BASIC_PROGRESS_BAR + + // + // HD44780 implements the following message blinking and + // message expiration because Status Line and Progress Bar + // share the same line on the display. + // + + #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) + #define GOT_MS + const millis_t ms = millis(); #endif - const bool encoderPastThreshold = (abs_diff >= epps); - if (encoderPastThreshold || lcd_clicked) { - if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { + // If the message will blink rather than expire... + #if DISABLED(PROGRESS_MSG_ONCE) + if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) + progress_bar_ms = ms; + #endif - #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) + #if PROGRESS_MSG_EXPIRE > 0 - int32_t encoderMultiplier = 1; + // Handle message expire + if (expire_status_ms) { - if (encoderRateMultiplierEnabled) { - const float encoderMovementSteps = float(abs_diff) / epps; - - if (lastEncoderMovementMillis) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the encoderDiff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; - - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - - // Enable to output the encoder steps per second value - //#define ENCODER_RATE_MULTIPLIER_DEBUG - #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); - SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); - SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); - SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); - SERIAL_EOL(); - #endif - } - - lastEncoderMovementMillis = ms; - } // encoderRateMultiplierEnabled - - #else - - constexpr int32_t encoderMultiplier = 1; - - #endif // ENCODER_RATE_MULTIPLIER - - if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; - - encoderDiff = 0; + // Expire the message if a job is active and the bar has ticks + if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { + if (ELAPSED(ms, expire_status_ms)) { + status_message[0] = '\0'; + expire_status_ms = 0; + } + } + else { + // Defer message expiration before bar appears + // and during any pause (not just SD) + expire_status_ms += LCD_UPDATE_INTERVAL; + } } - reset_status_timeout(ms); + #endif // PROGRESS_MSG_EXPIRE - refresh(LCDVIEW_REDRAW_NOW); + #endif // BASIC_PROGRESS_BAR - #ifdef LED_BACKLIGHT_TIMEOUT - if (!powersupply_on) leds.reset_timeout(ms); + #if HAS_LCD_MENU + if (use_click()) { + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + next_filament_display = millis() + 5000UL; // Show status message for 5s + #endif + goto_screen(menu_main); + #if DISABLED(NO_LCD_REINIT) + init_lcd(); // May revive the LCD if static electricity killed it + #endif + return; + } + + #endif + + #if ENABLED(ULTIPANEL_FEEDMULTIPLY) + + const int16_t old_frm = feedrate_percentage; + int16_t new_frm = old_frm + int16_t(encoderPosition); + + // Dead zone at 100% feedrate + if (old_frm == 100) { + if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) + new_frm -= ENCODER_FEEDRATE_DEADZONE; + else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) + new_frm += ENCODER_FEEDRATE_DEADZONE; + else + new_frm = old_frm; + } + else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) + new_frm = 100; + + LIMIT(new_frm, 10, 999); + + if (old_frm != new_frm) { + feedrate_percentage = new_frm; + encoderPosition = 0; + #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) + static millis_t next_beep; + #ifndef GOT_MS + const millis_t ms = millis(); + #endif + if (ELAPSED(ms, next_beep)) { + buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); + next_beep = ms + 500UL; + } #endif } + #endif // ULTIPANEL_FEEDMULTIPLY + + draw_status_screen(); + } + + void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { + init(); + status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); + TERN_(HAS_LCD_MENU, return_to_status()); + + // RED ALERT. RED ALERT. + #ifdef LED_BACKLIGHT_TIMEOUT + leds.set_color(LEDColorRed()); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + neo.set_background_color(255, 0, 0, 0); + neo.show(); + #endif #endif - // This runs every ~100ms when idling often enough. - // Instead of tracking changes just redraw the Status Screen once per second. - if (on_status_screen() && !lcd_status_update_delay--) { - lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); - if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number - refresh(LCDVIEW_REDRAW_NOW); + draw_kill_screen(); + } + + void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { + + TERN_(HAS_LCD_MENU, refresh()); + + #if HAS_ENCODER_ACTION + if (clear_buttons) buttons = 0; + next_button_update_ms = millis() + 500; + #else + UNUSED(clear_buttons); + #endif + + #if HAS_CHIRP + chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif + } + + //////////////////////////////////////////// + /////////////// Manual Move //////////////// + //////////////////////////////////////////// + + #if HAS_LCD_MENU + + ManualMove MarlinUI::manual_move{}; + + millis_t ManualMove::start_time = 0; + float ManualMove::menu_scale = 1; + #if IS_KINEMATIC + float ManualMove::offset = 0; + xyze_pos_t ManualMove::all_axes_destination = { 0 }; + bool ManualMove::processing = false; + #endif + #if MULTI_E_MANUAL + int8_t ManualMove::e_index = 0; + #endif + AxisEnum ManualMove::axis = NO_AXIS_ENUM; + + /** + * If a manual move has been posted and its time has arrived, and if the planner + * has a space for it, then add a linear move to current_position the planner. + * + * If any manual move needs to be interrupted, make sure to force a manual move + * by setting manual_move.start_time to millis() after updating current_position. + * + * To post a manual move: + * - Update current_position to the new place you want to go. + * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. + * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. + * + * For kinematic machines: + * - Set manual_move.offset to modify one axis and post the move. + * This is used to achieve more rapid stepping on kinematic machines. + * + * Currently used by the _lcd_move_xyz function in menu_motion.cpp + * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. + */ + void ManualMove::task() { + + if (processing) return; // Prevent re-entry from idle() calls + + // Add a manual move to the queue? + if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { + + const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + + #if IS_KINEMATIC + + #if HAS_MULTI_EXTRUDER + REMEMBER(ae, active_extruder); + #if MULTI_E_MANUAL + if (axis == E_AXIS) active_extruder = e_index; + #endif + #endif + + // Apply a linear offset to a single axis + if (axis == ALL_AXES_ENUM) + destination = all_axes_destination; + else if (axis <= XYZE) { + destination = current_position; + destination[axis] += offset; + } + + // Reset for the next move + offset = 0; + axis = NO_AXIS_ENUM; + + // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to + // move_to_destination. This will cause idle() to be called, which can then call this function while the + // previous invocation is being blocked. Modifications to offset shouldn't be made while + // processing is true or the planner will get out of sync. + processing = true; + prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination + processing = false; + + #else + + // For Cartesian / Core motion simply move to the current_position + planner.buffer_line(current_position, fr_mm_s, + TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder + ); + + //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); + + axis = NO_AXIS_ENUM; + + #endif + } } - #if BOTH(HAS_LCD_MENU, SCROLL_LONG_FILENAMES) - // If scrolling of long file names is enabled and we are in the sd card menu, - // cause a refresh to occur until all the text has scrolled into view. - if (currentScreen == menu_media && !lcd_status_update_delay--) { - lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start - if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; - refresh(LCDVIEW_REDRAW_NOW); - reset_status_timeout(ms); + // + // Tell ui.update() to start a move to current_position after a short delay. + // + void ManualMove::soon(const AxisEnum move_axis + OPTARG(MULTI_E_MANUAL, const int8_t eindex/*=active_extruder*/) + ) { + TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); + start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves + axis = move_axis; + //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); + } + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + void MarlinUI::external_encoder() { + if (external_control && encoderDiff) { + ubl.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing + encoderDiff = 0; // Hide encoder events from the screen handler + refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + } } + #endif - // Then we want to use only 50% of the time - const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; + #endif // HAS_LCD_MENU - if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { + /** + * Update the LCD, read encoder buttons, etc. + * - Read button states + * - Check the SD Card slot state + * - Act on RepRap World keypad input + * - Update the encoder position + * - Apply acceleration to the encoder position + * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events + * - Reset the Info Screen timeout if there's any input + * - Update status indicators, if any + * + * Run the current LCD menu handler callback function: + * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE + * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE + * - Call the menu handler. Menu handlers should do the following: + * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value + * (Encoder events automatically set lcdDrawUpdate for you.) + * - if (should_draw()) { redraw } + * - Before exiting the handler set lcdDrawUpdate to: + * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. + * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). + * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. + * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. + * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, + * so don't change lcdDrawUpdate without considering this. + * + * After the menu handler callback runs (or not): + * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW + * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) + * + * This function is only called from the main thread. + */ + + LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; + millis_t next_lcd_update_ms; + + inline bool can_encode() { + return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) + } + + void MarlinUI::update() { + + static uint16_t max_display_update_time = 0; + millis_t ms = millis(); + + #ifdef LED_BACKLIGHT_TIMEOUT + leds.update_timeout(powersupply_on); + #endif + + #if HAS_LCD_MENU + + // Handle any queued Move Axis motion + manual_move.task(); + + // Update button states for button_pressed(), etc. + // If the state changes the next update may be delayed 300-500ms. + update_buttons(); + + // If the action button is pressed... + static bool wait_for_unclick; // = false + + auto do_click = [&]{ + wait_for_unclick = true; // - Set debounce flag to ignore continuous clicks + lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click + wait_for_user = false; // - Any click clears wait for user + quick_feedback(); // - Always make a click sound + }; + + #if HAS_TOUCH_BUTTONS + if (touch_buttons) { + reset_status_timeout(ms); + if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority + if (ELAPSED(ms, next_button_update_ms)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; + if (touch_buttons & EN_A) encoderDiff *= -1; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + next_button_update_ms = ms + repeat_delay; // Assume the repeat delay + if (!wait_for_unclick) { + next_button_update_ms += 250; // Longer delay on first press + wait_for_unclick = true; // Avoid Back/Select click while repeating + chirp(); + } + } + } + else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: + do_click(); + } + // keep wait_for_unclick value + #endif + + if (!touch_buttons) { + // Integrated LCD click handling via button_pressed + if (!external_control && button_pressed()) { + if (!wait_for_unclick) do_click(); // Handle the click + } + else + wait_for_unclick = false; + } + + if (LCD_BACK_CLICKED()) { + quick_feedback(); + goto_previous_screen(); + } + + #endif // HAS_LCD_MENU + + if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { + + next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; + + #if HAS_TOUCH_BUTTONS + + if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; + + TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); + + #endif + + TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); + + #if HAS_ENCODER_ACTION + + TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context + + if (TERN0(IS_RRW_KEYPAD, handle_keypad())) + reset_status_timeout(ms); + + uint8_t abs_diff = ABS(encoderDiff); + + #if ENCODER_PULSES_PER_STEP > 1 + // When reversing the encoder direction, a movement step can be missed because + // encoderDiff has a non-zero residual value, making the controller unresponsive. + // The fix clears the residual value when the encoder is idle. + // Also check if past half the threshold to compensate for missed single steps. + static int8_t lastEncoderDiff; + + // Timeout? No decoder change since last check. 10 or 20 times per second. + if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? + encoderDiff = 0; // Clear residual pulses. + else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? + abs_diff = epps; // Treat as a full step size + encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. + } + lastEncoderDiff = encoderDiff; + #endif + + const bool encoderPastThreshold = (abs_diff >= epps); + if (encoderPastThreshold || lcd_clicked) { + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { + + #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) + + int32_t encoderMultiplier = 1; + + if (encoderRateMultiplierEnabled) { + const float encoderMovementSteps = float(abs_diff) / epps; + + if (lastEncoderMovementMillis) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the encoderDiff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; + + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + + // Enable to output the encoder steps per second value + //#define ENCODER_RATE_MULTIPLIER_DEBUG + #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); + SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); + SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); + SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); + SERIAL_EOL(); + #endif + } + + lastEncoderMovementMillis = ms; + } // encoderRateMultiplierEnabled + + #else + + constexpr int32_t encoderMultiplier = 1; + + #endif // ENCODER_RATE_MULTIPLIER + + if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; + + encoderDiff = 0; + } + + reset_status_timeout(ms); + + refresh(LCDVIEW_REDRAW_NOW); + + #ifdef LED_BACKLIGHT_TIMEOUT + if (!powersupply_on) leds.reset_timeout(ms); + #endif + } + + #endif + + // This runs every ~100ms when idling often enough. + // Instead of tracking changes just redraw the Status Screen once per second. + if (on_status_screen() && !lcd_status_update_delay--) { + lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); + if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number + refresh(LCDVIEW_REDRAW_NOW); + } + + #if BOTH(HAS_LCD_MENU, SCROLL_LONG_FILENAMES) + // If scrolling of long file names is enabled and we are in the sd card menu, + // cause a refresh to occur until all the text has scrolled into view. + if (currentScreen == menu_media && !lcd_status_update_delay--) { + lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start + if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; + refresh(LCDVIEW_REDRAW_NOW); + reset_status_timeout(ms); + } + #endif + + // Then we want to use only 50% of the time + const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; + + if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { + + // Change state of drawing flag between screen updates + if (!drawing_screen) switch (lcdDrawUpdate) { + case LCDVIEW_CALL_NO_REDRAW: + refresh(LCDVIEW_NONE); + break; + case LCDVIEW_CLEAR_CALL_REDRAW: + case LCDVIEW_CALL_REDRAW_NEXT: + refresh(LCDVIEW_REDRAW_NOW); + case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT + case LCDVIEW_NONE: + break; + } // switch + + TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); + + #if HAS_MARLINUI_U8GLIB + + #if ENABLED(LIGHTWEIGHT_UI) + const bool in_status = on_status_screen(), + do_u8g_loop = !in_status; + lcd_in_status(in_status); + if (in_status) status_screen(); + #else + constexpr bool do_u8g_loop = true; + #endif + + if (do_u8g_loop) { + if (!drawing_screen) { // If not already drawing pages + u8g.firstPage(); // Start the first page + drawing_screen = first_page = true; // Flag as drawing pages + } + set_font(FONT_MENU); // Setup font for every page draw + u8g.setColorIndex(1); // And reset the color + run_current_screen(); // Draw and process the current screen + first_page = false; + + // The screen handler can clear drawing_screen for an action that changes the screen. + // If still drawing and there's another page, update max-time and return now. + // The nextPage will already be set up on the next call. + if (drawing_screen && (drawing_screen = u8g.nextPage())) { + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + return; + } + } + + #else + + run_current_screen(); + + #endif + + TERN_(HAS_LCD_MENU, lcd_clicked = false); + + // Keeping track of the longest time for an individual LCD update. + // Used to do screen throttling when the planner starts to fill up. + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + } + + #if SCREENS_CAN_TIME_OUT + // Return to Status Screen after a timeout + if (on_status_screen() || defer_return_to_status) + reset_status_timeout(ms); + else if (ELAPSED(ms, return_to_status_ms)) + return_to_status(); + #endif // Change state of drawing flag between screen updates if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CALL_NO_REDRAW: - refresh(LCDVIEW_NONE); - break; case LCDVIEW_CLEAR_CALL_REDRAW: - case LCDVIEW_CALL_REDRAW_NEXT: - refresh(LCDVIEW_REDRAW_NOW); - case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT + clear_lcd(); break; + case LCDVIEW_REDRAW_NOW: + refresh(LCDVIEW_NONE); case LCDVIEW_NONE: - break; + case LCDVIEW_CALL_REDRAW_NEXT: + case LCDVIEW_CALL_NO_REDRAW: + default: break; } // switch - TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); + } // ELAPSED(ms, next_lcd_update_ms) - #if HAS_MARLINUI_U8GLIB + TERN_(HAS_GRAPHICAL_TFT, tft_idle()); + } - #if ENABLED(LIGHTWEIGHT_UI) - const bool in_status = on_status_screen(), - do_u8g_loop = !in_status; - lcd_in_status(in_status); - if (in_status) status_screen(); - #else - constexpr bool do_u8g_loop = true; - #endif + #if HAS_ADC_BUTTONS - if (do_u8g_loop) { - if (!drawing_screen) { // If not already drawing pages - u8g.firstPage(); // Start the first page - drawing_screen = first_page = true; // Flag as drawing pages - } - set_font(FONT_MENU); // Setup font for every page draw - u8g.setColorIndex(1); // And reset the color - run_current_screen(); // Draw and process the current screen - first_page = false; + typedef struct { + uint16_t ADCKeyValueMin, ADCKeyValueMax; + uint8_t ADCKeyNo; + } _stADCKeypadTable_; - // The screen handler can clear drawing_screen for an action that changes the screen. - // If still drawing and there's another page, update max-time and return now. - // The nextPage will already be set up on the next call. - if (drawing_screen && (drawing_screen = u8g.nextPage())) { - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - return; - } - } - - #else - - run_current_screen(); - - #endif - - TERN_(HAS_LCD_MENU, lcd_clicked = false); - - // Keeping track of the longest time for an individual LCD update. - // Used to do screen throttling when the planner starts to fill up. - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - } - - #if SCREENS_CAN_TIME_OUT - // Return to Status Screen after a timeout - if (on_status_screen() || defer_return_to_status) - reset_status_timeout(ms); - else if (ELAPSED(ms, return_to_status_ms)) - return_to_status(); + #ifndef ADC_BUTTONS_VALUE_SCALE + #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage + #endif + #ifndef ADC_BUTTONS_R_PULLUP + #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider + #endif + #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN + #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider + #endif + #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN + #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider + #endif + #ifndef ADC_BUTTONS_UP_R_PULLDOWN + #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider + #endif + #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN + #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider + #endif + #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN + #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider #endif - // Change state of drawing flag between screen updates - if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CLEAR_CALL_REDRAW: - clear_lcd(); break; - case LCDVIEW_REDRAW_NOW: - refresh(LCDVIEW_NONE); - case LCDVIEW_NONE: - case LCDVIEW_CALL_REDRAW_NEXT: - case LCDVIEW_CALL_NO_REDRAW: - default: break; - } // switch + // Calculate the ADC value for the voltage divider with specified pull-down resistor value + #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) - } // ELAPSED(ms, next_lcd_update_ms) + static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, + adc_other_button = HAL_ADC_RANGE * 1000 / 1024; + static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { + // VALUE_MIN, VALUE_MAX, KEY + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 + { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) + { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) + { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) + { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) + { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) + }; - TERN_(HAS_GRAPHICAL_TFT, tft_idle()); -} - -#if HAS_ADC_BUTTONS - - typedef struct { - uint16_t ADCKeyValueMin, ADCKeyValueMax; - uint8_t ADCKeyNo; - } _stADCKeypadTable_; - - #ifndef ADC_BUTTONS_VALUE_SCALE - #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage - #endif - #ifndef ADC_BUTTONS_R_PULLUP - #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider - #endif - #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN - #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider - #endif - #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN - #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider - #endif - #ifndef ADC_BUTTONS_UP_R_PULLDOWN - #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider - #endif - #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN - #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider - #endif - #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN - #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider - #endif - - // Calculate the ADC value for the voltage divider with specified pull-down resistor value - #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) - - static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, - adc_other_button = HAL_ADC_RANGE * 1000 / 1024; - static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { - // VALUE_MIN, VALUE_MAX, KEY - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 - { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) - { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) - { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) - { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) - { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) - }; - - uint8_t get_ADC_keyValue() { - if (thermalManager.ADCKey_count >= 16) { - const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; - thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; - thermalManager.ADCKey_count = 0; - if (currentkpADCValue < adc_other_button) - 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); - } - } - return 0; - } - -#endif // HAS_ADC_BUTTONS - -#if HAS_ENCODER_ACTION - - /** - * Read encoder buttons from the hardware registers - * Warning: This function is called from interrupt context! - */ - void MarlinUI::update_buttons() { - const millis_t now = millis(); - if (ELAPSED(now, next_button_update_ms)) { - - #if HAS_DIGITAL_BUTTONS - - #if ANY_BUTTON(EN1, EN2, ENC, BACK) - - uint8_t newbutton = 0; - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - if (can_encode() && BUTTON_PRESSED(ENC)) newbutton |= EN_C; - if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; - - #else - - constexpr uint8_t newbutton = 0; - - #endif - - // - // Directional buttons - // - #if ANY_BUTTON(UP, DWN, LFT, RT) - - const int8_t pulses = epps * encoderDirection; - - if (BUTTON_PRESSED(UP)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; + uint8_t get_ADC_keyValue() { + if (thermalManager.ADCKey_count >= 16) { + const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; + thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; + thermalManager.ADCKey_count = 0; + if (currentkpADCValue < adc_other_button) + 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); } - else if (BUTTON_PRESSED(DWN)) { - encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; - } - else if (BUTTON_PRESSED(LFT)) { - encoderDiff = -pulses; - next_button_update_ms = now + 300; - } - else if (BUTTON_PRESSED(RT)) { - encoderDiff = pulses; - next_button_update_ms = now + 300; - } - - #endif // UP || DWN || LFT || RT - - buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) - #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) - | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) - #endif - ); - - #elif HAS_ADC_BUTTONS - - buttons = 0; - - #endif - - #if HAS_ADC_BUTTONS - if (keypad_buttons == 0) { - const uint8_t b = get_ADC_keyValue(); - if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); - } - #endif - - #if HAS_SHIFT_ENCODER - /** - * 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_PIN, LOW); - WRITE(SHIFT_LD_PIN, HIGH); - LOOP_L_N(i, 8) { - val >>= 1; - if (READ(SHIFT_OUT_PIN)) SBI(val, 7); - WRITE(SHIFT_CLK_PIN, HIGH); - WRITE(SHIFT_CLK_PIN, LOW); - } - TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; - #endif - - #if IS_TFTGLCD_PANEL - next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); - buttons = slow_buttons; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - #endif - - } // next_button_update_ms - - #if HAS_ENCODER_WHEEL - static uint8_t lastEncoderBits; - - // Manage encoder rotation - #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } - - uint8_t enc = 0; - if (buttons & EN_A) enc |= B01; - if (buttons & EN_B) enc |= B10; - if (enc != lastEncoderBits) { - switch (enc) { - case ENCODER_PHASE_0: ENCODER_SPIN(ENCODER_PHASE_3, ENCODER_PHASE_1); break; - case ENCODER_PHASE_1: ENCODER_SPIN(ENCODER_PHASE_0, ENCODER_PHASE_2); break; - case ENCODER_PHASE_2: ENCODER_SPIN(ENCODER_PHASE_1, ENCODER_PHASE_3); break; - case ENCODER_PHASE_3: ENCODER_SPIN(ENCODER_PHASE_2, ENCODER_PHASE_0); break; - } - #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) - external_encoder(); - #endif - lastEncoderBits = enc; } + return 0; + } - #endif // HAS_ENCODER_WHEEL - } + #endif // HAS_ADC_BUTTONS -#endif // HAS_ENCODER_ACTION + #if HAS_ENCODER_ACTION + + /** + * Read encoder buttons from the hardware registers + * Warning: This function is called from interrupt context! + */ + void MarlinUI::update_buttons() { + const millis_t now = millis(); + if (ELAPSED(now, next_button_update_ms)) { + + #if HAS_DIGITAL_BUTTONS + + #if ANY_BUTTON(EN1, EN2, ENC, BACK) + + uint8_t newbutton = 0; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (can_encode() && BUTTON_PRESSED(ENC)) newbutton |= EN_C; + if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; + + #else + + constexpr uint8_t newbutton = 0; + + #endif + + // + // Directional buttons + // + #if ANY_BUTTON(UP, DWN, LFT, RT) + + const int8_t pulses = epps * encoderDirection; + + if (BUTTON_PRESSED(UP)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(DWN)) { + encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(LFT)) { + encoderDiff = -pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(RT)) { + encoderDiff = pulses; + next_button_update_ms = now + 300; + } + + #endif // UP || DWN || LFT || RT + + buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) + #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) + | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) + #endif + ); + + #elif HAS_ADC_BUTTONS + + buttons = 0; + + #endif + + #if HAS_ADC_BUTTONS + if (keypad_buttons == 0) { + const uint8_t b = get_ADC_keyValue(); + if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); + } + #endif + + #if HAS_SHIFT_ENCODER + /** + * 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_PIN, LOW); + WRITE(SHIFT_LD_PIN, HIGH); + LOOP_L_N(i, 8) { + val >>= 1; + if (READ(SHIFT_OUT_PIN)) SBI(val, 7); + WRITE(SHIFT_CLK_PIN, HIGH); + WRITE(SHIFT_CLK_PIN, LOW); + } + TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; + #endif + + #if IS_TFTGLCD_PANEL + next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); + buttons = slow_buttons; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + #endif + + } // next_button_update_ms + + #if HAS_ENCODER_WHEEL + static uint8_t lastEncoderBits; + + // Manage encoder rotation + #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } + + uint8_t enc = 0; + if (buttons & EN_A) enc |= B01; + if (buttons & EN_B) enc |= B10; + if (enc != lastEncoderBits) { + switch (enc) { + case ENCODER_PHASE_0: ENCODER_SPIN(ENCODER_PHASE_3, ENCODER_PHASE_1); break; + case ENCODER_PHASE_1: ENCODER_SPIN(ENCODER_PHASE_0, ENCODER_PHASE_2); break; + case ENCODER_PHASE_2: ENCODER_SPIN(ENCODER_PHASE_1, ENCODER_PHASE_3); break; + case ENCODER_PHASE_3: ENCODER_SPIN(ENCODER_PHASE_2, ENCODER_PHASE_0); break; + } + #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) + external_encoder(); + #endif + lastEncoderBits = enc; + } + + #endif // HAS_ENCODER_WHEEL + } + + #endif // HAS_ENCODER_ACTION #endif // HAS_WIRED_LCD From 0a655c84bfb2455ef7d9bf00e66b35daf4ee73df Mon Sep 17 00:00:00 2001 From: Glought Date: Tue, 29 Jun 2021 10:35:22 -0700 Subject: [PATCH 0334/2168] =?UTF-8?q?=F0=9F=9A=B8=20Sanity-check=20Slim=20?= =?UTF-8?q?LCD=20menus=20with=20Probe=20Offset=20Wizard=20(#22259)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 7524259f60..36ccbee9b9 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3588,6 +3588,13 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "Either enable MEATPACK_ON_SERIAL_PORT_* or BINARY_FILE_TRANSFER, not both." #endif +/** + * Sanity Check for Slim LCD Menus and Probe Offset Wizard + */ +#if BOTH(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) + #error "SLIM_LCD_MENUS disables \"Advanced Settings > Probe Offsets > PROBE_OFFSET_WIZARD.\"" +#endif + /** * Sanity check for unique start and stop values in NOZZLE_CLEAN_FEATURE */ From 61c48b8513f445e4c57e4bf3e4c46ea6e7b39808 Mon Sep 17 00:00:00 2001 From: Cytown Date: Wed, 30 Jun 2021 01:58:11 +0800 Subject: [PATCH 0335/2168] =?UTF-8?q?=F0=9F=9A=B8=20Retain=20power=20durin?= =?UTF-8?q?g=20Pause=20(#22227)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/MarlinCore.h | 6 +++++- Marlin/src/feature/power.cpp | 19 ++++++++++++++++--- Marlin/src/feature/power.h | 2 +- Marlin/src/lcd/marlinui.h | 7 +++++-- 5 files changed, 28 insertions(+), 8 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index f77f3b2f0b..254283da5b 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -617,7 +617,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { TERN_(USE_CONTROLLER_FAN, controllerFan.update()); // Check if fan should be turned on to cool stepper drivers down - TERN_(AUTO_POWER_CONTROL, powerManager.check()); + TERN_(AUTO_POWER_CONTROL, powerManager.check(!ui.on_status_screen() || printJobOngoing() || printingIsPaused())); TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check()); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 01a1be4d59..243811d7fb 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -91,7 +91,11 @@ extern bool wait_for_heatup; #define PSU_OFF_SOON() powerManager.power_off_soon() #else #define PSU_ON() PSU_PIN_ON() - #define PSU_OFF() PSU_PIN_OFF() + #if ENABLED(PS_OFF_SOUND) + #define PSU_OFF() do{ BUZZ(1000, 659); PSU_PIN_OFF(); }while(0) + #else + #define PSU_OFF() PSU_PIN_OFF() + #endif #define PSU_OFF_SOON PSU_OFF #endif #endif diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 519b2308d0..9b173d6ee7 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -50,6 +50,9 @@ Power powerManager; millis_t Power::lastPowerOn; bool Power::is_power_needed() { + + if (printJobOngoing() || printingIsPaused()) return true; + #if ENABLED(AUTO_POWER_FANS) FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; #endif @@ -110,9 +113,17 @@ bool Power::is_power_needed() { #define POWER_TIMEOUT 0 #endif -void Power::check() { +void Power::check(const bool pause) { + static bool _pause = false; static millis_t nextPowerCheck = 0; - millis_t now = millis(); + const millis_t now = millis(); + #if POWER_TIMEOUT > 0 + if (pause != _pause) { + lastPowerOn = now + !now; + _pause = pause; + } + if (pause) return; + #endif if (ELAPSED(now, nextPowerCheck)) { nextPowerCheck = now + 2500UL; if (is_power_needed()) @@ -123,7 +134,8 @@ void Power::check() { } void Power::power_on() { - lastPowerOn = millis(); + const millis_t now = millis(); + lastPowerOn = now + !now; if (!powersupply_on) { PSU_PIN_ON(); safe_delay(PSU_POWERUP_DELAY); @@ -152,6 +164,7 @@ void Power::power_off() { void Power::power_off_soon() { #if POWER_OFF_DELAY lastPowerOn = millis() - SEC_TO_MS(POWER_TIMEOUT) + SEC_TO_MS(POWER_OFF_DELAY); + //if (!lastPowerOn) ++lastPowerOn; #else power_off(); #endif diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 2462b9231b..bca5432946 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -29,7 +29,7 @@ class Power { public: - static void check(); + static void check(const bool pause); static void power_on(); static void power_off(); static void power_off_soon(); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 87ecc48366..7531fae674 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -529,10 +529,13 @@ public: static void draw_select_screen_prompt(PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr); - #elif HAS_WIRED_LCD + #else static constexpr bool on_status_screen() { return true; } - FORCE_INLINE static void run_current_screen() { status_screen(); } + + #if HAS_WIRED_LCD + FORCE_INLINE static void run_current_screen() { status_screen(); } + #endif #endif From b90de621971656df4c0030cd04a3b4c782e4511d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 29 Jun 2021 16:25:37 -0500 Subject: [PATCH 0336/2168] =?UTF-8?q?=F0=9F=94=A8=20Clean=20up=20build=20s?= =?UTF-8?q?cripts=20(#22264)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add 10K to marlin_blackSTM32F407VET6 (typo?) * Document custom build scripts. * Add a Robin common build script. * Extraneous .ldscript specifiers --- .../PlatformIO/boards/marlin_blackSTM32F407VET6.json | 2 +- buildroot/share/PlatformIO/scripts/custom_board.py | 3 +++ buildroot/share/PlatformIO/scripts/marlin.py | 8 -------- buildroot/share/PlatformIO/scripts/mks_robin.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_e3.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_e3p.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_lite.py | 4 ++-- .../share/PlatformIO/scripts/mks_robin_lite3.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_mini.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_nano.py | 4 ++-- .../share/PlatformIO/scripts/mks_robin_nano35.py | 4 ++-- buildroot/share/PlatformIO/scripts/mks_robin_pro.py | 4 ++-- buildroot/share/PlatformIO/scripts/robin.py | 12 ++++++++++++ .../share/PlatformIO/scripts/stm32_bootloader.py | 7 +++++++ ini/stm32f1.ini | 7 ------- ini/stm32f4.ini | 5 ----- 16 files changed, 41 insertions(+), 39 deletions(-) create mode 100644 buildroot/share/PlatformIO/scripts/robin.py diff --git a/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json index 1765634086..a3f130c6b1 100644 --- a/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json +++ b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json @@ -48,7 +48,7 @@ "upload": { "disable_flushing": false, "maximum_ram_size": 131072, - "maximum_size": 514288, + "maximum_size": 524288, "protocol": "stlink", "protocols": [ "stlink", diff --git a/buildroot/share/PlatformIO/scripts/custom_board.py b/buildroot/share/PlatformIO/scripts/custom_board.py index 5d3ca3c652..e462738190 100644 --- a/buildroot/share/PlatformIO/scripts/custom_board.py +++ b/buildroot/share/PlatformIO/scripts/custom_board.py @@ -1,6 +1,9 @@ # # buildroot/share/PlatformIO/scripts/custom_board.py # +# - For build.address replace VECT_TAB_ADDR to relocate the firmware +# - For build.ldscript use one of the linker scripts in buildroot/share/PlatformIO/ldscripts +# import marlin board = marlin.env.BoardConfig() diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 23c1b95742..3949037904 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -67,11 +67,3 @@ def encrypt_mks(source, target, env, new_name): def add_post_action(action): env.AddPostAction(join("$BUILD_DIR", "${PROGNAME}.bin"), action); - -# Apply customizations for a MKS Robin -def prepare_robin(address, ldname, fwname): - def encrypt(source, target, env): - encrypt_mks(source, target, env, fwname) - relocate_firmware(address) - custom_ld_script(ldname) - add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/mks_robin.py b/buildroot/share/PlatformIO/scripts/mks_robin.py index 8c5e4ae276..2dea7c615f 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin.ld", "Robin.bin") +import robin +robin.prepare("0x08007000", "mks_robin.ld", "Robin.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py index 7f6f538d6a..6ddeccbf80 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_e3.py # -import marlin -marlin.prepare_robin("0x08005000", "mks_robin_e3.ld", "Robin_e3.bin") +import robin +robin.prepare("0x08005000", "mks_robin_e3.ld", "Robin_e3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py index 1f3cacf873..5eeb93c096 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_e3p.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin_e3p.ld", "Robin_e3p.bin") +import robin +robin.prepare("0x08007000", "mks_robin_e3p.ld", "Robin_e3p.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py index b8c039ada8..c2018336fd 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_lite.py # -import marlin -marlin.prepare_robin("0x08005000", "mks_robin_lite.ld", "mksLite.bin") +import robin +robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py index bea8b80ace..42c8fb18b6 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_lite3.py # -import marlin -marlin.prepare_robin("0x08005000", "mks_robin_lite.ld", "mksLite3.bin") +import robin +robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py index 3ff9ccf4a6..b0d8388653 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_mini.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin_mini.ld", "Robin_mini.bin") +import robin +robin.prepare("0x08007000", "mks_robin_mini.ld", "Robin_mini.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py index 319b4d4982..35e99830c4 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_nano.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin_nano.ld", "Robin_nano.bin") +import robin +robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py index 310c3d6606..4a5726ad5b 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_nano35.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin_nano.ld", "Robin_nano35.bin") +import robin +robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano35.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py index c624663a33..60e2482bb0 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py @@ -1,5 +1,5 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_pro.py # -import marlin -marlin.prepare_robin("0x08007000", "mks_robin_pro.ld", "Robin_pro.bin") +import robin +robin.prepare("0x08007000", "mks_robin_pro.ld", "Robin_pro.bin") diff --git a/buildroot/share/PlatformIO/scripts/robin.py b/buildroot/share/PlatformIO/scripts/robin.py new file mode 100644 index 0000000000..50d0d92d2f --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/robin.py @@ -0,0 +1,12 @@ +# +# buildroot/share/PlatformIO/scripts/robin.py +# +import marlin + +# Apply customizations for a MKS Robin +def prepare(address, ldname, fwname): + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, fwname) + marlin.relocate_firmware(address) + marlin.custom_ld_script(ldname) + marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py index eb28b901d2..f3b1b273a2 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -1,6 +1,13 @@ # # stm32_bootloader.py # +# - If 'build.offset' is provided, either by JSON or by the environment... +# - Set linker flag LD_FLASH_OFFSET and relocate the VTAB based on 'build.offset'. +# - Set linker flag LD_MAX_DATA_SIZE based on 'build.maximum_ram_size'. +# - Define STM32_FLASH_SIZE from 'upload.maximum_size' for use by Flash-based EEPROM emulation. +# +# - For 'board_build.rename' add a post-action to rename the firmware file. +# import os,sys,marlin Import("env") diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 3f09a45c7b..0b394d1730 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -41,7 +41,6 @@ board = genericSTM32F103RC monitor_speed = 115200 board_build.core = stm32 board_build.variant = MARLIN_F103Rx -board_build.ldscript = ldscript.ld extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -108,7 +107,6 @@ extends = common_stm32 board = genericSTM32F103ZE board_build.core = stm32 board_build.variant = MARLIN_F103Zx -board_build.ldscript = ldscript.ld board_build.offset = 0x7000 board_build.encrypt = Robin.bin build_flags = ${common_stm32.build_flags} @@ -150,7 +148,6 @@ monitor_speed = 115200 board_build.core = stm32 board_build.variant = MARLIN_F103Rx board_build.offset = 0x7000 -board_build.ldscript = ldscript.ld board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC extra_scripts = ${common.extra_scripts} @@ -175,7 +172,6 @@ monitor_speed = 115200 board_build.core = stm32 board_build.variant = MARLIN_F103Rx board_build.offset = 0x7000 -board_build.ldscript = ldscript.ld board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} extra_scripts = ${common.extra_scripts} @@ -207,7 +203,6 @@ build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER= board = genericSTM32F103VE board_build.core = stm32 board_build.variant = MARLIN_F103Vx -board_build.ldscript = ldscript.ld board_build.offset = 0x7000 board_build.encrypt = Robin_mini.bin board_upload.offset_address = 0x08007000 @@ -227,7 +222,6 @@ build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER= board = genericSTM32F103VE board_build.core = stm32 board_build.variant = MARLIN_F103Vx -board_build.ldscript = ldscript.ld board_build.offset = 0x7000 board_build.encrypt = Robin_nano35.bin board_upload.offset_address = 0x08007000 @@ -248,7 +242,6 @@ extends = common_stm32 board = genericSTM32F103ZE board_build.core = stm32 board_build.variant = MARLIN_F103Zx -board_build.ldscript = ldscript.ld board_build.offset = 0x10000 build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index ee88135eca..e7695dcc7a 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -112,7 +112,6 @@ build_flags = ${common_stm32.build_flags} -DHAL_SD_MODULE_ENABLED -DHAL board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx -board_build.ldscript = ldscript.ld board_build.encrypt = firmware.srec # Just openblt.py (not stm32_bootloader.py) generates the file board_build.offset = 0x10000 @@ -222,7 +221,6 @@ extends = common_stm32 board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx -board_build.ldscript = ldscript.ld board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 extra_scripts = ${common.extra_scripts} @@ -344,7 +342,6 @@ upload_protocol = dfu monitor_speed = 500000 board_build.core = stm32 board_build.variant = MARLIN_F446VE -board_build.ldscript = ldscript.ld board_build.offset = 0x0000 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -361,7 +358,6 @@ build_flags = ${stm_flash_drive.build_flags} board = genericSTM32F407VET6 board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx -board_build.ldscript = ldscript.ld board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC @@ -387,7 +383,6 @@ build_flags = ${common_stm32.build_flags} ${stm32f4_I2C1.build_flags} - board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx -board_build.ldscript = ldscript.ld board_build.rename = Robin_nano_v3.bin board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 From 415166e02c981d21d1b2ee8e7ba9a0f90927cf04 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 30 Jun 2021 01:00:32 +0000 Subject: [PATCH 0337/2168] [cron] Bump distribution date (2021-06-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fdd672ec0e..bd6e276fd4 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 "2021-06-29" + #define STRING_DISTRIBUTION_DATE "2021-06-30" #endif /** From 106eee071bd8d17148477c33aefabfa5755ad1e1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 1 Jul 2021 01:00:20 +0000 Subject: [PATCH 0338/2168] [cron] Bump distribution date (2021-07-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bd6e276fd4..63e2ed957f 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 "2021-06-30" + #define STRING_DISTRIBUTION_DATE "2021-07-01" #endif /** From 03a469724af05223be2a8bac71a1082c9ebbc55c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 30 Jun 2021 21:58:25 -0500 Subject: [PATCH 0339/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20Z=5FSAFE=5FHO?= =?UTF-8?q?MING=20description?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 6fc4a7cd4c..3b3087e46f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1700,15 +1700,13 @@ //#define MANUAL_J_HOME_POS 0 //#define MANUAL_K_HOME_POS 0 -// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. -// -// With this feature enabled: -// -// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. -// - If stepper drivers time out, it will need X and Y homing again before Z homing. -// - Move the Z probe (or nozzle) to a defined XY point before Z Homing. -// - Prevent Z homing when the Z probe is outside bed area. -// +/** + * Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. + * + * - Moves the Z probe (or nozzle) to a defined XY point before Z homing. + * - Allows Z homing only when XY positions are known and trusted. + * - If stepper drivers sleep, XY homing may be required again before Z homing. + */ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) From e96720c0760c7b66367f08fcd081648dac070cc9 Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 2 Jul 2021 09:27:27 +1200 Subject: [PATCH 0340/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Arduino=20IDE=20?= =?UTF-8?q?build=20(TOUCH=5FUI=5FFTDI=5FEVE=20includes)=20(#22276)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp | 2 +- .../ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp | 2 +- Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h | 6 +++++- Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h | 2 +- Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp | 2 +- 5 files changed, 9 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index a64c237fa1..1d4711c0e2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -20,7 +20,7 @@ * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp index ea8d403753..b4165a742a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp @@ -20,7 +20,7 @@ * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "media_file_reader.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h index 76b231536b..05e19b20e4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/config.h @@ -21,6 +21,10 @@ #pragma once +// Configure this display with options in Configuration_adv.h +#include "../../../inc/MarlinConfigPre.h" +#if ENABLED(TOUCH_UI_FTDI_EVE) + #include "compat.h" -// Configure this display with options in Configuration_adv.h +#endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h index f118303d21..4fe4cb938a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -22,7 +22,7 @@ #pragma once -#include "compat.h" +#include "config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp index afbed0cab1..1ed712ded1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp @@ -20,7 +20,7 @@ * location: . * ****************************************************************************/ -#include "../compat.h" +#include "../config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) From 71bf61901c6469ed47cc068f34ce952d9e5d55f5 Mon Sep 17 00:00:00 2001 From: Cytown Date: Fri, 2 Jul 2021 08:37:44 +0800 Subject: [PATCH 0341/2168] =?UTF-8?q?=F0=9F=9A=B8=20Filament=20Change=20ad?= =?UTF-8?q?d=20confirm=20step=20(#22277)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_filament.cpp | 17 +++++++++++++---- Marlin/src/lcd/menu/menu_main.cpp | 10 +++++----- 2 files changed, 18 insertions(+), 9 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index c6b8568085..d70ed98aa8 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -106,10 +106,11 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { * "Change Filament" submenu */ #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - bool printingIsPaused(); +#endif - void menu_change_filament() { +void menu_change_filament() { + #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) // Say "filament change" when no print is active editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; @@ -204,8 +205,16 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { #endif END_MENU(); - } -#endif + + #else + + if (thermalManager.targetHotEnoughToExtrude(active_extruder)) + queue.inject_P(PSTR("M600B0")); + else + _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); + + #endif +} static uint8_t hotend_status_extruder = 0; diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 1e79edb864..4e3310f238 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -77,7 +77,6 @@ void menu_configuration(); #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - void _menu_temp_filament_op(const PauseMode, const int8_t); void menu_change_filament(); #endif @@ -365,10 +364,11 @@ void menu_main() { #if ENABLED(ADVANCED_PAUSE_FEATURE) #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) - if (thermalManager.targetHotEnoughToExtrude(active_extruder)) - GCODES_ITEM(MSG_FILAMENTCHANGE, PSTR("M600 B0")); - else - SUBMENU(MSG_FILAMENTCHANGE, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); + CONFIRM_ITEM(MSG_FILAMENTCHANGE, + MSG_YES, MSG_NO, + menu_change_filament, ui.goto_previous_screen, + GET_TEXT(MSG_FILAMENTCHANGE), (const char *)nullptr, PSTR("?") + ); #else SUBMENU(MSG_FILAMENTCHANGE, menu_change_filament); #endif From 2566f5e0f3fd3103b614606205dcd98d789dbdfc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 2 Jul 2021 01:01:44 +0000 Subject: [PATCH 0342/2168] [cron] Bump distribution date (2021-07-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 63e2ed957f..01fac61279 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 "2021-07-01" + #define STRING_DISTRIBUTION_DATE "2021-07-02" #endif /** From ee4c1839d49766f4f62a9ba14cfbcf82b525be57 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 3 Jul 2021 00:55:59 +0000 Subject: [PATCH 0343/2168] [cron] Bump distribution date (2021-07-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 01fac61279..9cb35a7f54 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 "2021-07-02" + #define STRING_DISTRIBUTION_DATE "2021-07-03" #endif /** From cff2d16be66cd88828d5d968cdecb2c6042e7163 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 4 Jul 2021 00:58:37 +0000 Subject: [PATCH 0344/2168] [cron] Bump distribution date (2021-07-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9cb35a7f54..cc52c73020 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 "2021-07-03" + #define STRING_DISTRIBUTION_DATE "2021-07-04" #endif /** From de38cae00cf45ef864e2df180a9d37dc509817a4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 5 Jul 2021 00:56:12 +0000 Subject: [PATCH 0345/2168] [cron] Bump distribution date (2021-07-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cc52c73020..5fdcc7c728 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 "2021-07-04" + #define STRING_DISTRIBUTION_DATE "2021-07-05" #endif /** From 9eb5444c20b552cc39a668a22ce68536bff3664d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 6 Jul 2021 01:00:11 +0000 Subject: [PATCH 0346/2168] [cron] Bump distribution date (2021-07-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5fdcc7c728..b432c821ac 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 "2021-07-05" + #define STRING_DISTRIBUTION_DATE "2021-07-06" #endif /** From b2f0913083d83bd3fd9af1c603d1f4cc1afb64eb Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Tue, 6 Jul 2021 17:36:41 -0700 Subject: [PATCH 0347/2168] =?UTF-8?q?=F0=9F=90=9B=20Redundant=20Temp=20Sen?= =?UTF-8?q?sor=20followup=20(#22196)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 136 ++-- Marlin/Configuration_adv.h | 19 +- Marlin/src/HAL/SAMD51/inc/SanityCheck.h | 3 +- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/core/macros.h | 4 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 12 +- Marlin/src/inc/Conditionals_post.h | 469 +++++++------ Marlin/src/inc/SanityCheck.h | 136 ++-- Marlin/src/libs/MAX31865.cpp | 500 ++++++++++++++ Marlin/src/libs/MAX31865.h | 131 ++++ Marlin/src/module/motion.cpp | 3 +- Marlin/src/module/temperature.cpp | 626 +++++++++--------- Marlin/src/module/temperature.h | 20 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 6 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 13 + Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 4 +- Marlin/src/pins/mega/pins_MALYAN_M180.h | 18 +- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 18 +- Marlin/src/pins/mega/pins_PICA.h | 6 +- Marlin/src/pins/pinsDebug_list.h | 40 +- Marlin/src/pins/rambo/pins_RAMBO.h | 6 +- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 6 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 6 +- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 6 +- Marlin/src/pins/ramps/pins_RAMPS.h | 6 +- Marlin/src/pins/ramps/pins_RAMPS_OLD.h | 6 +- Marlin/src/pins/ramps/pins_RIGIDBOARD.h | 8 +- Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h | 6 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 6 +- Marlin/src/pins/sam/pins_DUE3DOM.h | 6 +- Marlin/src/pins/sam/pins_DUE3DOM_MINI.h | 6 +- Marlin/src/pins/sam/pins_RADDS.h | 6 +- Marlin/src/pins/sam/pins_RAMPS_DUO.h | 8 +- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 6 +- Marlin/src/pins/sam/pins_RAMPS_SMART.h | 8 +- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 6 +- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 6 +- Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h | 11 +- .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 8 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 4 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 4 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 4 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 4 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 20 +- Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 12 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 4 +- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 4 +- ini/features.ini | 2 +- platformio.ini | 1 + 49 files changed, 1567 insertions(+), 787 deletions(-) create mode 100644 Marlin/src/libs/MAX31865.cpp create mode 100644 Marlin/src/libs/MAX31865.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 3b3087e46f..e9a49b6056 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -397,70 +397,92 @@ // @section temperature /** - * --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table + * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table * * Temperature sensors available: * - * -5 : PT100 / PT1000 with MAX31865 (only for sensors 0-1) - * -3 : thermocouple with MAX31855 (only for sensors 0-1) - * -2 : thermocouple with MAX6675 (only for sensors 0-1) - * -4 : thermocouple with AD8495 - * -1 : thermocouple with AD595 + * SPI RTD/Thermocouple Boards - IMPORTANT: Read the NOTE below! + * ------- + * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) + * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. + * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) + * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) + * + * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, + * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, + * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the + * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. + * + * Analog Themocouple Boards + * ------- + * -4 : AD8495 with Thermocouple + * -1 : AD595 with Thermocouple + * + * Analog Thermistors - 4.7kΩ pullup - Normal + * ------- + * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors + * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA + * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE + * 2 : 200kΩ ATC Semitec 204GT-2 + * 202 : 200kΩ Copymaster 3D + * 3 : ???Ω Mendel-parts thermistor + * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! + * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C + * 501 : 100kΩ Zonestar - Tronxy X3A + * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M + * 512 : 100kΩ RPW-Ultra hotend + * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) + * 7 : 100kΩ Honeywell 135-104LAG-J01 + * 71 : 100kΩ Honeywell 135-104LAF-J01 + * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT + * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 + * 10 : 100kΩ RS PRO 198-961 + * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% + * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed + * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% + * 15 : 100kΩ Calibrated for JGAurora A5 hotend + * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 + * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input + * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input + * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 + * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 + * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 + * 66 : 4.7MΩ Dyze Design High Temperature Thermistor + * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 70 : 100kΩ bq Hephestos 2 + * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * + * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. + * ------- (but gives greater accuracy and more stable PID) + * 51 : 100kΩ EPCOS (1kΩ pullup) + * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) + * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) + * + * Analog Thermistors - 10kΩ pullup - Atypical + * ------- + * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor + * + * Analog RTDs (Pt100/Pt1000) + * ------- + * 110 : Pt100 with 1kΩ pullup (atypical) + * 147 : Pt100 with 4.7kΩ pullup + * 1010 : Pt1000 with 1kΩ pullup (atypical) + * 1047 : Pt1000 with 4.7kΩ pullup (E3D) + * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. + * NOTE: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. + * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v ADC reference voltage (STM32, LPC176x....) and 5V INA826 amplifier board supply. + * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. + * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x + * + * Custom/Dummy/Other Thermos + * ------ * 0 : not used - * 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup) - * 331 : (3.3V scaled thermistor 1 table for MEGA) - * 332 : (3.3V scaled thermistor 1 table for DUE) - * 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) - * 202 : 200k thermistor - Copymaster 3D - * 3 : Mendel-parts thermistor (4.7k pullup) - * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! - * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup) - * 501 : 100K Zonestar (Tronxy X3A) Thermistor - * 502 : 100K Zonestar Thermistor used by hot bed in Zonestar Průša P802M - * 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup) - * 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) - * 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup) - * 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup) - * 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) - * 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) - * 10 : 100k RS thermistor 198-961 (4.7k pullup) - * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup) - * 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) - * 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE" - * 15 : 100k thermistor calibration for JGAurora A5 hotend - * 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. - * NOTES: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. - * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v ADC reference voltage (STM32, LPC176x....) and 5V INA826 amplifier board supply. - * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. - * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) - * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) - * 30 : Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K / B3950 (4.7k pullup) - * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x - * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 - * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup - * 66 : 4.7M High Temperature thermistor from Dyze Design - * 67 : 450C thermistor from SliceEngineering - * 70 : the 100K thermistor found in the bq Hephestos 2 - * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor - * 99 : 100k thermistor with a 10K pull-up resistor (found on some Wanhao i3 machines) - * - * 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k. - * (but gives greater accuracy and more stable PID) - * 51 : 100k thermistor - EPCOS (1k pullup) - * 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup) - * 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) - * - * 1047 : Pt1000 with 4k7 pullup (E3D) - * 1010 : Pt1000 with 1k pullup (non standard) - * 147 : Pt100 with 4k7 pullup - * 110 : Pt100 with 1k pullup (non standard) - * * 1000 : Custom - Specify parameters in Configuration_adv.h * - * Use these for Testing or Development purposes. NEVER for production machine. + * !!! Use these for Testing or Development purposes. NEVER for production machine. !!! * 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below. * 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below. + * */ #define TEMP_SENSOR_0 1 #define TEMP_SENSOR_1 0 @@ -482,7 +504,7 @@ // Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 //#define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) -//#define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for AdaFruit PT100; 4300 for AdaFruit PT1000 +//#define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 //#define MAX31865_SENSOR_OHMS_1 100 //#define MAX31865_CALIBRATION_OHMS_1 430 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 818edecea2..6a7219383b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -131,10 +131,21 @@ #define REDUNDANT_BETA 3950 // Beta value #endif -// -// Hephestos 2 24V heated bed upgrade kit. -// https://store.bq.com/en/heated-bed-kit-hephestos2 -// +/** + * Configuration options for MAX Thermocouples (-2, -3, -5). + * FORCE_HW_SPI: Ignore SCK/MOSI/MISO pins and just use the CS pin & default SPI bus. + * MAX31865_WIRES: Set the number of wires for the probe connected to a MAX31865 board, 2-4. Default: 2 + * MAX31865_50HZ: Enable 50Hz filter instead of the default 60Hz. + */ +//#define TEMP_SENSOR_FORCE_HW_SPI +//#define MAX31865_SENSOR_WIRES_0 2 +//#define MAX31865_SENSOR_WIRES_1 2 +//#define MAX31865_50HZ_FILTER + +/** + * Hephestos 2 24V heated bed upgrade kit. + * https://store.bq.com/en/heated-bed-kit-hephestos2 + */ //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef TEMP_SENSOR_BED diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index 2a4bde98e6..38c6dd9e08 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -31,7 +31,8 @@ #error "No custom SD drive cable defined for this board." #endif -#if defined(MAX6675_SCK_PIN) && defined(MAX6675_DO_PIN) && (MAX6675_SCK_PIN == SCK1 || MAX6675_DO_PIN == MISO1) +#if (defined(TEMP_0_SCK_PIN) && defined(TEMP_0_MISO_PIN) && (TEMP_0_SCK_PIN == SCK1 || TEMP_0_MISO_PIN == MISO1)) || \ + (defined(TEMP_1_SCK_PIN) && defined(TEMP_1_MISO_PIN) && (TEMP_1_SCK_PIN == SCK1 || TEMP_1_MISO_PIN == MISO1)) #error "OnBoard SPI BUS can't be shared with other devices." #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 254283da5b..dc9fbb2ba7 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1169,10 +1169,10 @@ void setup() { // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0) - OUT_WRITE(MAX6675_SS_PIN, HIGH); // Disable + OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable #endif #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) - OUT_WRITE(MAX6675_SS2_PIN, HIGH); // Disable + OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 295eee9bcf..05640bce87 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -204,8 +204,8 @@ #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 _OPTARG(A) , A -#define OPTARG(O,A) TERN_(O,DEFER4(_OPTARG)(A)) +#define _OPTARG(A...) , A +#define OPTARG(O,A...) TERN_(O,DEFER4(_OPTARG)(A)) #define _OPTCODE(A) A; #define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 6869962028..50f3419c89 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -314,11 +314,13 @@ void GcodeSuite::G34() { sprintf_P(msg, PSTR("1:2=%s" TERN_(TRIPLE_Z, " 3-2=%s 3-1=%s") TERN_(QUAD_Z, " 4-3=%s 4-2=%s 4-1=%s")), dtostrf(ABS(z_measured[1] - z_measured[0]), 1, 3, fstr1) - OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2)) - OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) - OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4)) - OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5)) - OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) + OPTARG(TRIPLE_Z, + dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2), + dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) + OPTARG(QUAD_Z, + dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4), + dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5), + dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) ); ui.set_status(msg); #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 45271bca72..2f5af2b700 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -615,20 +615,21 @@ #if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 #define TEMP_SENSOR_0_IS_MAX_TC 1 - #define HAS_MAX_TC 1 - #if TEMP_SENSOR_0 == -3 - #define TEMP_SENSOR_0_MAX_TC_TMIN -270 - #define TEMP_SENSOR_0_MAX_TC_TMAX 1800 - #else - #define TEMP_SENSOR_0_MAX_TC_TMIN 0 - #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 - #endif #if TEMP_SENSOR_0 == -5 #define TEMP_SENSOR_0_IS_MAX31865 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif #elif TEMP_SENSOR_0 == -3 #define TEMP_SENSOR_0_IS_MAX31855 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN -270 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1800 #elif TEMP_SENSOR_0 == -2 #define TEMP_SENSOR_0_IS_MAX6675 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 #endif #elif TEMP_SENSOR_0 == -4 #define TEMP_SENSOR_0_IS_AD8495 1 @@ -648,21 +649,23 @@ #if TEMP_SENSOR_1 == -5 || TEMP_SENSOR_1 == -3 || TEMP_SENSOR_1 == -2 #define TEMP_SENSOR_1_IS_MAX_TC 1 - #define HAS_MAX_TC 1 - #if TEMP_SENSOR_1 == -3 + #if TEMP_SENSOR_1 == -5 + #define TEMP_SENSOR_1_IS_MAX31865 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN 0 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #elif TEMP_SENSOR_1 == -3 + #define TEMP_SENSOR_1_IS_MAX31855 1 #define TEMP_SENSOR_1_MAX_TC_TMIN -270 #define TEMP_SENSOR_1_MAX_TC_TMAX 1800 - #else + #elif TEMP_SENSOR_1 == -2 + #define TEMP_SENSOR_1_IS_MAX6675 1 #define TEMP_SENSOR_1_MAX_TC_TMIN 0 #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 #endif - #if TEMP_SENSOR_1 == -5 - #define TEMP_SENSOR_1_IS_MAX31865 1 - #elif TEMP_SENSOR_1 == -3 - #define TEMP_SENSOR_1_IS_MAX31855 1 - #elif TEMP_SENSOR_1 == -2 - #define TEMP_SENSOR_1_IS_MAX6675 1 - #endif + #if TEMP_SENSOR_1 != TEMP_SENSOR_0 #if TEMP_SENSOR_1 == -5 #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." @@ -690,37 +693,48 @@ #if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 - #define HAS_MAX_TC 1 - #if TEMP_SENSOR_REDUNDANT == -3 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 - #else - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 - #endif - #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 - #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN - #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 - #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN - #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - #endif + #if TEMP_SENSOR_REDUNDANT == -5 #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif - #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 + + #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #elif TEMP_SENSOR_REDUNDANT == -3 #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif - #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 + + #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 #elif TEMP_SENSOR_REDUNDANT == -2 #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif - #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 + + #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #endif + + // mimic setting up the source TEMP_SENSOR + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #endif + #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) #if TEMP_SENSOR_REDUNDANT == -5 #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." @@ -743,101 +757,182 @@ #endif #endif +#if TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC + #define HAS_MAX_TC 1 +#endif +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 + #define HAS_MAX6675 1 +#endif #if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 #define HAS_MAX31855 1 #endif #if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 #define HAS_MAX31865 1 #endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 - #define HAS_MAX6675 1 -#endif // // Compatibility layer for MAX (SPI) temp boards // -#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) +#if HAS_MAX_TC -#if PIN_EXISTS(MAX6675_SS) - #if TEMP_SENSOR_IS_MAX(0, MAX31855) - #define MAX31855_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_IS_MAX(0, MAX31865) - #define MAX31865_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_IS_MAX(0, MAX6675) - #define MAX6675_CS_PIN MAX6675_SS_PIN + // Translate old _SS, _CS, _SCK, _DO, _DI, _MISO, and _MOSI PIN defines. + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + + #if !PIN_EXISTS(TEMP_0_CS) // SS, CS + #if PIN_EXISTS(MAX6675_SS) + #define TEMP_0_CS_PIN MAX6675_SS_PIN + #elif PIN_EXISTS(MAX6675_CS) + #define TEMP_0_CS_PIN MAX6675_CS_PIN + #elif PIN_EXISTS(MAX31855_SS) + #define TEMP_0_CS_PIN MAX31855_SS_PIN + #elif PIN_EXISTS(MAX31855_CS) + #define TEMP_0_CS_PIN MAX31855_CS_PIN + #elif PIN_EXISTS(MAX31865_SS) + #define TEMP_0_CS_PIN MAX31865_SS_PIN + #elif PIN_EXISTS(MAX31865_CS) + #define TEMP_0_CS_PIN MAX31865_CS_PIN + #endif + #endif + + #if TEMP_SENSOR_0_IS_MAX6675 + #if !PIN_EXISTS(TEMP_0_MISO) // DO + #if PIN_EXISTS(MAX6675_MISO) + #define TEMP_0_MISO_PIN MAX6675_MISO_PIN + #elif PIN_EXISTS(MAX6675_DO) + #define TEMP_0_MISO_PIN MAX6675_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_0_SCK) && PIN_EXISTS(MAX6675_SCK) + #define TEMP_0_SCK_PIN MAX6675_SCK_PIN + #endif + + #elif TEMP_SENSOR_0_IS_MAX31855 + #if !PIN_EXISTS(TEMP_0_MISO) // DO + #if PIN_EXISTS(MAX31855_MISO) + #define TEMP_0_MISO_PIN MAX31855_MISO_PIN + #elif PIN_EXISTS(MAX31855_DO) + #define TEMP_0_MISO_PIN MAX31855_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_0_SCK) && PIN_EXISTS(MAX31855_SCK) + #define TEMP_0_SCK_PIN MAX31855_SCK_PIN + #endif + + #elif TEMP_SENSOR_1_IS_MAX31865 + #if !PIN_EXISTS(TEMP_1_MISO) // DO + #if PIN_EXISTS(MAX31865_MISO) + #define TEMP_1_MISO_PIN MAX31865_MISO_PIN + #elif PIN_EXISTS(MAX31865_DO) + #define TEMP_1_MISO_PIN MAX31865_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX31865_SCK) + #define TEMP_1_SCK_PIN MAX31865_SCK_PIN + #endif + #if !PIN_EXISTS(TEMP_1_MOSI) && PIN_EXISTS(MAX31865_MOSI) // MOSI for '65 only + #define TEMP_1_MOSI_PIN MAX31865_MOSI_PIN + #endif + #endif + + // Software SPI - enable if MISO/SCK are defined. + #if PIN_EXISTS(TEMP_0_MISO) && PIN_EXISTS(TEMP_0_SCK) && DISABLED(TEMP_SENSOR_0_FORCE_HW_SPI) + #if TEMP_SENSOR_0_IS_MAX31865 && !PIN_EXISTS(TEMP_0_MOSI) + #error "TEMP_SENSOR_0 MAX31865 requires TEMP_0_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_0_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_0_HAS_SPI_PINS 1 + #endif + #endif + + #endif // TEMP_SENSOR_0_IS_MAX_TC + + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + + #if !PIN_EXISTS(TEMP_1_CS) // SS2, CS2 + #if PIN_EXISTS(MAX6675_SS2) + #define TEMP_1_CS_PIN MAX6675_SS2_PIN + #elif PIN_EXISTS(MAX6675_CS) + #define TEMP_1_CS_PIN MAX6675_CS2_PIN + #elif PIN_EXISTS(MAX31855_SS2) + #define TEMP_1_CS_PIN MAX31855_SS2_PIN + #elif PIN_EXISTS(MAX31855_CS2) + #define TEMP_1_CS_PIN MAX31855_CS2_PIN + #elif PIN_EXISTS(MAX31865_SS2) + #define TEMP_1_CS_PIN MAX31865_SS2_PIN + #elif PIN_EXISTS(MAX31865_CS2) + #define TEMP_1_CS_PIN MAX31865_CS2_PIN + #endif + #endif + + #if TEMP_SENSOR_1_IS_MAX6675 + #if !PIN_EXISTS(TEMP_1_MISO) // DO + #if PIN_EXISTS(MAX6675_MISO) + #define TEMP_1_MISO_PIN MAX6675_MISO_PIN + #elif PIN_EXISTS(MAX6675_DO) + #define TEMP_1_MISO_PIN MAX6675_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX6675_SCK) + #define TEMP_1_SCK_PIN MAX6675_SCK_PIN + #endif + + #elif TEMP_SENSOR_1_IS_MAX31855 + #if !PIN_EXISTS(TEMP_1_MISO) // DO + #if PIN_EXISTS(MAX31855_MISO) + #define TEMP_1_MISO_PIN MAX31855_MISO_PIN + #elif PIN_EXISTS(MAX31855_DO) + #define TEMP_1_MISO_PIN MAX31855_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX31855_SCK) + #define TEMP_1_SCK_PIN MAX31855_SCK_PIN + #endif + + #elif TEMP_SENSOR_1_IS_MAX31865 + #if !PIN_EXISTS(TEMP_1_MISO) // DO + #if PIN_EXISTS(MAX31865_MISO) + #define TEMP_1_MISO_PIN MAX31865_MISO_PIN + #elif PIN_EXISTS(MAX31865_DO) + #define TEMP_1_MISO_PIN MAX31865_DO_PIN + #endif + #endif + #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX31865_SCK) + #define TEMP_1_SCK_PIN MAX31865_SCK_PIN + #endif + #if !PIN_EXISTS(TEMP_1_MOSI) && PIN_EXISTS(MAX31865_MOSI) // MOSI for '65 only + #define TEMP_1_MOSI_PIN MAX31865_MOSI_PIN + #endif + #endif + + // Software SPI - enable if MISO/SCK are defined. + #if PIN_EXISTS(TEMP_1_MISO) && PIN_EXISTS(TEMP_1_SCK) && DISABLED(TEMP_SENSOR_1_FORCE_HW_SPI) + #if TEMP_SENSOR_1_IS_MAX31865 && !PIN_EXISTS(TEMP_1_MOSI) + #error "TEMP_SENSOR_1 MAX31865 requires TEMP_1_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_1_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_1_HAS_SPI_PINS 1 + #endif + #endif + + #endif // TEMP_SENSOR_1_IS_MAX_TC + + // + // User-defined thermocouple libraries + // + // Add LIB_MAX6675 / LIB_MAX31855 / LIB_MAX31865 to the build_flags + // to select a USER library for MAX6675, MAX31855, MAX31865 + // + #if BOTH(HAS_MAX6675, LIB_MAX6675) + #define LIB_USR_MAX6675 1 #endif -#endif - -#if PIN_EXISTS(MAX6675_SS2) - #if TEMP_SENSOR_IS_MAX(1, MAX31855) - #define MAX31855_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_IS_MAX(1, MAX31865) - #define MAX31865_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_IS_MAX(1, MAX6675) - #define MAX6675_CS2_PIN MAX6675_SS2_PIN + #if BOTH(HAS_MAX31855, LIB_MAX31855) + #define LIB_USR_MAX31855 1 #endif -#endif - -#if PIN_EXISTS(MAX6675_DO) - #if HAS_MAX31855 - #define MAX31855_MISO_PIN MAX6675_DO_PIN - #elif HAS_MAX31865 - #define MAX31865_MISO_PIN MAX6675_DO_PIN - #elif HAS_MAX6675 - #define MAX6675_MISO_PIN MAX6675_DO_PIN - #endif -#endif - -#if PIN_EXISTS(MAX6675_SCK) - #if HAS_MAX31855 - #define MAX31855_SCK_PIN MAX6675_SCK_PIN - #elif HAS_MAX31865 - #define MAX31865_SCK_PIN MAX6675_SCK_PIN - #endif -#endif - -// Compatibility Layer for use when HAL manipulates PINS for MAX31855 and MAX6675 -#if PIN_EXISTS(MAX31855_CS) && !PIN_EXISTS(MAX6675_SS) - #define MAX6675_SS_PIN MAX31855_CS_PIN -#endif -#if PIN_EXISTS(MAX31855_CS2) && !PIN_EXISTS(MAX6675_SS2) - #define MAX6675_SS2_PIN MAX31855_CS2_PIN -#endif -#if PIN_EXISTS(MAX6675_CS) && !PIN_EXISTS(MAX6675_SS) - #define MAX6675_SS_PIN MAX6675_CS_PIN -#endif -#if PIN_EXISTS(MAX6675_CS2) && !PIN_EXISTS(MAX6675_SS2) - #define MAX6675_SS2_PIN MAX6675_CS2_PIN -#endif -#if PIN_EXISTS(MAX31855_MISO) && !PIN_EXISTS(MAX6675_DO) - #define MAX6675_DO_PIN MAX31855_MISO_PIN -#endif -#if PIN_EXISTS(MAX6675_MISO) && !PIN_EXISTS(MAX6675_DO) - #define MAX6675_DO_PIN MAX6675_MISO_PIN -#endif -#if PIN_EXISTS(MAX31855_SCK) && !PIN_EXISTS(MAX6675_SCK) - #define MAX6675_SCK_PIN MAX31855_SCK_PIN -#endif - -// -// User-defined thermocouple libraries -// -// Add LIB_MAX6675 / LIB_MAX31855 / LIB_MAX31865 to the build_flags -// to select a USER library for MAX6675, MAX31855, MAX31865 -// -#if BOTH(HAS_MAX6675, LIB_MAX6675) - #define LIB_USR_MAX6675 1 -#endif -#if BOTH(HAS_MAX31855, LIB_MAX31855) - #define LIB_USR_MAX31855 1 -#endif -#if HAS_MAX31865 - #if ENABLED(LIB_MAX31865) + #if BOTH(HAS_MAX31865, LIB_MAX31865) #define LIB_USR_MAX31865 1 - #else - #define LIB_ADAFRUIT_MAX31865 1 + #elif HAS_MAX31865 + #define LIB_INTERNAL_MAX31865 1 #endif -#endif + +#endif //HAS_MAX_TC #if TEMP_SENSOR_2 == -4 #define TEMP_SENSOR_2_IS_AD8495 1 @@ -2722,6 +2817,77 @@ #define BED_OR_CHAMBER_OR_FAN 1 #endif +/** + * Up to 3 PWM fans + */ +#ifndef FAN_INVERTING + #define FAN_INVERTING false +#endif + +#if HAS_FAN7 + #define FAN_COUNT 8 +#elif HAS_FAN6 + #define FAN_COUNT 7 +#elif HAS_FAN5 + #define FAN_COUNT 6 +#elif HAS_FAN4 + #define FAN_COUNT 5 +#elif HAS_FAN3 + #define FAN_COUNT 4 +#elif HAS_FAN2 + #define FAN_COUNT 3 +#elif HAS_FAN1 + #define FAN_COUNT 2 +#elif HAS_FAN0 + #define FAN_COUNT 1 +#else + #define FAN_COUNT 0 +#endif + +#if FAN_COUNT > 0 + #define HAS_FAN 1 +#endif + +/** + * Part Cooling fan multipliexer + */ +#if PIN_EXISTS(FANMUX0) + #define HAS_FANMUX 1 +#endif + +/** + * MIN/MAX fan PWM scaling + */ +#ifndef FAN_OFF_PWM + #define FAN_OFF_PWM 0 +#endif +#ifndef FAN_MIN_PWM + #if FAN_OFF_PWM > 0 + #define FAN_MIN_PWM (FAN_OFF_PWM + 1) + #else + #define FAN_MIN_PWM 0 + #endif +#endif +#ifndef FAN_MAX_PWM + #define FAN_MAX_PWM 255 +#endif +#if FAN_MIN_PWM < 0 || FAN_MIN_PWM > 255 + #error "FAN_MIN_PWM must be a value from 0 to 255." +#elif FAN_MAX_PWM < 0 || FAN_MAX_PWM > 255 + #error "FAN_MAX_PWM must be a value from 0 to 255." +#elif FAN_MIN_PWM > FAN_MAX_PWM + #error "FAN_MIN_PWM must be less than or equal to FAN_MAX_PWM." +#elif FAN_OFF_PWM > FAN_MIN_PWM + #error "FAN_OFF_PWM must be less than or equal to FAN_MIN_PWM." +#endif + +/** + * FAST PWM FAN Settings + */ +#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default +#endif + // Servos #if PIN_EXISTS(SERVO0) && NUM_SERVOS > 0 #define HAS_SERVO_0 1 @@ -2996,77 +3162,6 @@ #undef PREHEAT_SHORTCUT_MENU_ITEM #endif -/** - * Up to 3 PWM fans - */ -#ifndef FAN_INVERTING - #define FAN_INVERTING false -#endif - -#if HAS_FAN7 - #define FAN_COUNT 8 -#elif HAS_FAN6 - #define FAN_COUNT 7 -#elif HAS_FAN5 - #define FAN_COUNT 6 -#elif HAS_FAN4 - #define FAN_COUNT 5 -#elif HAS_FAN3 - #define FAN_COUNT 4 -#elif HAS_FAN2 - #define FAN_COUNT 3 -#elif HAS_FAN1 - #define FAN_COUNT 2 -#elif HAS_FAN0 - #define FAN_COUNT 1 -#else - #define FAN_COUNT 0 -#endif - -#if FAN_COUNT > 0 - #define HAS_FAN 1 -#endif - -/** - * Part Cooling fan multipliexer - */ -#if PIN_EXISTS(FANMUX0) - #define HAS_FANMUX 1 -#endif - -/** - * MIN/MAX fan PWM scaling - */ -#ifndef FAN_OFF_PWM - #define FAN_OFF_PWM 0 -#endif -#ifndef FAN_MIN_PWM - #if FAN_OFF_PWM > 0 - #define FAN_MIN_PWM (FAN_OFF_PWM + 1) - #else - #define FAN_MIN_PWM 0 - #endif -#endif -#ifndef FAN_MAX_PWM - #define FAN_MAX_PWM 255 -#endif -#if FAN_MIN_PWM < 0 || FAN_MIN_PWM > 255 - #error "FAN_MIN_PWM must be a value from 0 to 255." -#elif FAN_MAX_PWM < 0 || FAN_MAX_PWM > 255 - #error "FAN_MAX_PWM must be a value from 0 to 255." -#elif FAN_MIN_PWM > FAN_MAX_PWM - #error "FAN_MIN_PWM must be less than or equal to FAN_MAX_PWM." -#elif FAN_OFF_PWM > FAN_MIN_PWM - #error "FAN_OFF_PWM must be less than or equal to FAN_MIN_PWM." -#endif - -/** - * FAST PWM FAN Settings - */ -#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default -#endif - /** * MIN/MAX case light PWM scaling */ diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 36ccbee9b9..f416ca88bd 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -416,8 +416,19 @@ #error "MBL_Z_STEP is now MESH_EDIT_Z_STEP." #elif defined(CHDK) #error "CHDK is now CHDK_PIN." -#elif defined(MAX6675_SS) || defined(MAX6675_SS2) - #error "MAX6675_SS / MAX6675_SS2 is now MAX6675_SS_PIN / MAX6675_SS2_PIN." +#elif ANY_PIN( \ + MAX6675_SS, MAX6675_SS2, MAX6675_CS, MAX6675_CS2, \ + MAX31855_SS, MAX31855_SS2, MAX31855_CS, MAX31855_CS2, \ + MAX31865_SS, MAX31865_SS2, MAX31865_CS, MAX31865_CS2) + #warning "MAX*_SS_PIN, MAX*_SS2_PIN, MAX*_CS_PIN, and MAX*_CS2_PIN are deprecated and will be removed in a future version. Please use TEMP_0_CS_PIN/TEMP_1_CS_PIN instead." +#elif ANY_PIN(MAX6675_SCK, MAX31855_SCK, MAX31865_SCK) + #warning "MAX*_SCK_PIN is deprecated and will be removed in a future version. Please use TEMP_0_SCK_PIN/TEMP_1_SCK_PIN instead." +#elif ANY_PIN(MAX6675_MISO, MAX6675_DO, MAX31855_MISO, MAX31855_DO, MAX31865_MISO, MAX31865_DO) + #warning "MAX*_MISO_PIN and MAX*_DO_PIN are deprecated and will be removed in a future version. Please use TEMP_0_MISO_PIN/TEMP_1_MISO_PIN instead." +#elif PIN_EXISTS(MAX31865_MOSI) + #warning "MAX31865_MOSI_PIN is deprecated and will be removed in a future version. Please use TEMP_0_MOSI_PIN/TEMP_1_MOSI_PIN instead." +#elif ANY_PIN(THERMO_CS1_PIN, THERMO_CS2_PIN, THERMO_DO_PIN, THERMO_SCK_PIN) + #error "THERMO_*_PIN is now TEMP_n_CS_PIN, TEMP_n_SCK_PIN, TEMP_n_MOSI_PIN, TEMP_n_MISO_PIN." #elif defined(MAX31865_SENSOR_OHMS) #error "MAX31865_SENSOR_OHMS is now MAX31865_SENSOR_OHMS_0." #elif defined(MAX31865_CALIBRATION_OHMS) @@ -1953,14 +1964,21 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * Pins and Sensor IDs must be set for each heater + * Required MAX31865 settings */ -#if TEMP_SENSOR_0_IS_MAX6675 && !ANY_PIN(MAX6675_SS, MAX31855_CS, MAX31865_CS, MAX6675_CS) - #error "TEMP_SENSOR_0 -2 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." -#elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY - #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 - #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." +#if TEMP_SENSOR_0_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 0) + #if !defined(MAX31865_SENSOR_WIRES_0) || !WITHIN(MAX31865_SENSOR_WIRES_0, 2, 4) + #error "MAX31865_SENSOR_WIRES_0 must be defined as an integer between 2 and 4." + #elif !defined(MAX31865_SENSOR_OHMS_0) || !defined(MAX31865_CALIBRATION_OHMS_0) + #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." + #endif +#endif +#if TEMP_SENSOR_1_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + #if !defined(MAX31865_SENSOR_WIRES_1) || !WITHIN(MAX31865_SENSOR_WIRES_1, 2, 4) + #error "MAX31865_SENSOR_WIRES_1 must be defined as an integer between 2 and 4." + #elif !defined(MAX31865_SENSOR_OHMS_1) || !defined(MAX31865_CALIBRATION_OHMS_1) + #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1/TEMP_SENSOR_REDUNDANT is MAX31865." + #endif #endif /** @@ -2023,20 +2041,36 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Cooler (-5): requires TEMP_COOLER_PIN" #endif - #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 && !PIN_EXISTS(MAX6675_SS) - #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 0 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 && !PIN_EXISTS(MAX6675_SS2) - #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 1 requires a MAX6675_SS2_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 && !PIN_EXISTS(TEMP_0_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 0 requires TEMP_0_CS_PIN." + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 && !PIN_EXISTS(TEMP_1_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 1 requires TEMP_1_CS_PIN." #endif #endif +/** + * Test Sensor & Heater pin combos. + * Pins and Sensor IDs must be set for each heater + */ +#if !ANY_PIN(TEMP_0, TEMP_0_CS) + #error "TEMP_0_PIN or TEMP_0_CS_PIN not defined for this board." +#elif !HAS_HEATER_0 && EXTRUDERS + #error "HEATER_0_PIN not defined for this board." +#elif TEMP_SENSOR_0_IS_MAX_TC && !PIN_EXISTS(TEMP_0_CS) + #error "TEMP_SENSOR_0 MAX thermocouple requires TEMP_0_CS_PIN." +#elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY + #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." +#elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 + #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." +#endif + #if HAS_MULTI_HOTEND - #if TEMP_SENSOR_1_IS_MAX6675 && !ANY_PIN(MAX6675_SS2, MAX31855_CS2, MAX31865_CS2, MAX6675_CS2) - #error "TEMP_SENSOR_1 requires a MAX6675_SS2_PIN, MAX6675_CS2_PIN, MAX31855_CS2_PIN, or MAX31865_CS2_PIN." + #if TEMP_SENSOR_1_IS_MAX_TC && !PIN_EXISTS(TEMP_1_CS) + #error "TEMP_SENSOR_1 MAX thermocouple requires TEMP_1_CS_PIN." #elif TEMP_SENSOR_1 == 0 #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS." - #elif !ANY_PIN(TEMP_1, MAX6675_SS2) && !TEMP_SENSOR_1_IS_DUMMY - #error "TEMP_1_PIN or MAX6675_SS2_PIN not defined for this board." + #elif !ANY_PIN(TEMP_1, TEMP_1_CS) && !TEMP_SENSOR_1_IS_DUMMY + #error "TEMP_1_PIN or TEMP_1_CS_PIN not defined for this board." #endif #if HOTENDS > 2 #if TEMP_SENSOR_2 == 0 @@ -2148,14 +2182,31 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_6 shouldn't be set with only 1 HOTEND." #elif TEMP_SENSOR_7 != 0 #error "TEMP_SENSOR_7 shouldn't be set with only 1 HOTEND." -#endif +#endif // HAS_MULTI_HOTEND +/** + * Pins must be set for temp sensors, with some other feature requirements. + */ #if TEMP_SENSOR_CHAMBER && !PIN_EXISTS(TEMP_CHAMBER) #error "TEMP_SENSOR_CHAMBER requires TEMP_CHAMBER_PIN." #endif -#if TEMP_SENSOR_COOLER && !(PIN_EXISTS(TEMP_COOLER) && ENABLED(LASER_FEATURE)) - #error "TEMP_SENSOR_COOLER requires LASER_FEATURE and TEMP_COOLER_PIN." +#if TEMP_SENSOR_COOLER + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_COOLER requires TEMP_COOLER_PIN." + #elif DISABLED(LASER_FEATURE) + #error "TEMP_SENSOR_COOLER requires LASER_FEATURE." + #endif +#endif + +#if TEMP_SENSOR_PROBE + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN." + #elif !HAS_TEMP_ADC_PROBE + #error "TEMP_PROBE_PIN must be an ADC pin." + #elif DISABLED(FIX_MOUNTED_PROBE) + #error "TEMP_SENSOR_PROBE shouldn't be set without FIX_MOUNTED_PROBE." + #endif #endif #if ENABLED(LASER_COOLANT_FLOW_METER) && !(PIN_EXISTS(FLOWMETER) && ENABLED(LASER_FEATURE)) @@ -2186,41 +2237,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if TEMP_SENSOR_PROBE - #if !PIN_EXISTS(TEMP_PROBE) - #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN." - #elif !HAS_TEMP_ADC_PROBE - #error "TEMP_PROBE_PIN must be an ADC pin." - #elif DISABLED(FIX_MOUNTED_PROBE) - #error "TEMP_SENSOR_PROBE shouldn't be set without FIX_MOUNTED_PROBE." - #endif -#endif - -#if TEMP_SENSOR_IS_MAX(0, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_0) && defined(MAX31865_CALIBRATION_OHMS_0)) - #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." -#elif TEMP_SENSOR_IS_MAX(1, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_1) && defined(MAX31865_CALIBRATION_OHMS_1)) - #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1/TEMP_SENSOR_REDUNDANT is MAX31865." -#endif - -/** - * Test Heater, Temp Sensor, and Extruder Pins - */ -#if !HAS_HEATER_0 && EXTRUDERS - #error "HEATER_0_PIN not defined for this board." -#elif !ANY_PIN(TEMP_0, MAX6675_SS) - #error "TEMP_0_PIN or MAX6675_SS not defined for this board." -#endif - -#if HAS_EXTRUDERS - #if ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) - #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." - #elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) - #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." - #elif EXTRUDERS && TEMP_SENSOR_0 == 0 - #error "TEMP_SENSOR_0 is required if there are any extruders." - #endif -#endif - /** * Temperature status LEDs */ @@ -2262,6 +2278,16 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Test Extruder Stepper Pins */ +#if HAS_EXTRUDERS + #if ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) + #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." + #elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) + #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." + #elif EXTRUDERS && TEMP_SENSOR_0 == 0 + #error "TEMP_SENSOR_0 is required if there are any extruders." + #endif +#endif + #if E_STEPPERS #if !(PINS_EXIST(E0_STEP, E0_DIR) && HAS_E0_ENABLE) #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp new file mode 100644 index 0000000000..590dea5ca5 --- /dev/null +++ b/Marlin/src/libs/MAX31865.cpp @@ -0,0 +1,500 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Based on Based on Adafruit MAX31865 library: + * + * This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + * Designed specifically to work with the Adafruit RTD Sensor + * https://www.adafruit.com/products/3328 + * + * This sensor uses SPI to communicate, 4 pins are required to interface. + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * Written by Limor Fried/Ladyada for Adafruit Industries. + * + * Modifications by JoAnn Manges (@GadgetAngel) + * Copyright (c) 2020, JoAnn Manges + * All rights reserved. + */ + +// Useful for RTD debugging. +//#define MAX31865_DEBUG +//#define MAX31865_DEBUG_SPI + +//TODO: switch to SPIclass/SoftSPI + +#include "../inc/MarlinConfig.h" + +#if HAS_MAX31865 && !LIB_USR_MAX31865 + +#include "MAX31865.h" + +// The maximum speed the MAX31865 can do is 5 MHz +SPISettings MAX31865::spiConfig = SPISettings( + #if defined(TARGET_LPC1768) + SPI_QUARTER_SPEED + #elif defined(ARDUINO_ARCH_STM32) + SPI_CLOCK_DIV4 + #else + 500000 + #endif + , MSBFIRST + , SPI_MODE_1 // CPOL0 CPHA1 +); + +#ifndef LARGE_PINMAP + + /** + * Create the interface object using software (bitbang) SPI for PIN values + * less than or equal to 127. + * + * @param spi_cs the SPI CS pin to use + * @param spi_mosi the SPI MOSI pin to use + * @param spi_miso the SPI MISO pin to use + * @param spi_clk the SPI clock pin to use + */ + MAX31865::MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, int8_t spi_clk) { + _cs = spi_cs; + _mosi = spi_mosi; + _miso = spi_miso; + _sclk = spi_clk; + } + + /** + * Create the interface object using hardware SPI for PIN for PIN values less + * than or equal to 127. + * + * @param spi_cs the SPI CS pin to use along with the default SPI device + */ + MAX31865::MAX31865(int8_t spi_cs) { + _cs = spi_cs; + _sclk = _miso = _mosi = -1; + } + +#else + + /** + * Create the interface object using software (bitbang) SPI for PIN values + * which are larger than 127. If you have PIN values less than or equal to + * 127 use the other call for SW SPI. + * + * @param spi_cs the SPI CS pin to use + * @param spi_mosi the SPI MOSI pin to use + * @param spi_miso the SPI MISO pin to use + * @param spi_clk the SPI clock pin to use + * @param pin_mapping set to 1 for positive pin values + */ + MAX31865::MAX31865(uint32_t spi_cs, uint32_t spi_mosi, + uint32_t spi_miso, uint32_t spi_clk, + uint8_t pin_mapping) { + _cs = spi_cs; + _mosi = spi_mosi; + _miso = spi_miso; + _sclk = spi_clk; + } + + /** + * Create the interface object using hardware SPI for PIN values which are + * larger than 127. If you have PIN values less than or equal to 127 use + * the other call for HW SPI. + * + * @param spi_cs the SPI CS pin to use along with the default SPI device + * @param pin_mapping set to 1 for positive pin values + */ + MAX31865::MAX31865(uint32_t spi_cs, uint8_t pin_mapping) { + _cs = spi_cs; + _sclk = _miso = _mosi = -1UL; //-1UL or 0xFFFFFFFF or 4294967295 + } + +#endif // LARGE_PINMAP + + +/** + * + * Instance & Class methods + * + */ + + +/** + * Initialize the SPI interface and set the number of RTD wires used + * + * @param wires The number of wires in enum format. Can be MAX31865_2WIRE, MAX31865_3WIRE, or MAX31865_4WIRE. + * @param zero The resistance of the RTD at 0 degC, in ohms. + * @param ref The resistance of the reference resistor, in ohms. + */ +void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { + Rzero = zero; + Rref = ref; + + OUT_WRITE(_cs, HIGH); + + if (_sclk != TERN(LARGE_PINMAP, -1UL, -1)) { + // define pin modes for Software SPI + #ifdef MAX31865_DEBUG + SERIAL_ECHOLN("Initializing MAX31865 Software SPI"); + #endif + + OUT_WRITE(_sclk, LOW); + SET_OUTPUT(_mosi); + SET_INPUT(_miso); + } else { + // start and configure hardware SPI + #ifdef MAX31865_DEBUG + SERIAL_ECHOLN("Initializing MAX31865 Hardware SPI"); + #endif + + SPI.begin(); + } + + setWires(wires); + enableBias(false); + autoConvert(false); + clearFault(); + + #ifdef MAX31865_DEBUG_SPI + #ifndef LARGE_PINMAP + SERIAL_ECHOLNPAIR( + "Regular begin call with _cs: ", _cs, + " _miso: ", _miso, + " _sclk: ", _sclk, + " _mosi: ", _mosi + ); + #else + SERIAL_ECHOLNPAIR( + "LARGE_PINMAP begin call with _cs: ", _cs, + " _miso: ", _miso, + " _sclk: ", _sclk, + " _mosi: ", _mosi + ); + #endif // LARGE_PINMAP + + SERIAL_ECHOLNPAIR("config: ", readRegister8(MAX31856_CONFIG_REG)); + SERIAL_EOL(); + #endif // MAX31865_DEBUG_SPI +} + +/** + * Read the raw 8-bit FAULTSTAT register + * + * @return The raw unsigned 8-bit FAULT status register + */ +uint8_t MAX31865::readFault() { + return readRegister8(MAX31856_FAULTSTAT_REG); +} + +/** + * Clear all faults in FAULTSTAT. + */ +void MAX31865::clearFault() { + setConfig(MAX31856_CONFIG_FAULTSTAT, 1); +} + +/** + * Whether we want to have continuous conversions (50/60 Hz) + * + * @param b If true, auto conversion is enabled + */ +void MAX31865::autoConvert(bool b) { + setConfig(MAX31856_CONFIG_MODEAUTO, b); +} + +/** + * Whether we want filter out 50Hz noise or 60Hz noise + * + * @param b If true, 50Hz noise is filtered, else 60Hz(default) + */ +void MAX31865::enable50HzFilter(bool b) { + setConfig(MAX31856_CONFIG_FILT50HZ, b); +} + +/** + * Enable the bias voltage on the RTD sensor + * + * @param b If true bias is enabled, else disabled + */ +void MAX31865::enableBias(bool b) { + setConfig(MAX31856_CONFIG_BIAS, b); + + // From the datasheet: + // Note that if VBIAS is off (to reduce supply current between conversions), any filter + // capacitors at the RTDIN inputs need to charge before an accurate conversion can be + // performed. Therefore, enable VBIAS and wait at least 10.5 time constants of the input + // RC network plus an additional 1ms before initiating the conversion. + if (b) + DELAY_US(11500); //11.5ms +} + +/** + * Start a one-shot temperature reading. + */ +void MAX31865::oneShot() { + setConfig(MAX31856_CONFIG_1SHOT, 1); + + // From the datasheet: + // Note that a single conversion requires approximately 52ms in 60Hz filter + // mode or 62.5ms in 50Hz filter mode to complete. 1-Shot is a self-clearing bit. + // TODO: switch this out depeding on the filter mode. + DELAY_US(65000); // 65ms +} + +/** + * How many wires we have in our RTD setup, can be MAX31865_2WIRE, + * MAX31865_3WIRE, or MAX31865_4WIRE + * + * @param wires The number of wires in enum format + */ +void MAX31865::setWires(max31865_numwires_t wires) { + uint8_t t = readRegister8(MAX31856_CONFIG_REG); + if (wires == MAX31865_3WIRE) + t |= MAX31856_CONFIG_3WIRE; + else // 2 or 4 wire + t &= ~MAX31856_CONFIG_3WIRE; + writeRegister8(MAX31856_CONFIG_REG, t); +} + +/** + * Read the raw 16-bit value from the RTD_REG in one shot mode. This will include + * the fault bit, D0. + * + * @return The raw unsigned 16-bit register value with ERROR bit attached, NOT temperature! + */ +uint16_t MAX31865::readRaw() { + clearFault(); + enableBias(true); + + oneShot(); + uint16_t rtd = readRegister16(MAX31856_RTDMSB_REG); + + #ifdef MAX31865_DEBUG + SERIAL_ECHOLNPAIR("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); + #endif + + // Disable the bias to lower power dissipation between reads. + // If the ref resistor heats up, the temperature reading will be skewed. + enableBias(false); + + return rtd; +} + +/** + * Calulate and return the resistance value of the connected RTD. + * + * @param refResistor The value of the matching reference resistor, usually 430 or 4300 + * @return The raw RTD resistance value, NOT temperature! + */ +float MAX31865::readResistance() { + // Strip the error bit (D0) and convert to a float ratio. + // less precise method: (readRaw() * Rref) >> 16 + return (((readRaw() >> 1) / 32768.0f) * Rref); +} + +/** + * Read the RTD and pass it to temperature(float) for calculation. + * + * @return Temperature in C + */ +float MAX31865::temperature() { + return temperature(readResistance()); +} + +/** + * Given the 15-bit ADC value, calculate the resistance and pass it to temperature(float) for calculation. + * + * @return Temperature in C + */ +float MAX31865::temperature(uint16_t adcVal) { + return temperature(((adcVal) / 32768.0f) * Rref); +} + +/** + * Calculate the temperature in C from the RTD resistance. + * Uses the technique outlined in this PDF: + * http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf + * + * @param Rrtd the resistance value in ohms + * @return the temperature in degC + */ +float MAX31865::temperature(float Rrtd) { + float temp = (RTD_Z1 + sqrt(RTD_Z2 + (RTD_Z3 * Rrtd))) / RTD_Z4; + + // From the PDF... + // + // The previous equation is valid only for temperatures of 0°C and above. + // The equation for RRTD(t) that defines negative temperature behavior is a + // fourth-order polynomial (after expanding the third term) and is quite + // impractical to solve for a single expression of temperature as a function + // of resistance. + // + if (temp < 0) { + Rrtd = (Rrtd / Rzero) * 100; // normalize to 100 ohm + float rpoly = Rrtd; + + temp = -242.02 + (2.2228 * rpoly); + rpoly *= Rrtd; // square + temp += 2.5859e-3 * rpoly; + rpoly *= Rrtd; // ^3 + temp -= 4.8260e-6 * rpoly; + rpoly *= Rrtd; // ^4 + temp -= 2.8183e-8 * rpoly; + rpoly *= Rrtd; // ^5 + temp += 1.5243e-10 * rpoly; + } + + return temp; +} + +// +// private: +// + + +/** + * Set a value in the configuration register. + * + * @param config 8-bit value for the config item + * @param enable whether to enable or disable the value + */ +void MAX31865::setConfig(uint8_t config, bool enable) { + uint8_t t = readRegister8(MAX31856_CONFIG_REG); + if (enable) + t |= config; + else + t &= ~config; // disable + writeRegister8(MAX31856_CONFIG_REG, t); +} + +/** + * Read a single byte from the specified register address. + * + * @param addr the register address + * @return the register contents + */ +uint8_t MAX31865::readRegister8(uint8_t addr) { + uint8_t ret = 0; + readRegisterN(addr, &ret, 1); + + return ret; +} + +/** + * Read two bytes: 1 from the specified register address, and 1 from the next address. + * + * @param addr the first register address + * @return both register contents as a single 16-bit int + */ +uint16_t MAX31865::readRegister16(uint8_t addr) { + uint8_t buffer[2] = {0, 0}; + readRegisterN(addr, buffer, 2); + + uint16_t ret = buffer[0]; + ret <<= 8; + ret |= buffer[1]; + + return ret; +} + +/** + * Read +n+ bytes from a specified address into +buffer+. Set D7 to 0 to specify a read. + * + * @param addr the first register address + * @param buffer storage for the read bytes + * @param n the number of bytes to read + */ +void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { + addr &= 0x7F; // make sure top bit is not set + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.beginTransaction(spiConfig); + else + WRITE(_sclk, LOW); + + WRITE(_cs, LOW); + spixfer(addr); + + while (n--) { + buffer[0] = spixfer(0xFF); + #ifdef MAX31865_DEBUG_SPI + SERIAL_ECHOLNPAIR("buffer read ", n, " data: ", buffer[0]); + #endif + buffer++; + } + + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.endTransaction(); + + WRITE(_cs, HIGH); +} + +/** + * Write an 8-bit value to a register. Set D7 to 1 to specify a write. + * + * @param addr the address to write to + * @param data the data to write + */ +void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.beginTransaction(spiConfig); + else + WRITE(_sclk, LOW); + + WRITE(_cs, LOW); + + spixfer(addr | 0x80); // make sure top bit is set + spixfer(data); + + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + SPI.endTransaction(); + + WRITE(_cs, HIGH); +} + +/** + * Transfer SPI data +x+ and read the response. From the datasheet... + * Input data (SDI) is latched on the internal strobe edge and output data (SDO) is + * shifted out on the shift edge. There is one clock for each bit transferred. + * Address and data bits are transferred in groups of eight, MSB first. + * + * @param x an 8-bit chunk of data to write + * @return the 8-bit response + */ +uint8_t MAX31865::spixfer(uint8_t x) { + if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + return SPI.transfer(x); + + uint8_t reply = 0; + for (int i = 7; i >= 0; i--) { + reply <<= 1; + WRITE(_sclk, HIGH); + WRITE(_mosi, x & (1 << i)); + WRITE(_sclk, LOW); + if (READ(_miso)) + reply |= 1; + } + + return reply; +} + +#endif // HAS_MAX31865 && !LIB_USR_MAX31865 diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h new file mode 100644 index 0000000000..2ab78ecbe8 --- /dev/null +++ b/Marlin/src/libs/MAX31865.h @@ -0,0 +1,131 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Based on Adafruit MAX31865 library: + * + * This is a library for the Adafruit PT100/P1000 RTD Sensor w/MAX31865 + * Designed specifically to work with the Adafruit RTD Sensor + * https://www.adafruit.com/products/3328 + * + * This sensor uses SPI to communicate, 4 pins are required to interface. + * + * Adafruit invests time and resources providing this open source code, + * please support Adafruit and open-source hardware by purchasing + * products from Adafruit! + * + * Written by Limor Fried/Ladyada for Adafruit Industries. + * + * Modifications by JoAnn Manges (@GadgetAngel) + * Copyright (c) 2020, JoAnn Manges + * All rights reserved. + */ +#pragma once + +#include "../inc/MarlinConfig.h" +#include "../HAL/shared/Delay.h" +#include HAL_PATH(../HAL, MarlinSPI.h) + +#define MAX31856_CONFIG_REG 0x00 +#define MAX31856_CONFIG_BIAS 0x80 +#define MAX31856_CONFIG_MODEAUTO 0x40 +#define MAX31856_CONFIG_MODEOFF 0x00 +#define MAX31856_CONFIG_1SHOT 0x20 +#define MAX31856_CONFIG_3WIRE 0x10 +#define MAX31856_CONFIG_24WIRE 0x00 +#define MAX31856_CONFIG_FAULTSTAT 0x02 +#define MAX31856_CONFIG_FILT50HZ 0x01 +#define MAX31856_CONFIG_FILT60HZ 0x00 + +#define MAX31856_RTDMSB_REG 0x01 +#define MAX31856_RTDLSB_REG 0x02 +#define MAX31856_HFAULTMSB_REG 0x03 +#define MAX31856_HFAULTLSB_REG 0x04 +#define MAX31856_LFAULTMSB_REG 0x05 +#define MAX31856_LFAULTLSB_REG 0x06 +#define MAX31856_FAULTSTAT_REG 0x07 + +#define MAX31865_FAULT_HIGHTHRESH 0x80 // D7 +#define MAX31865_FAULT_LOWTHRESH 0x40 // D6 +#define MAX31865_FAULT_REFINLOW 0x20 // D5 +#define MAX31865_FAULT_REFINHIGH 0x10 // D4 +#define MAX31865_FAULT_RTDINLOW 0x08 // D3 +#define MAX31865_FAULT_OVUV 0x04 // D2 + +// http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf +// constants for calulating temperature from the measured RTD resistance. +#define RTD_Z1 -0.0039083 +#define RTD_Z2 0.00001758480889 +#define RTD_Z3 -0.0000000231 +#define RTD_Z4 -0.000001155 + +typedef enum max31865_numwires { + MAX31865_2WIRE = 0, + MAX31865_3WIRE = 1, + MAX31865_4WIRE = 0 +} max31865_numwires_t; + +/* Interface class for the MAX31865 RTD Sensor reader */ +class MAX31865 { +private: + static SPISettings spiConfig; + + TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; + float Rzero, Rref; + + void setConfig(uint8_t config, bool enable); + + void readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n); + uint8_t readRegister8(uint8_t addr); + uint16_t readRegister16(uint8_t addr); + + void writeRegister8(uint8_t addr, uint8_t reg); + uint8_t spixfer(uint8_t addr); + +public: + #ifdef LARGE_PINMAP + MAX31865(uint32_t spi_cs, uint8_t pin_mapping); + MAX31865(uint32_t spi_cs, uint32_t spi_mosi, uint32_t spi_miso, + uint32_t spi_clk, uint8_t pin_mapping); + #else + MAX31865(int8_t spi_cs); + MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, + int8_t spi_clk); + #endif + + void begin(max31865_numwires_t wires, float zero, float ref); + + uint8_t readFault(); + void clearFault(); + + void setWires(max31865_numwires_t wires); + void autoConvert(bool b); + void enable50HzFilter(bool b); + void enableBias(bool b); + void oneShot(); + + uint16_t readRaw(); + float readResistance(); + float temperature(); + float temperature(uint16_t adcVal); + float temperature(float Rrtd); +}; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 63fdd5afc3..eb6dc6597c 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -703,8 +703,7 @@ void restore_feedrate_and_scaling() { * at the same positions relative to the machine. */ void update_software_endstops(const AxisEnum axis - OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index/*=0*/) - OPTARG(HAS_HOTEND_OFFSET, const uint8_t new_tool_index/*=0*/) + OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index/*=0*/, const uint8_t new_tool_index/*=0*/) ) { #if ENABLED(DUAL_X_CARRIAGE) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9f32ce933b..83187259ff 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -34,6 +34,7 @@ #include "temperature.h" #include "endstops.h" #include "planner.h" +#include "printcounter.h" #if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../feature/cooler.h" @@ -56,112 +57,56 @@ #include "../feature/host_actions.h" #endif -#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && ENABLED(TEMP_SENSOR_REDUNDANT_SOURCE) && TEMP_SENSOR_REDUNDANT_SOURCE == n)) - -// LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library -#if LIB_USR_MAX31855 - #include - #if PIN_EXISTS(MAX31855_MISO) && PIN_EXISTS(MAX31855_SCK) - #define MAX31855_USES_SW_SPI 1 - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX31855) && PIN_EXISTS(MAX31855_CS) - #define HAS_MAX31855_TEMP 1 - Adafruit_MAX31855 max31855_0 = Adafruit_MAX31855(MAX31855_CS_PIN - #if MAX31855_USES_SW_SPI - , MAX31855_MISO_PIN, MAX31855_SCK_PIN // For software SPI also set MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX31855) && PIN_EXISTS(MAX31855_CS2) - #define HAS_MAX31855_TEMP 1 - Adafruit_MAX31855 max31855_1 = Adafruit_MAX31855(MAX31855_CS2_PIN - #if MAX31855_USES_SW_SPI - , MAX31855_MISO_PIN, MAX31855_SCK_PIN // For software SPI also set MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); - #endif -#endif - -// LIB_MAX31865 can be added to the build_flags in platformio.ini to use a user-defined library. -// If LIB_MAX31865 is not on the build_flags then the Adafruit MAX31865 V1.1.0 library is used. -#if HAS_MAX31865 - #include - #ifndef MAX31865_MOSI_PIN - #define MAX31865_MOSI_PIN SD_MOSI_PIN - #endif - #if PIN_EXISTS(MAX31865_MISO) && PIN_EXISTS(MAX31865_SCK) - #define MAX31865_USES_SW_SPI 1 - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX31865) && PIN_EXISTS(MAX31865_CS) - #define HAS_MAX31865_TEMP 1 - Adafruit_MAX31865 max31865_0 = Adafruit_MAX31865(MAX31865_CS_PIN - #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) - , MAX31865_MOSI_PIN, MAX31865_MISO_PIN, MAX31865_SCK_PIN // For software SPI also set MOSI/MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX31865) && PIN_EXISTS(MAX31865_CS2) - #define HAS_MAX31865_TEMP 1 - Adafruit_MAX31865 max31865_1 = Adafruit_MAX31865(MAX31865_CS2_PIN - #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) - , MAX31865_MOSI_PIN, MAX31865_MISO_PIN, MAX31865_SCK_PIN // For software SPI also set MOSI/MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); - #endif -#endif +// MAX TC related macros +#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && TEMP_SENSOR_REDUNDANT_SOURCE == n)) // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library -#if LIB_USR_MAX6675 +// If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. +#if HAS_MAX6675 && LIB_USR_MAX6675 #include - #if PIN_EXISTS(MAX6675_MISO) && PIN_EXISTS(MAX6675_SCK) - #define MAX6675_USES_SW_SPI 1 - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) - #define HAS_MAX6675_TEMP 1 - MAX6675 max6675_0 = MAX6675(MAX6675_CS_PIN - #if MAX6675_USES_SW_SPI - , MAX6675_MISO_PIN, MAX6675_SCK_PIN // For software SPI also set MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) - #define HAS_MAX6675_TEMP 1 - MAX6675 max6675_1 = MAX6675(MAX6675_CS2_PIN - #if MAX6675_USES_SW_SPI - , MAX6675_MISO_PIN, MAX6675_SCK_PIN // For software SPI also set MISO/SCK - #endif - #if ENABLED(LARGE_PINMAP) - , HIGH - #endif - ); + #define HAS_MAX6675_LIBRARY 1 +#endif + +// LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library. +// If LIB_MAX31855 is not on the build_flags then raw SPI reads will be used. +#if HAS_MAX31855 && LIB_USR_MAX31855 + #include + #define HAS_MAX31855_LIBRARY 1 + typedef Adafruit_MAX31855 MAX31855; +#endif + +#if HAS_MAX31865 + #if LIB_USR_MAX31865 + #include + typedef Adafruit_MAX31865 MAX31865; + #else + #include "../libs/MAX31865.h" #endif #endif -#if !HAS_MAX6675_TEMP && !HAS_MAX31855_TEMP && !HAS_MAX31865_TEMP - #define NO_THERMO_TEMPS 1 +#if HAS_MAX6675_LIBRARY || HAS_MAX31855_LIBRARY || HAS_MAX31865 + #define HAS_MAXTC_LIBRARIES 1 #endif -#if (TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && PINS_EXIST(MAX6675_SCK, MAX6675_DO) && NO_THERMO_TEMPS - #define THERMO_SEPARATE_SPI 1 +// If we have a MAX TC with SCK and MISO pins defined, it's either on a separate/dedicated Hardware +// SPI bus, or some pins for Software SPI. Alternate Hardware SPI buses are not supported yet, so +// your SPI options are: +// +// 1. Only CS pin(s) defined: Hardware SPI on the default bus (usually the SD card SPI). +// 2. CS, MISO, and SCK pins defined: Software SPI on a separate bus, as defined by MISO, SCK. +// 3. CS, MISO, and SCK pins w/ FORCE_HW_SPI: Hardware SPI on the default bus, ignoring MISO, SCK. +// +#if TEMP_SENSOR_IS_ANY_MAX_TC(0) && TEMP_SENSOR_0_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_0_USES_SW_SPI 1 +#endif +#if TEMP_SENSOR_IS_ANY_MAX_TC(1) && TEMP_SENSOR_1_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_1_USES_SW_SPI 1 #endif -#if THERMO_SEPARATE_SPI +#if (TEMP_SENSOR_0_USES_SW_SPI || TEMP_SENSOR_1_USES_SW_SPI) && !HAS_MAXTC_LIBRARIES #include "../libs/private_spi.h" + #define HAS_MAXTC_SW_SPI 1 #endif #if ENABLED(PID_EXTRUSION_SCALING) @@ -172,8 +117,6 @@ #include "../feature/babystep.h" #endif -#include "printcounter.h" - #if ENABLED(FILAMENT_WIDTH_SENSOR) #include "../feature/filwidth.h" #endif @@ -246,7 +189,67 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #define _E_PSTR(h,N) ((HOTENDS) > N && (h) == N) ? PSTR(LCD_STR_E##N) : #define HEATER_PSTR(h) _BED_PSTR(h) _CHAMBER_PSTR(h) _COOLER_PSTR(h) _E_PSTR(h,1) _E_PSTR(h,2) _E_PSTR(h,3) _E_PSTR(h,4) _E_PSTR(h,5) PSTR(LCD_STR_E0) -// public: +// +// Initialize MAX TC objects/SPI +// +#if HAS_MAX_TC + + #if HAS_MAXTC_SW_SPI + // Initialize SoftSPI for non-lib Software SPI; Libraries take care of it themselves. + template + SoftSPI SPIclass::softSPI; + SPIclass max_tc_spi; + #endif + + #define MAXTC_INIT(n, M) \ + MAX##M max##M##_##n = MAX##M( \ + TEMP_##n##_CS_PIN \ + OPTARG(_MAX31865_##n##_SW, TEMP_##n##_MOSI_PIN) \ + OPTARG(TEMP_SENSOR_##n##_USES_SW_SPI, TEMP_##n##_MISO_PIN, TEMP_##n##_SCK_PIN) \ + OPTARG(LARGE_PINMAP, HIGH) \ + ) + + #if HAS_MAX6675_LIBRARY + #if TEMP_SENSOR_IS_MAX(0, 6675) + MAXTC_INIT(0, 6675); + #endif + #if TEMP_SENSOR_IS_MAX(1, 6675) + MAXTC_INIT(1, 6675); + #endif + #endif + + #if HAS_MAX31855_LIBRARY + #if TEMP_SENSOR_IS_MAX(0, 31855) + MAXTC_INIT(0, 31855); + #endif + #if TEMP_SENSOR_IS_MAX(1, 31855) + MAXTC_INIT(1, 31855); + #endif + #endif + + // MAX31865 always uses a library, unlike '55 & 6675 + #if HAS_MAX31865 + #define _MAX31865_0_SW TEMP_SENSOR_0_USES_SW_SPI + #define _MAX31865_1_SW TEMP_SENSOR_1_USES_SW_SPI + + #if TEMP_SENSOR_IS_MAX(0, 31865) + MAXTC_INIT(0, 31865); + #endif + #if TEMP_SENSOR_IS_MAX(1, 31865) + MAXTC_INIT(1, 31865); + #endif + + #undef _MAX31865_0_SW + #undef _MAX31865_1_SW + #endif + + #undef MAXTC_INIT + +#endif + +/** + * public: + */ #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) bool Temperature::adaptive_fan_slowing = true; @@ -274,6 +277,25 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, uint8_t Temperature::coolerfan_speed; // = 0 #endif +// Init fans according to whether they're native PWM or Software PWM +#ifdef BOARD_OPENDRAIN_MOSFETS + #define _INIT_SOFT_FAN(P) OUT_WRITE_OD(P, FAN_INVERTING ? LOW : HIGH) +#else + #define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH) +#endif +#if ENABLED(FAN_SOFT_PWM) + #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P) +#else + #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) +#endif +#if ENABLED(FAST_PWM_FAN) + #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) +#else + #define SET_FAST_PWM_FREQ(P) NOOP +#endif +#define INIT_FAN_PIN(P) do{ _INIT_FAN_PIN(P); SET_FAST_PWM_FREQ(P); }while(0) + +// HAS_FAN does not include CONTROLLER_FAN #if HAS_FAN uint8_t Temperature::fan_speed[FAN_COUNT]; // = { 0 } @@ -419,7 +441,18 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, celsius_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; #endif -// private: +#if HAS_ADC_BUTTONS + uint32_t Temperature::current_ADCKey_raw = HAL_ADC_RANGE; + uint16_t Temperature::ADCKey_count = 0; +#endif + +#if ENABLED(PID_EXTRUSION_SCALING) + int16_t Temperature::lpq_len; // Initialized in settings.cpp +#endif + +/** + * private: + */ volatile bool Temperature::raw_temps_ready = false; @@ -472,16 +505,10 @@ volatile bool Temperature::raw_temps_ready = false; bool Temperature::paused_for_probing; #endif -// public: - -#if HAS_ADC_BUTTONS - uint32_t Temperature::current_ADCKey_raw = HAL_ADC_RANGE; - uint16_t Temperature::ADCKey_count = 0; -#endif - -#if ENABLED(PID_EXTRUSION_SCALING) - int16_t Temperature::lpq_len; // Initialized in settings.cpp -#endif +/** + * public: + * Class and Instance Methods + */ #if HAS_PID_HEATING @@ -758,10 +785,6 @@ volatile bool Temperature::raw_temps_ready = false; #endif // HAS_PID_HEATING -/** - * Class and Instance Methods - */ - int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { switch (heater_id) { #if HAS_HEATED_BED @@ -781,6 +804,16 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _EFANOVERLAP(A,B) _FANOVERLAP(E##A,B) #if HAS_AUTO_FAN + #if EXTRUDER_AUTO_FAN_SPEED != 255 + #define INIT_E_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) + #else + #define INIT_E_AUTO_FAN_PIN(P) SET_OUTPUT(P) + #endif + #if CHAMBER_AUTO_FAN_SPEED != 255 + #define INIT_CHAMBER_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) + #else + #define INIT_CHAMBER_AUTO_FAN_PIN(P) SET_OUTPUT(P) + #endif #define CHAMBER_FAN_INDEX HOTENDS @@ -1668,11 +1701,6 @@ void Temperature::manage_heater() { } celsius_float_t Temperature::user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw) { - //#if (MOTHERBOARD == BOARD_RAMPS_14_EFB) - // static uint32_t clocks_total = 0; - // static uint32_t calls = 0; - // uint32_t tcnt5 = TCNT5; - //#endif if (!WITHIN(t_index, 0, COUNT(user_thermistor) - 1)) return 25; @@ -1700,14 +1728,6 @@ void Temperature::manage_heater() { value += t.sh_c_coeff * cu(log_resistance); value = 1.0f / value; - //#if (MOTHERBOARD == BOARD_RAMPS_14_EFB) - // int32_t clocks = TCNT5 - tcnt5; - // if (clocks >= 0) { - // clocks_total += clocks; - // calls++; - // } - //#endif - // Return degrees C (up to 999, as the LCD only displays 3 digits) return _MIN(value + THERMISTOR_ABS_ZERO_C, 999); } @@ -1730,7 +1750,14 @@ void Temperature::manage_heater() { #if TEMP_SENSOR_0_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_0, raw); #elif TEMP_SENSOR_0_IS_MAX_TC - return TERN(TEMP_SENSOR_0_IS_MAX31865, max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0), raw * 0.25); + #if TEMP_SENSOR_0_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_0.temperature((uint16_t)raw), + max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) + ); + #else + return raw * 0.25; + #endif #elif TEMP_SENSOR_0_IS_AD595 return TEMP_AD595(raw); #elif TEMP_SENSOR_0_IS_AD8495 @@ -1742,7 +1769,14 @@ void Temperature::manage_heater() { #if TEMP_SENSOR_1_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_1, raw); #elif TEMP_SENSOR_1_IS_MAX_TC - return TERN(TEMP_SENSOR_1_IS_MAX31865, max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1), raw * 0.25); + #if TEMP_SENSOR_0_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_1.temperature((uint16_t)raw), + max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) + ); + #else + return raw * 0.25; + #endif #elif TEMP_SENSOR_1_IS_AD595 return TEMP_AD595(raw); #elif TEMP_SENSOR_1_IS_AD8495 @@ -1901,9 +1935,9 @@ void Temperature::manage_heater() { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0), raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature((uint16_t)raw), raw * 0.25); #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1), raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature((uint16_t)raw), raw * 0.25); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); #elif TEMP_SENSOR_REDUNDANT_IS_AD595 @@ -1936,6 +1970,7 @@ void Temperature::updateTemperaturesFromRawValues() { TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].raw = READ_MAX_TC(1)); TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(TEMP_SENSOR_REDUNDANT_SOURCE)); + #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif @@ -2008,40 +2043,7 @@ void Temperature::updateTemperaturesFromRawValues() { if (cutter.unitPower > 0 && COOLERCMP(temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); if (COOLERCMP(mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); #endif -} - -#if THERMO_SEPARATE_SPI - template SoftSPI SPIclass::softSPI; - SPIclass max_tc_spi; -#endif - -// Init fans according to whether they're native PWM or Software PWM -#ifdef BOARD_OPENDRAIN_MOSFETS - #define _INIT_SOFT_FAN(P) OUT_WRITE_OD(P, FAN_INVERTING ? LOW : HIGH) -#else - #define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH) -#endif -#if ENABLED(FAN_SOFT_PWM) - #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P) -#else - #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) -#endif -#if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) -#else - #define SET_FAST_PWM_FREQ(P) NOOP -#endif -#define INIT_FAN_PIN(P) do{ _INIT_FAN_PIN(P); SET_FAST_PWM_FREQ(P); }while(0) -#if EXTRUDER_AUTO_FAN_SPEED != 255 - #define INIT_E_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) -#else - #define INIT_E_AUTO_FAN_PIN(P) SET_OUTPUT(P) -#endif -#if CHAMBER_AUTO_FAN_SPEED != 255 - #define INIT_CHAMBER_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) -#else - #define INIT_CHAMBER_AUTO_FAN_PIN(P) SET_OUTPUT(P) -#endif +} // Temperature::updateTemperaturesFromRawValues /** * Initialize the temperature manager @@ -2070,50 +2072,47 @@ void Temperature::init() { #endif // Init (and disable) SPI thermocouples - #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) - OUT_WRITE(MAX6675_CS_PIN, HIGH); + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && PIN_EXISTS(TEMP_0_CS) + OUT_WRITE(TEMP_0_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) - OUT_WRITE(MAX6675_CS2_PIN, HIGH); - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31855_CS) - OUT_WRITE(MAX31855_CS_PIN, HIGH); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31855_CS2) - OUT_WRITE(MAX31855_CS2_PIN, HIGH); - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31865_CS) - OUT_WRITE(MAX31865_CS_PIN, HIGH); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31865_CS2) - OUT_WRITE(MAX31865_CS2_PIN, HIGH); + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) && PIN_EXISTS(TEMP_1_CS) + OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif - #if HAS_MAX31865_TEMP - #if TEMP_SENSOR_IS_MAX(0, MAX31865) - max31865_0.begin(MAX31865_2WIRE); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX31865) - max31865_1.begin(MAX31865_2WIRE); - #endif - #endif + // Setup objects for library-based polling of MAX TCs + #if HAS_MAXTC_LIBRARIES + #define _MAX31865_WIRES(n) MAX31865_##n##WIRE + #define MAX31865_WIRES(n) _MAX31865_WIRES(n) - #if HAS_MAX31855_TEMP - #if TEMP_SENSOR_IS_MAX(0, MAX31855) - max31855_0.begin(MAX31855); + #if TEMP_SENSOR_IS_MAX(0, 6675) && HAS_MAX6675_LIBRARY + max6675_0.begin(); + #elif TEMP_SENSOR_IS_MAX(0, 31855) && HAS_MAX31855_LIBRARY + max31855_0.begin(); + #elif TEMP_SENSOR_IS_MAX(0, 31865) + max31865_0.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_0) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) + ); + #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) + max31865_0.enable50HzFilter(1); + #endif #endif - #if TEMP_SENSOR_IS_MAX(1, MAX31855) - max31855_1.begin(MAX31855); - #endif - #endif - #if HAS_MAX6675_TEMP - #if TEMP_SENSOR_IS_MAX(0, MAX6675) - max6675_0.begin(MAX6675); - #endif - #if TEMP_SENSOR_IS_MAX(1, MAX6675) - max6675_1.begin(MAX6675); + #if TEMP_SENSOR_IS_MAX(1, 6675) && HAS_MAX6675_LIBRARY + max6675_1.begin(); + #elif TEMP_SENSOR_IS_MAX(1, 31855) && HAS_MAX31855_LIBRARY + max31855_1.begin(); + #elif TEMP_SENSOR_IS_MAX(1, 31865) + max31865_1.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_1) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) + ); + #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) + max31865_1.enable50HzFilter(1); + #endif #endif + #undef MAX31865_WIRES + #undef _MAX31865_WIRES #endif #if MB(RUMBA) @@ -2152,7 +2151,6 @@ void Temperature::init() { OUT_WRITE(HEATER_0_PIN, HEATER_0_INVERTING); #endif #endif - #if HAS_HEATER_1 OUT_WRITE(HEATER_1_PIN, HEATER_1_INVERTING); #endif @@ -2219,7 +2217,9 @@ void Temperature::init() { INIT_FAN_PIN(CONTROLLER_FAN_PIN); #endif - TERN_(THERMO_SEPARATE_SPI, max_tc_spi.init()); + #if HAS_MAXTC_SW_SPI + max_tc_spi.init(); + #endif HAL_adc_init(); @@ -2318,11 +2318,7 @@ void Temperature::init() { INIT_CHAMBER_AUTO_FAN_PIN(CHAMBER_AUTO_FAN_PIN); #endif - // Wait for temperature measurement to settle - //delay(250); - #if HAS_HOTEND - #define _TEMP_MIN_E(NR) do{ \ const celsius_t tmin = _MAX(HEATER_##NR##_MINTEMP, TERN(TEMP_SENSOR_##NR##_IS_CUSTOM, 0, (int)pgm_read_word(&TEMPTABLE_##NR [TEMP_SENSOR_##NR##_MINTEMP_IND].celsius))); \ temp_range[NR].mintemp = tmin; \ @@ -2386,7 +2382,6 @@ void Temperature::init() { #if _MINMAX_TEST(7, MAX) _TEMP_MAX_E(7); #endif - #endif // HAS_HOTEND #if HAS_HEATED_BED @@ -2520,9 +2515,8 @@ void Temperature::init() { void Temperature::disable_all_heaters() { + // Disable autotemp, unpause and reset everything TERN_(AUTOTEMP, planner.autotemp_enabled = false); - - // Unpause and reset everything TERN_(PROBING_HEATERS_OFF, pause_heaters(false)); #if HAS_HOTEND @@ -2558,8 +2552,6 @@ void Temperature::disable_all_heaters() { #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - #include "printcounter.h" - bool Temperature::auto_job_over_threshold() { #if HAS_HOTEND HOTEND_LOOP() if (degTargetHotend(e) > (EXTRUDE_MINTEMP) / 2) return true; @@ -2578,7 +2570,7 @@ void Temperature::disable_all_heaters() { } } -#endif +#endif // PRINTJOB_TIMER_AUTOSTART #if ENABLED(PROBING_HEATERS_OFF) @@ -2616,7 +2608,7 @@ void Temperature::disable_all_heaters() { #endif } -#endif +#endif // SINGLENOZZLE_STANDBY_TEMP || SINGLENOZZLE_STANDBY_FAN #if HAS_MAX_TC @@ -2624,113 +2616,114 @@ void Temperature::disable_all_heaters() { #define THERMOCOUPLE_MAX_ERRORS 15 #endif - int Temperature::read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex/*=0*/)) { - #define MAX6675_HEAT_INTERVAL 250UL + /** + * @brief Read MAX Thermocouple temperature. + * + * Reads the thermocouple board via HW or SW SPI, using a library (LIB_USR_x) or raw SPI reads. + * Doesn't strictly return a temperature; returns an "ADC Value" (i.e. raw register content). + * + * @param hindex the hotend we're referencing (if MULTI_MAX_TC) + * @return integer representing the board's buffer, to be converted later if needed + */ + int16_t Temperature::read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex/*=0*/)) { + #define MAXTC_HEAT_INTERVAL 250UL - #if HAS_MAX31855_TEMP - static uint32_t max_tc_temp = 2000; - #define MAX_TC_ERROR_MASK 7 - #define MAX_TC_DISCARD_BITS 18 - #define MAX_TC_SPEED_BITS 3 // (_BV(SPR1)) // clock ÷ 64 - #elif HAS_MAX31865_TEMP - static uint16_t max_tc_temp = 2000; // From datasheet 16 bits D15-D0 - #define MAX_TC_ERROR_MASK 1 // D0 Bit not used + #if HAS_MAX31855 + #define MAX_TC_ERROR_MASK 7 // D2-0: SCV, SCG, OC + #define MAX_TC_DISCARD_BITS 18 // Data D31-18; sign bit D31 + #define MAX_TC_SPEED_BITS 3 // ~1MHz + #elif HAS_MAX31865 + #define MAX_TC_ERROR_MASK 1 // D0 Bit on fault only #define MAX_TC_DISCARD_BITS 1 // Data is in D15-D1 - #define MAX_TC_SPEED_BITS 3 // (_BV(SPR1)) // clock ÷ 64 - #else - static uint16_t max_tc_temp = 2000; - #define MAX_TC_ERROR_MASK 4 - #define MAX_TC_DISCARD_BITS 3 - #define MAX_TC_SPEED_BITS 2 // (_BV(SPR0)) // clock ÷ 16 + #define MAX_TC_SPEED_BITS 3 // ~1MHz + #else // MAX6675 + #define MAX_TC_ERROR_MASK 3 // D2 only; 1 = open circuit + #define MAX_TC_DISCARD_BITS 3 // Data D15-D1 + #define MAX_TC_SPEED_BITS 2 // ~2MHz #endif #if HAS_MULTI_MAX_TC // Needed to return the correct temp when this is called between readings - static celsius_t max_tc_temp_previous[MAX_TC_COUNT] = { 0 }; + static int16_t max_tc_temp_previous[MAX_TC_COUNT] = { 0 }; #define THERMO_TEMP(I) max_tc_temp_previous[I] #define THERMO_SEL(A,B) (hindex ? (B) : (A)) - #define MAX6675_WRITE(V) do{ switch (hindex) { case 1: WRITE(MAX6675_SS2_PIN, V); break; default: WRITE(MAX6675_SS_PIN, V); } }while(0) - #define MAX6675_SET_OUTPUT() do{ switch (hindex) { case 1: SET_OUTPUT(MAX6675_SS2_PIN); break; default: SET_OUTPUT(MAX6675_SS_PIN); } }while(0) + #define MAXTC_CS_WRITE(V) do{ switch (hindex) { case 1: WRITE(TEMP_1_CS_PIN, V); break; default: WRITE(TEMP_0_CS_PIN, V); } }while(0) #else + // When we have only 1 max tc, THERMO_SEL will pick the appropriate sensor + // variable, and MAXTC_*() macros will be hardcoded to the correct CS pin. constexpr uint8_t hindex = 0; #define THERMO_TEMP(I) max_tc_temp - #if TEMP_SENSOR_IS_ANY_MAX_TC(1) - #define THERMO_SEL(A,B) B - #else + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) #define THERMO_SEL(A,B) A - #endif - #if TEMP_SENSOR_IS_MAX(0, MAX6675) - #define MAX6675_WRITE(V) WRITE(MAX6675_SS_PIN, V) - #define MAX6675_SET_OUTPUT() SET_OUTPUT(MAX6675_SS_PIN) + #define MAXTC_CS_WRITE(V) WRITE(TEMP_0_CS_PIN, V) #else - #define MAX6675_WRITE(V) WRITE(MAX6675_SS2_PIN, V) - #define MAX6675_SET_OUTPUT() SET_OUTPUT(MAX6675_SS2_PIN) + #define THERMO_SEL(A,B) B + #define MAXTC_CS_WRITE(V) WRITE(TEMP_1_CS_PIN, V) #endif - #endif + static TERN(HAS_MAX31855, uint32_t, uint16_t) max_tc_temp = THERMO_SEL( + TEMP_SENSOR_0_MAX_TC_TMAX, + TEMP_SENSOR_1_MAX_TC_TMAX + ); + static uint8_t max_tc_errors[MAX_TC_COUNT] = { 0 }; + static millis_t next_max_tc_ms[MAX_TC_COUNT] = { 0 }; // Return last-read value between readings - static millis_t next_max_tc_ms[MAX_TC_COUNT] = { 0 }; millis_t ms = millis(); - if (PENDING(ms, next_max_tc_ms[hindex])) return int(THERMO_TEMP(hindex)); - next_max_tc_ms[hindex] = ms + MAX6675_HEAT_INTERVAL; + if (PENDING(ms, next_max_tc_ms[hindex])) + return (int16_t)THERMO_TEMP(hindex); - // - // TODO: spiBegin, spiRec and spiInit doesn't work when soft spi is used. - // - #if !THERMO_SEPARATE_SPI && NO_THERMO_TEMPS - spiBegin(); - spiInit(MAX_TC_SPEED_BITS); - #endif + next_max_tc_ms[hindex] = ms + MAXTC_HEAT_INTERVAL; - #if NO_THERMO_TEMPS - MAX6675_WRITE(LOW); // enable TT_MAX6675 - DELAY_NS(100); // Ensure 100ns delay - #endif + #if !HAS_MAXTC_LIBRARIES + max_tc_temp = 0; - max_tc_temp = 0; + #if !HAS_MAXTC_SW_SPI + // Initialize SPI using the default Hardware SPI bus. + // FIXME: spiBegin, spiRec and spiInit doesn't work when soft spi is used. + spiBegin(); + spiInit(MAX_TC_SPEED_BITS); + #endif - // Read a big-endian temperature value - #if NO_THERMO_TEMPS + MAXTC_CS_WRITE(LOW); // enable MAXTC + DELAY_NS(100); // Ensure 100ns delay + + // Read a big-endian temperature value without using a library for (uint8_t i = sizeof(max_tc_temp); i--;) { - max_tc_temp |= TERN(THERMO_SEPARATE_SPI, max_tc_spi.receive(), spiRec()); + max_tc_temp |= TERN(HAS_MAXTC_SW_SPI, max_tc_spi.receive(), spiRec()); if (i > 0) max_tc_temp <<= 8; // shift left if not the last byte } - MAX6675_WRITE(HIGH); // disable TT_MAX6675 - #endif - #if HAS_MAX31855_TEMP - Adafruit_MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1); - max_tc_temp = max855ref.readRaw32(); - #endif + MAXTC_CS_WRITE(HIGH); // disable MAXTC + #else + #if HAS_MAX6675_LIBRARY + MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1); + max_tc_temp = max6675ref.readRaw16(); + #endif - #if HAS_MAX31865_TEMP - Adafruit_MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1); - #if ENABLED(LIB_USR_MAX31865) - max_tc_temp = max865ref.readRTD_with_Fault(); + #if HAS_MAX31855_LIBRARY + MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1); + max_tc_temp = max855ref.readRaw32(); + #endif + + #if HAS_MAX31865 + MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1); + max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); #endif #endif - #if HAS_MAX6675_TEMP - MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1); - max_tc_temp = max6675ref.readRaw16(); - #endif - - #if ENABLED(LIB_ADAFRUIT_MAX31865) - const uint8_t fault_31865 = max865ref.readFault() & 0x3FU; - #endif - - if (DISABLED(IGNORE_THERMOCOUPLE_ERRORS) - && TERN(LIB_ADAFRUIT_MAX31865, fault_31865, (max_tc_temp & MAX_TC_ERROR_MASK)) - ) { + // Handle an error. If there have been more than THERMOCOUPLE_MAX_ERRORS, send an error over serial. + // Either way, return the TMAX for the thermocouple to trigger a max_temp_error() + if (max_tc_temp & MAX_TC_ERROR_MASK) { max_tc_errors[hindex]++; + if (max_tc_errors[hindex] > THERMOCOUPLE_MAX_ERRORS) { SERIAL_ERROR_START(); SERIAL_ECHOPGM("Temp measurement error! "); - #if MAX_TC_ERROR_MASK == 7 - SERIAL_ECHOPGM("MAX31855 Fault : (", max_tc_temp & 0x7, ") >> "); + #if HAS_MAX31855 + SERIAL_ECHOPAIR("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); else if (max_tc_temp & 0x2) @@ -2738,59 +2731,46 @@ void Temperature::disable_all_heaters() { else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); #elif HAS_MAX31865 - #if ENABLED(LIB_USR_MAX31865) - // At the present time we do not have the ability to set the MAX31865 HIGH threshold - // or thr LOW threshold, so no need to check for them, zero these bits out - const uint8_t fault_31865 = max865ref.readFault() & 0x3FU; - #endif + const uint8_t fault_31865 = max865ref.readFault(); max865ref.clearFault(); if (fault_31865) { SERIAL_EOL(); - SERIAL_ECHOLNPAIR("\nMAX31865 Fault :(", fault_31865, ") >>"); + SERIAL_ECHOLNPAIR("\nMAX31865 Fault: (", fault_31865, ") >>"); if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); if (fault_31865 & MAX31865_FAULT_REFINLOW) - SERIAL_ECHOLNPGM("REFIN- > 0.85 x Bias"); + SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); if (fault_31865 & MAX31865_FAULT_REFINHIGH) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x Bias - FORCE- open"); + SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); if (fault_31865 & MAX31865_FAULT_RTDINLOW) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x Bias - FORCE- open"); + SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); } - #else - SERIAL_ECHOLNPGM("MAX6675 Open Circuit"); + #else // MAX6675 + SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); #endif - // Thermocouple open - max_tc_temp = 4 * THERMO_SEL(TEMP_SENSOR_0_MAX_TC_TMAX, TEMP_SENSOR_1_MAX_TC_TMAX); + // Set thermocouple above max temperature (TMAX) + max_tc_temp = THERMO_SEL(TEMP_SENSOR_0_MAX_TC_TMAX, TEMP_SENSOR_1_MAX_TC_TMAX) << (MAX_TC_DISCARD_BITS + 1); } - else - max_tc_temp >>= MAX_TC_DISCARD_BITS; } else { - max_tc_temp >>= MAX_TC_DISCARD_BITS; - max_tc_errors[hindex] = 0; + max_tc_errors[hindex] = 0; // No error bit, reset error count } - #if HAS_MAX31855 - if (max_tc_temp & 0x00002000) max_tc_temp |= 0xFFFFC000; // Support negative temperature - #endif + max_tc_temp >>= MAX_TC_DISCARD_BITS; - // Return the RTD resistance for MAX31865 for display in SHOW_TEMP_ADC_VALUES - #if HAS_MAX31865_TEMP - #if ENABLED(LIB_ADAFRUIT_MAX31865) - max_tc_temp = (uint32_t(max865ref.readRTD()) * THERMO_SEL(MAX31865_CALIBRATION_OHMS_0, MAX31865_CALIBRATION_OHMS_1)) >> 16; - #elif ENABLED(LIB_USR_MAX31865) - max_tc_temp = (uint32_t(max_tc_temp) * THERMO_SEL(MAX31865_CALIBRATION_OHMS_0, MAX31865_CALIBRATION_OHMS_1)) >> 16; - #endif + #if HAS_MAX31855 + // Support negative temperature for MAX38155 + if (max_tc_temp & 0x00002000) max_tc_temp |= 0xFFFFC000; #endif THERMO_TEMP(hindex) = max_tc_temp; - return int(max_tc_temp); + return (int16_t)max_tc_temp; } #endif // HAS_MAX_TC @@ -2815,16 +2795,16 @@ void Temperature::update_raw_temperatures() { temp_redundant.update(); #endif - TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); - TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update()); - TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update()); - TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); - TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); - TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); - TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); + TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); + TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update()); + TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update()); + TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); + TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); + TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); + TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); TERN_(HAS_TEMP_ADC_CHAMBER, temp_chamber.update()); - TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); - TERN_(HAS_TEMP_ADC_COOLER, temp_cooler.update()); + TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); + TERN_(HAS_TEMP_ADC_COOLER, temp_cooler.update()); TERN_(HAS_JOY_ADC_X, joystick.x.update()); TERN_(HAS_JOY_ADC_Y, joystick.y.update()); @@ -3465,7 +3445,7 @@ void Temperature::isr() { SERIAL_PRINT(t, SFP); #if ENABLED(SHOW_TEMP_ADC_VALUES) // Temperature MAX SPI boards do not have an OVERSAMPLENR defined - SERIAL_ECHOPAIR(" (", TERN(NO_THERMO_TEMPS, false, k == 'T') ? r : r * RECIPROCAL(OVERSAMPLENR)); + SERIAL_ECHOPAIR(" (", TERN(HAS_MAXTC_LIBRARIES, k == 'T', false) ? r : r * RECIPROCAL(OVERSAMPLENR)); SERIAL_CHAR(')'); #endif delay(2); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 3a8c506a5d..26c1dca8af 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -428,6 +428,15 @@ class Temperature { static heater_idle_t heater_idle[NR_HEATER_IDLE]; + #endif // HEATER_IDLE_TIMER + + #if HAS_ADC_BUTTONS + static uint32_t current_ADCKey_raw; + static uint16_t ADCKey_count; + #endif + + #if ENABLED(PID_EXTRUSION_SCALING) + static int16_t lpq_len; #endif private: @@ -486,15 +495,6 @@ class Temperature { #endif public: - #if HAS_ADC_BUTTONS - static uint32_t current_ADCKey_raw; - static uint16_t ADCKey_count; - #endif - - #if ENABLED(PID_EXTRUSION_SCALING) - static int16_t lpq_len; - #endif - /** * Instance Methods */ @@ -915,7 +915,7 @@ class Temperature { #else #define READ_MAX_TC(N) read_max_tc() #endif - static int read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); + static int16_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif static void checkExtruderAutoFans(); diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index ab1446f07c..568086e066 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -133,11 +133,11 @@ #define TEMP_1_PIN 1 // Analog Input #define TEMP_BED_PIN 2 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 066c65be3a..f7e566e2d6 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -73,6 +73,19 @@ #endif #endif +// CS, MISO, MOSI, and SCK for MAX Thermocouple SPI +#if HAS_MAX_TC + //#define TEMP_0_CS_PIN P... + //#define TEMP_0_MISO_PIN P... + //#define TEMP_0_MOSI_PIN P... + //#define TEMP_0_SCK_PIN P... + + //#define TEMP_1_CS_PIN P... + //#define TEMP_1_MISO_PIN P... + //#define TEMP_1_MOSI_PIN P... + //#define TEMP_1_SCK_PIN P... +#endif + // // Heaters / Fans // diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 83fcf36e4e..c25f676a08 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -248,8 +248,8 @@ #define PS_ON_PIN P2_12 // (12) -#if !defined(MAX6675_SS_PIN) && DISABLED(USE_ZMAX_PLUG) - #define MAX6675_SS_PIN P1_28 +#if !defined(TEMP_0_CS_PIN) && DISABLED(USE_ZMAX_PLUG) + #define TEMP_0_CS_PIN P1_28 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h index e244d294f1..19095a5379 100644 --- a/Marlin/src/pins/mega/pins_MALYAN_M180.h +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -72,17 +72,17 @@ #define TEMP_BED_PIN 15 // Analog Input // Extruder thermocouples 0 and 1 are read out by two separate ICs using -// SPI for Max6675 Thermocouple +// SPI for MAX Thermocouple // Uses a separate SPI bus -#define THERMO_SCK_PIN 78 // E2 - SCK -#define THERMO_DO_PIN 3 // E5 - DO -#define THERMO_CS1_PIN 5 // E3 - CS0 -#define THERMO_CS2_PIN 2 // E4 - CS1 +#define TEMP_0_CS_PIN 5 // E3 - CS0 +#define TEMP_0_SCK_PIN 78 // E2 - SCK +#define TEMP_0_MISO_PIN 3 // E5 - MISO +//#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define TEMP_1_CS_PIN 2 // E4 - CS1 +#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN +#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN +//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // // Heaters / Fans diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 2531f10a7a..aea05134a8 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -125,7 +125,7 @@ // K7 - 69 / ADC15 - 15 #define TEMP_BED_PIN 15 -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // Uses a separate SPI bus // // 3 E5 DO (SO) @@ -133,15 +133,15 @@ // 2 E4 CS2 // 78 E2 SCK // -#define THERMO_SCK_PIN 78 // E2 -#define THERMO_DO_PIN 3 // E5 -#define THERMO_CS1_PIN 5 // E3 -#define THERMO_CS2_PIN 2 // E4 +#define TEMP_0_CS_PIN 5 // E3 +#define TEMP_0_SCK_PIN 78 // E2 +#define TEMP_0_MISO_PIN 3 // E5 +//#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define TEMP_1_CS_PIN 2 // E4 +#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN +#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN +//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // // Augmentation for auto-assigning plugs diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 41afe5d891..47c101711c 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -118,11 +118,11 @@ #define SSR_PIN 6 -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 1ab7188b70..8b1cad3a7c 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -760,17 +760,29 @@ #if PIN_EXISTS(LED_RED) REPORT_NAME_DIGITAL(__LINE__, LED_RED_PIN) #endif -#if PIN_EXISTS(MAX6675_DO) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_DO_PIN) +#if PIN_EXISTS(TEMP_0_CS) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_CS_PIN) #endif -#if PIN_EXISTS(MAX6675_SCK) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SCK_PIN) +#if PIN_EXISTS(TEMP_0_SCK) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_SCK_PIN) #endif -#if PIN_EXISTS(MAX6675_SS) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SS_PIN) +#if PIN_EXISTS(TEMP_0_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_MOSI_PIN) #endif -#if PIN_EXISTS(MAX6675_SS2) - REPORT_NAME_DIGITAL(__LINE__, MAX6675_SS2_PIN) +#if PIN_EXISTS(TEMP_0_MISO) + REPORT_NAME_DIGITAL(__LINE__, TEMP_0_MISO_PIN) +#endif +#if PIN_EXISTS(TEMP_1_CS) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_CS_PIN) +#endif +#if PIN_EXISTS(TEMP_1_SCK) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_SCK_PIN) +#endif +#if PIN_EXISTS(TEMP_1_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_MOSI_PIN) +#endif +#if PIN_EXISTS(TEMP_1_MISO) + REPORT_NAME_DIGITAL(__LINE__, TEMP_1_MISO_PIN) #endif #if PIN_EXISTS(MAX7219_CLK) REPORT_NAME_DIGITAL(__LINE__, MAX7219_CLK_PIN) @@ -1010,18 +1022,6 @@ #if PIN_EXISTS(SUICIDE) REPORT_NAME_DIGITAL(__LINE__, SUICIDE_PIN) #endif -#if PIN_EXISTS(THERMO_CS1) - REPORT_NAME_DIGITAL(__LINE__, THERMO_CS1_PIN) -#endif -#if PIN_EXISTS(THERMO_CS2) - REPORT_NAME_DIGITAL(__LINE__, THERMO_CS2_PIN) -#endif -#if PIN_EXISTS(THERMO_DO) - REPORT_NAME_DIGITAL(__LINE__, THERMO_DO_PIN) -#endif -#if PIN_EXISTS(THERMO_SCK) - REPORT_NAME_DIGITAL(__LINE__, THERMO_SCK_PIN) -#endif #if PIN_EXISTS(TLC_BLANK) REPORT_NAME_DIGITAL(__LINE__, TLC_BLANK_PIN) #endif diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 5d6f9c1fd0..f2d34dc00d 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -171,10 +171,10 @@ #define SPINDLE_DIR_PIN 32 // -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // -#ifndef MAX6675_SS_PIN - #define MAX6675_SS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN +#ifndef TEMP_0_CS_PIN + #define TEMP_0_CS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN #endif // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 383501caaa..34a4ceb27d 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -114,11 +114,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index ac0b7428f4..5f645e5d95 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -111,11 +111,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 3 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 76a9fbe628..c953cff3d0 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -111,11 +111,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index c2d4dbeb3f..b13b5e72a0 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -167,10 +167,10 @@ #endif // -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // -#ifndef MAX6675_SS_PIN - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) +#ifndef TEMP_0_CS_PIN + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index a43ee3c6ca..9747666235 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -74,11 +74,11 @@ #define TEMP_0_PIN 2 // Analog Input #define TEMP_BED_PIN 1 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index 345c51d5de..203af5e081 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -75,12 +75,12 @@ #define TEMP_1_PIN 13 // Analog Input #define TEMP_BED_PIN 15 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card + #define TEMP_0_CS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card #else - #define MAX6675_SS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present + #define TEMP_0_CS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present #endif // diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index 53e419af00..de8db60847 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -123,11 +123,11 @@ #define TEMP_1_PIN 15 // Analog Input #define TEMP_BED_PIN 14 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN -1 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN -1 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN -1 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN -1 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index aba8f80e61..57a9a560d3 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -181,11 +181,11 @@ #define TEMP_4_PIN 12 #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple //#if DISABLED(SDSUPPORT) -// #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card +// #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card //#else -// #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) //#endif // diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index de3cb33e8d..81eca3e4b1 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -82,11 +82,11 @@ #define TEMP_2_PIN 5 // Analog Input (unused) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN -1 + #define TEMP_0_CS_PIN -1 #else - #define MAX6675_SS_PIN -1 + #define TEMP_0_CS_PIN -1 #endif // diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index c52199a54d..bc0d29b00a 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -71,11 +71,11 @@ #define TEMP_2_PIN 5 // Analog Input (OnBoard thermistor beta 3950) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #endif // diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 7b0ec5ab68..7a865b4ad8 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -179,11 +179,11 @@ #define TEMP_4_PIN 5 // dummy so will compile when PINS_DEBUGGING is enabled #define TEMP_BED_PIN 4 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif // diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index b1a6680c50..5b2b2f0b66 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -60,12 +60,12 @@ #undef TEMP_BED_PIN #define TEMP_BED_PIN 10 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 69 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 69 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 69 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 69 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index e4c53530f7..30f209ad37 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -109,11 +109,11 @@ #define TEMP_2_PIN 3 // Analog Input #define TEMP_BED_PIN 0 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif // diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 3882dfb944..96d0c9e1cc 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -94,12 +94,12 @@ #undef TEMP_BED_PIN #define TEMP_BED_PIN 11 // Analog Input -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS_PIN +// SPI for MAX Thermocouple +#undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 67 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN 67 // Don't use 53 if using Display/SD card #else - #define MAX6675_SS_PIN 67 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN 67 // Don't use 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index a52af48e11..b217428911 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -156,12 +156,12 @@ #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif */ diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 37ebb567a6..7002886908 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -142,12 +142,12 @@ #define TEMP_5_PIN 6 // A6 (Marlin 2.0 not support) #endif -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 53 + #define TEMP_0_CS_PIN 53 #else - #define MAX6675_SS_PIN 49 + #define TEMP_0_CS_PIN 49 #endif */ diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index e567b0f5e1..a655d0121c 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -149,12 +149,11 @@ #define SD_MISO_PIN 74 #define SD_MOSI_PIN 75 -// SPI for Max6675 or Max31855 Thermocouple -#define MAX6675_SS_PIN 65 -#define MAX31855_SS0 65 -#define MAX31855_SS1 52 -#define MAX31855_SS2 50 -#define MAX31855_SS3 51 +// SPI for MAX Thermocouple +#define TEMP_0_CS_PIN 65 +#define TEMP_1_CS_PIN 52 +#define TEMP_2_CS_PIN 50 +#define TEMP_3_CS_PIN 51 #define ENC424_SS 61 diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index 429cf14ac5..179c04a304 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -100,10 +100,10 @@ //#define TEMP_0_PIN PB3 // E0 K+ #define TEMP_BED_PIN PF7 // THERM_BED -#define MAX6675_SS_PIN PB5 -#define MAX6675_SCK_PIN PB3 -#define MAX6675_DO_PIN PB4 -#define MAX6675_MOSI_PIN PA14 +#define TEMP_0_CS_PIN PB5 +#define TEMP_0_SCK_PIN PB3 +#define TEMP_0_MISO_PIN PB4 +#define TEMP_0_MOSI_PIN PA14 // // Heaters / Fans diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index b9f1074c7a..8da4dcc9de 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -121,8 +121,8 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 // // Filament runout sensor diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index ea3a7a1eea..0e2aee9e99 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -124,8 +124,8 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 // // Misc. Functions diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 6ef3a08043..3a203aab49 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -188,8 +188,8 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 // // Misc. Functions diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index b56971c7a3..129b640d97 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -175,8 +175,8 @@ /** * Note: MKS Robin Pro board is using SPI2 interface. Make sure your stm32duino library is configured accordingly */ -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PF11 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PF11 // TC2 - CS2 #define POWER_LOSS_PIN PA2 // PW_DET #define PS_ON_PIN PG11 // PW_OFF diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 4438ed63ac..3151a38ae8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -298,19 +298,19 @@ #define TEMP_BED_PIN PC0 // T0 <-> Bed -// SPI for Max6675 or Max31855 Thermocouple +// SPI for MAX Thermocouple // Uses a separate SPI bus -// If you have a two-way thermocouple, you can customize two THERMO_CSx_PIN pins (x:1~2) +// If you have a two-way thermocouple, you can customize two TEMP_x_CS_PIN pins (x:0~1) -#define THERMO_SCK_PIN PI1 // SCK -#define THERMO_DO_PIN PI2 // MISO -#define THERMO_CS1_PIN PH9 // GTR K-TEMP -#define THERMO_CS2_PIN PH2 // M5 K-TEMP +#define TEMP_0_CS_PIN PH9 // GTR K-TEMP +#define TEMP_0_SCK_PIN PI1 // SCK +#define TEMP_0_MISO_PIN PI2 // MISO +//#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define MAX6675_SS_PIN THERMO_CS1_PIN -#define MAX6675_SS2_PIN THERMO_CS2_PIN -#define MAX6675_SCK_PIN THERMO_SCK_PIN -#define MAX6675_DO_PIN THERMO_DO_PIN +#define TEMP_1_CS_PIN PH2 // M5 K-TEMP +#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN +#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN +//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // // Heaters / Fans diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 105d0d6f60..65db99025c 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -104,16 +104,16 @@ // MAX6675 Cold-Junction-Compensated K-Thermocouple to Digital Converter (0°C to +1024°C) // https://datasheets.maximintegrated.com/en/ds/MAX6675.pdf -#define MAX6675_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested -#define MAX6675_DO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested -#define MAX6675_SS_PIN PC4 // max6675 datasheet: /CS pin, found with multimeter, not tested and likely wrong +#define TEMP_0_CS_PIN PC4 // max6675 datasheet: /CS pin, found with multimeter, not tested and likely wrong +#define TEMP_0_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested +#define TEMP_0_MISO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested // Expansion board with second max6675 // Warning: Some boards leave the slot unpopulated. -//#define MAX6675_SCK2_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested -//#define MAX6675_DO2_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested -//#define MAX6675_SS2_PIN PF1 // max6675 datasheet: /CS pin, found with multimeter, not tested +//#define TEMP_1_CS_PIN PF1 // max6675 datasheet: /CS pin, found with multimeter, not tested +//#define TEMP_1_SCK_PIN PB3 // max6675 datasheet: SCK pin, found with multimeter, not tested +//#define TEMP_1_MISO_PIN PB4 // max6675 datasheet: SO pin, found with multimeter, not tested // // Heaters / Fans diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 5a056b97cd..9ae2870a40 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -172,8 +172,8 @@ // // Thermocouples // -//#define MAX6675_SS_PIN HEATER_0_PIN // TC1 - CS1 -//#define MAX6675_SS_PIN HEATER_1_PIN // TC2 - CS2 +//#define TEMP_0_CS_PIN HEATER_0_PIN // TC1 - CS1 +//#define TEMP_0_CS_PIN HEATER_1_PIN // TC2 - CS2 // // Misc. Functions diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 2b0df002d3..0b9512a1cb 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -189,8 +189,8 @@ // // Thermocouples // -//#define MAX6675_SS_PIN PE5 // TC1 - CS1 -//#define MAX6675_SS_PIN PE6 // TC2 - CS2 +//#define TEMP_0_CS_PIN PE5 // TC1 - CS1 +//#define TEMP_0_CS_PIN PE6 // TC2 - CS2 // // Misc. Functions diff --git a/ini/features.ini b/ini/features.ini index a1e9688447..5a1b48804d 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -27,9 +27,9 @@ HAS_TMC26X = TMC26XStepper=https://github.com/trinam src_filter=+ HAS_L64XX = Arduino-L6470@0.8.0 src_filter=+ + + + +LIB_INTERNAL_MAX31865 = src_filter=+ NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ -TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 I2C_AMMETER = peterus/INA226Lib@1.1.2 USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 diff --git a/platformio.ini b/platformio.ini index f55f5f5a93..afdd823f9e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -230,6 +230,7 @@ default_src_filter = + - - + - - - - - - + - - - - - From 1093224ba2309d09ca55c4289394d6328a63f043 Mon Sep 17 00:00:00 2001 From: George Fu Date: Wed, 7 Jul 2021 08:40:11 +0800 Subject: [PATCH 0348/2168] =?UTF-8?q?=F0=9F=94=A8=20FYSETC=20S6=20small=20?= =?UTF-8?q?bootloader=20target=20(#22207)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/pins/pins.h | 6 ++-- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 4 ++- Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h | 6 ++++ .../PlatformIO/boards/marlin_fysetc_s6.json | 2 +- .../boards/marlin_fysetc_s6_8000.json | 35 +++++++++++++++++++ ini/stm32f4.ini | 19 ++++++++-- 6 files changed, 64 insertions(+), 8 deletions(-) create mode 100644 buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 88dd170a9e..1f53227553 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -610,11 +610,11 @@ #elif MB(VAKE403D) #include "stm32f4/pins_VAKE403D.h" // STM32F4 #elif MB(FYSETC_S6) - #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 + #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FYSETC_S6_V2_0) - #include "stm32f4/pins_FYSETC_S6_V2_0.h" // STM32F4 env:FYSETC_S6 + #include "stm32f4/pins_FYSETC_S6_V2_0.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FYSETC_SPIDER) - #include "stm32f4/pins_FYSETC_SPIDER.h" // STM32F4 env:FYSETC_S6 + #include "stm32f4/pins_FYSETC_SPIDER.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FLYF407ZG) #include "stm32f4/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG #elif MB(MKS_ROBIN2) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 7aeab0196a..504a86d7d0 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -56,7 +56,9 @@ // // Servos // -#define SERVO0_PIN PA3 +#ifndef SERVO0_PIN + #define SERVO0_PIN PA3 +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index a33f35bd55..e90ac552ae 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -68,6 +68,12 @@ // #define X_ENABLE_PIN PE9 +// +// Servos +// Z_MAX_PIN only works in input mode +// +#define SERVO0_PIN PA2 + #if HAS_TMC_UART #define X_SERIAL_TX_PIN PE7 #define X_SERIAL_RX_PIN PE7 diff --git a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json index 286e46ffbd..42a203786d 100644 --- a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json +++ b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json @@ -21,7 +21,7 @@ "name": "3D Printer control board", "upload": { "maximum_ram_size": 131072, - "maximum_size": 524288, + "maximum_size": 458752, "protocol": "stlink", "protocols": [ "jlink", diff --git a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json new file mode 100644 index 0000000000..1d808a23d7 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json @@ -0,0 +1,35 @@ +{ + "build": { + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F446xx", + "f_cpu": "180000000L", + "mcu": "stm32f446ret6", + "variant": "MARLIN_FYSETC_S6" + }, + "connectivity": [ + "can" + ], + "debug": { + "jlink_device": "STM32F446RE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F446x.svd" + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "3D Printer control board", + "upload": { + "maximum_ram_size": 131072, + "maximum_size": 491520, + "protocol": "stlink", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial" + ] + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html", + "vendor": "FYSETC" +} diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index e7695dcc7a..6067bbc3b8 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -76,15 +76,28 @@ platform = ${common_stm32.platform} extends = common_stm32 platform_packages = tool-stm32duino board = marlin_fysetc_s6 -build_flags = ${common_stm32.build_flags} - -DVECT_TAB_OFFSET=0x10000 - -DHAL_PCD_MODULE_ENABLED +build_flags = ${common_stm32.build_flags} -DVECT_TAB_OFFSET=0x10000 -DHAL_PCD_MODULE_ENABLED extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py debug_tool = stlink upload_protocol = dfu upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" +# +# FYSETC S6 new bootloader +# +[env:FYSETC_S6_8000] +platform = ${common_stm32.platform} +extends = env:FYSETC_S6 +board = marlin_fysetc_s6_8000 +board_build.offset = 0x8000 +board_upload.offset_address = 0x08008000 +build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py +upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" + # # STM32F407VET6 with RAMPS-like shield # 'Black' STM32F407VET6 board - https://wiki.stm32duino.com/index.php?title=STM32F407 From 0595b87d9a86a8ef6bdd4189701cdbd9229ce164 Mon Sep 17 00:00:00 2001 From: ldursw <37294448+ldursw@users.noreply.github.com> Date: Tue, 6 Jul 2021 21:50:01 -0300 Subject: [PATCH 0349/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Maple=20/=20STM3?= =?UTF-8?q?2=20serial=20buffer=20(#22292)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/fix_framework_weakness.py | 12 ------------ .../share/PlatformIO/scripts/stm32_serialbuffer.py | 7 ++++++- ini/stm32f1-maple.ini | 4 +++- ini/stm32f1.ini | 4 ++-- 4 files changed, 11 insertions(+), 16 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py index 29705de442..fa91b7bb70 100644 --- a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py +++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py @@ -30,15 +30,3 @@ if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"): print("Done patching exception handler") print("Libmaple modified and ready for post mortem debugging") - -mf = env["MARLIN_FEATURES"] -rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0" -txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0" -if int(rxBuf) < 64: - rxBuf = "64" -if int(txBuf) < 64: - txBuf = "64" - -build_flags = env.get('BUILD_FLAGS') -build_flags.append("-DUSART_RX_BUF_SIZE=" + rxBuf + " -DUSART_TX_BUF_SIZE=" + txBuf) -env.Replace(BUILD_FLAGS=build_flags) diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py index 2be5a202ef..fecce47db3 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -13,11 +13,16 @@ Import("env") # # The script will set the value as the default one (64 bytes) # or the user-configured one, whichever is higher. +# +# Marlin has 128 and 32 as default values for RX_BUFFER_SIZE and +# TX_BUFFER_SIZE respectively. We use the highest value. mf = env["MARLIN_FEATURES"] -rxBuf = str(max(64, int(mf["RX_BUFFER_SIZE"]) if "RX_BUFFER_SIZE" in mf else 0)) +rxBuf = str(max(128, int(mf["RX_BUFFER_SIZE"]) if "RX_BUFFER_SIZE" in mf else 0)) txBuf = str(max(64, int(mf["TX_BUFFER_SIZE"]) if "TX_BUFFER_SIZE" in mf else 0)) build_flags = env.get('BUILD_FLAGS') build_flags.append("-DSERIAL_RX_BUFFER_SIZE=" + rxBuf) build_flags.append("-DSERIAL_TX_BUFFER_SIZE=" + txBuf) +build_flags.append("-DUSART_RX_BUF_SIZE=" + rxBuf) +build_flags.append("-DUSART_TX_BUF_SIZE=" + txBuf) env.Replace(BUILD_FLAGS=build_flags) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 25ebfb64b6..2580c4700c 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -36,6 +36,7 @@ lib_deps = ${common.lib_deps} platform_packages = tool-stm32duino extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py + pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py # # STM32F103RC @@ -325,7 +326,8 @@ lib_ignore = ${common_stm32f1.lib_ignore} platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_CHITU_F103 -extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py +extra_scripts = ${common_stm32f1.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/common-dependencies.py pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py buildroot/share/PlatformIO/scripts/chitu_crypt.py build_flags = ${common_stm32f1.build_flags} diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 0b394d1730..6c39d0b6fa 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -150,7 +150,7 @@ board_build.variant = MARLIN_F103Rx board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py pre:buildroot/share/PlatformIO/scripts/random-bin.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -174,7 +174,7 @@ board_build.variant = MARLIN_F103Rx board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py debug_tool = jlink From 3d333c4e5d5db64725f20382f92c03a81882dc52 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jul 2021 19:54:02 -0500 Subject: [PATCH 0350/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Fix=20up=20and?= =?UTF-8?q?=20use=20YESNO=5FITEM=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_item.h | 18 +++++++++--------- Marlin/src/lcd/menu/menu_main.cpp | 3 +-- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 0f2bd3cb1f..0a4f4bb7d1 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -434,23 +434,23 @@ class MenuItem_bool : public MenuEditItemBase { }while(0) // Indexed items set a global index value -#define _CONFIRM_ITEM_N_P(N, V...) _CONFIRM_ITEM_N_S_P(N, nullptr, V) +#define _CONFIRM_ITEM_N_P(N, V...) _CONFIRM_ITEM_N_S_P(N, nullptr, V) -#define CONFIRM_ITEM_P(PLABEL,A,B,V...) _CONFIRM_ITEM_P(PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) -#define CONFIRM_ITEM(LABEL, V...) CONFIRM_ITEM_P(GET_TEXT(LABEL), ##V) +#define CONFIRM_ITEM_P(PLABEL,A,B,V...) _CONFIRM_ITEM_P(PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) +#define CONFIRM_ITEM(LABEL, V...) CONFIRM_ITEM_P(GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_P(PLABEL, V...) _CONFIRM_ITEM_P(PLABEL, ##V) -#define YESNO_ITEM(LABEL, V...) YESNO_ITEM_P(GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_P(PLABEL, V...) CONFIRM_ITEM_P(PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM(LABEL, V...) YESNO_ITEM_P(GET_TEXT(LABEL), ##V) #define CONFIRM_ITEM_N_S_P(N,S,PLABEL,A,B,V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) #define CONFIRM_ITEM_N_S(N,S,LABEL,V...) CONFIRM_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) #define CONFIRM_ITEM_N_P(N,PLABEL,A,B,V...) _CONFIRM_ITEM_N_P(N, PLABEL, GET_TEXT(A), GET_TEXT(B), ##V) #define CONFIRM_ITEM_N(N,LABEL, V...) CONFIRM_ITEM_N_P(N, GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_N_S_P(N,S,PLABEL, V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, ##V) -#define YESNO_ITEM_N_S(N,S,LABEL, V...) YESNO_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) -#define YESNO_ITEM_N_P(N,PLABEL, V...) _CONFIRM_ITEM_N_P(N, PLABEL, ##V) -#define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_N_S_P(N,S,PLABEL, V...) _CONFIRM_ITEM_N_S_P(N, S, PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N_S(N,S,LABEL, V...) YESNO_ITEM_N_S_P(N, S, GET_TEXT(LABEL), ##V) +#define YESNO_ITEM_N_P(N,PLABEL, V...) CONFIRM_ITEM_N_P(N, PLABEL, MSG_YES, MSG_NO, ##V) +#define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_P(N, GET_TEXT(LABEL), ##V) #if ENABLED(LEVEL_BED_CORNERS) void _lcd_level_bed_corners(); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 4e3310f238..6f32ef1d60 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -364,8 +364,7 @@ void menu_main() { #if ENABLED(ADVANCED_PAUSE_FEATURE) #if E_STEPPERS == 1 && DISABLED(FILAMENT_LOAD_UNLOAD_GCODES) - CONFIRM_ITEM(MSG_FILAMENTCHANGE, - MSG_YES, MSG_NO, + YESNO_ITEM(MSG_FILAMENTCHANGE, menu_change_filament, ui.goto_previous_screen, GET_TEXT(MSG_FILAMENTCHANGE), (const char *)nullptr, PSTR("?") ); From bec2c50d2927213b67c379a2aded39ded44ac827 Mon Sep 17 00:00:00 2001 From: Serhiy-K <52166448+Serhiy-K@users.noreply.github.com> Date: Wed, 7 Jul 2021 03:55:31 +0300 Subject: [PATCH 0351/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Russian=20and?= =?UTF-8?q?=20Ukrainian=20(#22290)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_ru.h | 26 +++++++++------ Marlin/src/lcd/language/language_uk.h | 46 +++++++++++++++------------ 2 files changed, 42 insertions(+), 30 deletions(-) diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 4240ecbec3..bf2bb02ba3 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -127,23 +127,28 @@ namespace Language_ru { PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Охлаждение"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Управление лазером"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключить шпиндель"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпиндель"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); #else + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинд."); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключ.лазер"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпинд"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощн. лазера"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключ. обдув"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключ. вакуум"); #endif - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); @@ -356,13 +361,14 @@ namespace Language_ru { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); PROGMEM Language_Str MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлаждение"); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасность потока"); - #else - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлажд."); + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охлажд."); PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); + #else + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлажд. лазера"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охл."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопас.потока"); #endif PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Кулер"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 86d0e01fe6..cee795745c 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -34,7 +34,7 @@ namespace Language_uk { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Ukranian"); + PROGMEM Language_Str LANGUAGE = _UxGT("Ukrainian"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Готовий."); PROGMEM Language_Str MSG_YES = _UxGT("ТАК"); @@ -133,23 +133,24 @@ namespace Language_uk { PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужність лазера"); - #else - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потуж.лазера"); - #endif - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкнути шпіндель"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); - #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінделя"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкн. шпіндель"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінделя"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); #else - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінд."); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп. мс"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужн. лазера"); + PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемк. шпінд."); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемк. вакуум"); + PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкн. лазер"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінд."); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп., мс"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкн. обдув"); #endif - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); @@ -361,18 +362,19 @@ namespace Language_uk { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); PROGMEM Language_Str MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодження"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк. охолодж."); #else - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодж."); + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодж. лазеру"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк.охолод"); #endif PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Швидк. вент."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. швидк. вент. ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж.швидк.вент. ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Дод. швидк. вент. ~"); #else PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); @@ -391,8 +393,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Автотемпер."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Увімк"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Вимк."); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Увім"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Вимк"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Автопідбір PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Автопідбір PID *"); @@ -426,8 +428,12 @@ namespace Language_uk { PROGMEM Language_Str MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Швидк.макс *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк.мін"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщення мін"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк. мін"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщення мін"); + #else + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); + #endif PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Прискорення, мм/с2"); PROGMEM Language_Str MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; From 3c746645ccc9239ee96e220b47de59981ee98e64 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 7 Jul 2021 01:18:25 +0000 Subject: [PATCH 0352/2168] [cron] Bump distribution date (2021-07-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b432c821ac..9c9e2d3ee2 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 "2021-07-06" + #define STRING_DISTRIBUTION_DATE "2021-07-07" #endif /** From e5e939bb4c02212ac8a3a7006737b0b8895c7525 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Tue, 6 Jul 2021 19:32:08 -0600 Subject: [PATCH 0353/2168] =?UTF-8?q?=F0=9F=93=BA=20Assorted=20small=20FTD?= =?UTF-8?q?I=20Eve=20Touch=20UI=20fixes=20(#22273)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../archim2-flash/media_file_reader.h | 4 +- .../ftdi_eve_touch_ui/cocoa_press/screens.h | 1 - .../cocoa_press/status_screen.cpp | 10 ++ .../cocoa_press/status_screen.h | 2 + .../ftdi_eve_lib/extended/poly_ui.h | 6 +- .../ftdi_eve_lib/scripts/file2cpp.py | 47 ++++++++ .../ftdi_eve_lib/scripts/font2cpp.py | 108 +++++++++++++++++ .../ftdi_eve_lib/scripts/img2cpp.py | 113 ++++++++++++++++++ .../generic/bed_mesh_edit_screen.cpp | 16 +-- .../generic/bed_mesh_view_screen.cpp | 3 +- .../ftdi_eve_touch_ui/generic/boot_screen.cpp | 6 +- .../confirm_user_request_alert_box.cpp | 15 ++- .../generic/leveling_menu.cpp | 35 +++--- .../ftdi_eve_touch_ui/generic/tune_menu.cpp | 11 +- .../generic/z_offset_screen.cpp | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 4 +- .../src/lcd/extui/ftdi_eve_touch_ui/screens.h | 2 +- .../extui/ftdi_eve_touch_ui/theme/bitmaps.h | 66 ++++++++-- Marlin/src/lcd/extui/ui_api.h | 6 +- 19 files changed, 396 insertions(+), 61 deletions(-) create mode 100755 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py create mode 100755 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py create mode 100755 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h index 249c57b9c6..eb76bb9b2b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h @@ -32,9 +32,7 @@ class MediaFileReader { private: #if ENABLED(SDSUPPORT) - DiskIODriver_SPI_SD card; - SdVolume volume; - SdFile root, file; + SdFile root, file; #endif public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h index 3a47d6bee4..87d31da6f6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -118,7 +118,6 @@ enum { #include "../generic/files_screen.h" #include "../generic/move_axis_screen.h" #include "../generic/flow_percent_screen.h" -#include "../generic/tune_menu.h" #if HAS_JUNCTION_DEVIATION #include "../generic/junction_deviation_screen.h" #else diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index 38fdc2bb26..467d3b9119 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -294,4 +294,14 @@ void StatusScreen::onIdle() { } } +void StatusScreen::onMediaInserted() { + if (AT_SCREEN(StatusScreen)) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); +} + +void StatusScreen::onMediaRemoved() { + if (AT_SCREEN(StatusScreen) || ExtUI::isPrintingFromMedia()) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); +} + #endif // COCOA_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h index 1cddfa0896..75b4333351 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h @@ -52,4 +52,6 @@ class StatusScreen : public BaseScreen, public CachedScreen static bool onTouchHeld(uint8_t tag); static bool onTouchEnd(uint8_t tag); static void onIdle(); + static void onMediaInserted(); + static void onMediaRemoved(); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h index ba41650f2f..2e74ec3a47 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h @@ -239,9 +239,11 @@ class DeduplicatedPolyReader : public POLY_READER { */ template> class GenericPolyUI { - private: + protected: CommandProcessor &cmd; + draw_mode_t mode; + private: // Attributes used to paint buttons uint32_t btn_fill_color = 0x000000; @@ -250,8 +252,6 @@ class GenericPolyUI { uint32_t btn_stroke_color = 0x000000; uint8_t btn_stroke_width = 28; - draw_mode_t mode; - public: enum ButtonStyle : uint8_t { FILL = 1, diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py new file mode 100755 index 0000000000..25919c3c4d --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py @@ -0,0 +1,47 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2021 - SynDaver Labs, Inc. +# +# 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. +# +# To view a copy of the GNU General Public License, go to the following +# location: . + +from __future__ import print_function +import argparse +import textwrap +import os +import zlib + +def deflate(data): + return zlib.compress(data) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a file into a packed C array for use as data') + parser.add_argument("input") + parser.add_argument("-d", "--deflate", action="store_true", help="Packs the data using the deflate algorithm") + args = parser.parse_args() + + varname = os.path.splitext(os.path.basename(args.input))[0]; + + with open(args.input, "rb") as in_file: + data = in_file.read() + if args.deflate: + data = deflate(data) + data = bytearray(data) + data = list(map(lambda a: "0x" + format(a, '02x'), data)) + nElements = len(data) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + + print("const unsigned char " + varname + "[" + format(nElements) + "] PROGMEM = {") + print(data) + print("};") diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py new file mode 100755 index 0000000000..0c4499e9aa --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py @@ -0,0 +1,108 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2019 - Aleph Objects, Inc. +# +# 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. +# +# To view a copy of the GNU General Public License, go to the following +# location: . + +from __future__ import print_function +from PIL import Image +import argparse +import textwrap + +def pack_rle(data): + """Use run-length encoding to pack the bytes""" + rle = [] + value = data[0] + count = 0 + for i in data: + if i != value or count == 255: + rle.append(count) + rle.append(value) + value = i + count = 1 + else: + count += 1 + rle.append(count) + rle.append(value) + return rle + +class WriteSource: + def __init__(self, lines_in_blocks): + self.blocks = [] + self.values = [] + self.block_size = lines_in_blocks + self.rows = 0 + + def add_pixel(self, value): + self.values.append(value) + + def convert_to_4bpp(self, data, chunk_size = 0): + # Invert the image + data = list(map(lambda i: 255 - i, data)) + # Quanitize 8-bit values into 4-bits + data = list(map(lambda i: i >> 4, data)) + # Make sure there is an even number of elements + if (len(data) & 1) == 1: + data.append(0) + # Combine each two adjacent values into one + i = iter(data) + data = list(map(lambda a, b: a << 4 | b, i ,i)) + # Pack the data + data = pack_rle(data) + # Convert values into hex strings + return list(map(lambda a: "0x" + format(a, '02x'), data)) + + def end_row(self, y): + # Pad each row into even number of values + if len(self.values) & 1: + self.values.append(0) + + self.rows += 1 + if self.block_size and (self.rows % self.block_size) == 0: + self.blocks.append(self.values) + self.values = [] + + def write(self): + if len(self.values): + self.blocks.append(self.values) + + block_strs = []; + for b in self.blocks: + data = self.convert_to_4bpp(b) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + block_strs.append(data) + + print("const unsigned char font[] PROGMEM = {") + for i, b in enumerate(block_strs): + if i: + print(',') + print('\n /* {} */'.format(i)) + print(b, end='') + print("\n};") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a grayscale bitmap into a 16-level RLE packed C array for use as font data') + parser.add_argument("input") + parser.add_argument('--char_height', help='Adds a separator every so many lines', type=int) + args = parser.parse_args() + + writer = WriteSource(args.char_height) + + img = Image.open(args.input).convert('L') + for y in range(img.height): + for x in range(img.width): + writer.add_pixel(img.getpixel((x,y))) + writer.end_row(y) + writer.write() diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py new file mode 100755 index 0000000000..5908f5bf17 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py @@ -0,0 +1,113 @@ +#!/usr/bin/python + +# Written By Marcio Teixeira 2021 - SynDaver Labs, Inc. +# +# 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. +# +# To view a copy of the GNU General Public License, go to the following +# location: . + +from __future__ import print_function +from PIL import Image +import argparse +import textwrap +import os +import sys +import zlib + +class WriteSource: + def __init__(self, mode): + self.values = [] + self.mode = mode + self.offset = 8 + self.byte = 0 + + def finish_byte(self): + if self.offset != 8: + self.values.append(self.byte) + self.offset = 8 + self.byte = 0 + + def add_bits_to_byte(self, value, size = 1): + self.offset -= size + self.byte = self.byte | value << self.offset + if self.offset == 0: + self.finish_byte() + + def append_rgb565(self, color): + value = ((color[0] & 0xF8) << 8) + ((color[1] & 0xFC) << 3) + ((color[2] & 0xF8) >> 3) + self.values.append((value & 0x00FF) >> 0); + self.values.append((value & 0xFF00) >> 8); + + def append_rgb332(self, color): + value = (color[0] & 0xE0) + ((color[1] & 0xE0) >> 3) + ((color[2] & 0xC0) >> 6) + self.values.append(value); + + def append_grayscale(self, color, bits): + luminance = int(0.2126 * color[0] + 0.7152 * color[1] + 0.0722 * color[2]) + self.add_bits_to_byte(luminance >> (8 - bits), bits) + + def deflate(self, data): + return zlib.compress(data) + + def add_pixel(self, color): + if self.mode == "l1": + self.append_grayscale(color, 1) + elif self.mode == "l2": + self.append_grayscale(color, 2) + elif self.mode == "l4": + self.append_grayscale(color, 4) + elif self.mode == "l8": + self.append_grayscale(color, 8) + elif self.mode == "rgb565": + self.append_rgb565(color) + elif self.mode == "rgb332": + self.append_rgb332(color) + + def end_row(self, y): + if self.mode in ["l1", "l2", "l3"]: + self.finish_byte() + + def write(self, varname, deflate): + print("Length of uncompressed data: ", len(self.values), file=sys.stderr) + data = bytes(bytearray(self.values)) + if deflate: + data = self.deflate(data) + print("Length of data after compression: ", len(data), file=sys.stderr) + data = bytearray(data) + data = list(map(lambda a: "0x" + format(a, '02x'), data)) + nElements = len(data) + data = ', '.join(data) + data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') + + print("const unsigned char " + varname + "[" + format(nElements) + "] PROGMEM = {") + print(data) + print("};") + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Converts a bitmap into a C array') + parser.add_argument("input") + parser.add_argument("-d", "--deflate", action="store_true", help="Packs the data using the deflate algorithm") + parser.add_argument("-m", "--mode", default="l1", help="Mode, can be l1, l2, l4, l8, rgb332 or rgb565") + args = parser.parse_args() + + varname = os.path.splitext(os.path.basename(args.input))[0]; + + writer = WriteSource(args.mode) + + img = Image.open(args.input) + print("Image height: ", img.height, file=sys.stderr) + print("Image width: ", img.width, file=sys.stderr) + for y in range(img.height): + for x in range(img.width): + writer.add_pixel(img.getpixel((x,y))) + writer.end_row(y) + writer.write(varname, args.deflate) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index e06fb52773..3dfcd429a5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -190,17 +190,11 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { } void BedMeshEditScreen::show() { - // On entry, home if needed and save current mesh - if (!ExtUI::isMachineHomed()) { - SpinnerDialogBox::enqueueAndWait_P(F("G28\nG29 S1")); - // After the spinner, go to this screen. - current_screen.forget(); - PUSH_SCREEN(BedMeshEditScreen); - } - else { - injectCommands_P(PSTR("G29 S1")); - GOTO_SCREEN(BedMeshEditScreen); - } + // On entry, always home (to account for possible Z offset changes) and save current mesh + SpinnerDialogBox::enqueueAndWait_P(F("G28\nG29 S1")); + // After the spinner, go to this screen. + current_screen.forget(); + PUSH_SCREEN(BedMeshEditScreen); } #endif // FTDI_BED_MESH_EDIT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 75b15828a2..552cd831ea 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -132,7 +132,6 @@ void BedMeshViewScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI mydata.count = GRID_MAX_POINTS; break; case ExtUI::G26_START: - GOTO_SCREEN(BedMeshViewScreen); mydata.message = nullptr; mydata.count = 0; break; @@ -161,7 +160,7 @@ void BedMeshViewScreen::doProbe() { void BedMeshViewScreen::doMeshValidation() { mydata.count = 0; GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("M75\nG28 O\nM117 Heating...\nG26 R X0 Y0\nG27\nM77")); + injectCommands_P(PSTR("G28\nM117 Heating...\nG26 R X0 Y0\nG27")); } void BedMeshViewScreen::show() { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp index d2a2269295..c0940bed5c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp @@ -83,8 +83,10 @@ void BootScreen::onIdle() { if (UIData::animations_enabled()) { // If there is a startup video in the flash SPI, play // that, otherwise show a static splash screen. - if (!MediaPlayerScreen::playBootMedia()) - showSplashScreen(); + #ifdef FTDI_MEDIA_PLAYER_SCREEN + if (!MediaPlayerScreen::playBootMedia()) + #endif + showSplashScreen(); } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp index 4aabbaab59..c10d372743 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp @@ -35,12 +35,15 @@ void ConfirmUserRequestAlertBox::onRedraw(draw_mode_t mode) { bool ConfirmUserRequestAlertBox::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - if (ExtUI::isPrintingPaused()) { - // The TuneMenu will call ExtUI::setUserConfirmed() - GOTO_SCREEN(TuneMenu); - current_screen.forget(); - } - else { + #ifdef FTDI_TUNE_MENU + if (ExtUI::isPrintingPaused()) { + // The TuneMenu will call ExtUI::setUserConfirmed() + GOTO_SCREEN(TuneMenu); + current_screen.forget(); + } + else + #endif + { ExtUI::setUserConfirmed(); GOTO_PREVIOUS(); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 826e01a9cf..797bb37996 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -83,6 +83,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .font(font_medium).colors(normal_btn) .enabled(EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION)) .tag(2).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_LEVEL_X_AXIS)) + .enabled(ENABLED(HAS_BED_PROBE)) .tag(3).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) .enabled(ENABLED(HAS_MESH)) .tag(4).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) @@ -101,30 +102,32 @@ void LevelingMenu::onRedraw(draw_mode_t what) { bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: GOTO_PREVIOUS(); break; + case 1: GOTO_PREVIOUS(); break; #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) - case 2: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; + case 2: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; #endif - case 3: - #ifndef BED_LEVELING_COMMANDS - #define BED_LEVELING_COMMANDS "G29" + #if ENABLED(HAS_BED_PROBE) + case 3: + #ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + BedMeshViewScreen::doProbe(); + #else + SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); + #endif + break; #endif #if ENABLED(AUTO_BED_LEVELING_UBL) - BedMeshViewScreen::doProbe(); - #else - SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); - #endif - break; - #if ENABLED(AUTO_BED_LEVELING_UBL) - case 4: BedMeshViewScreen::show(); break; - case 5: BedMeshEditScreen::show(); break; + case 4: BedMeshViewScreen::show(); break; + case 5: BedMeshEditScreen::show(); break; #endif #if ENABLED(G26_MESH_VALIDATION) - case 6: BedMeshViewScreen::doMeshValidation(); break; + case 6: BedMeshViewScreen::doMeshValidation(); break; #endif #if ENABLED(BLTOUCH) - case 7: injectCommands_P(PSTR("M280 P0 S60")); break; - case 8: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + case 7: injectCommands_P(PSTR("M280 P0 S60")); break; + case 8: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; #endif default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index b4afae9f17..a5e2460631 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -77,8 +77,11 @@ void TuneMenu::onRedraw(draw_mode_t what) { .tag(3).button(FIL_CHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(9).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) - .enabled(BOTH(HAS_LEVELING, HAS_BED_PROBE) || ENABLED(BABYSTEPPING)) - .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(TERN(BABYSTEPPING, MSG_NUDGE_NOZZLE, MSG_ZPROBE_ZOFFSET))) + #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND + .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_NUDGE_NOZZLE)) + #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + #endif .tag(5).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) .enabled(sdOrHostPrinting) .tag(sdOrHostPaused ? 7 : 6) @@ -99,11 +102,11 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { using namespace Theme; using namespace ExtUI; switch (tag) { - case 1: GOTO_PREVIOUS(); break; + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: GOTO_SCREEN(TemperatureScreen); break; case 3: GOTO_SCREEN(ChangeFilamentScreen); break; case 4: - #if ENABLED(BABYSTEPPING) + #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND GOTO_SCREEN(NudgeNozzleScreen); #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) GOTO_SCREEN(ZOffsetScreen); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp index 073665e586..2a75596a03 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -53,7 +53,7 @@ void ZOffsetScreen::onRedraw(draw_mode_t what) { w.heading( GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); w.color(z_axis).adjuster(4, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), getZOffset_mm()); w.increments(); - w.button(2, GET_TEXT_F(MSG_PROBE_WIZARD), !isPrinting()); + w.button(2, GET_TEXT_F(MSG_PROBE_WIZARD), !isPrinting() && !wizardRunning()); } void ZOffsetScreen::move(float mm, int16_t steps) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 4ac44501d5..0d883d8d02 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -130,7 +130,7 @@ namespace Language_en { PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; PROGMEM Language_Str MSG_EEPROM_SAVED = u8"Settings saved!"; - PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings for next power-on?"; + PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Settings applied. Save these settings for next power-on?"; PROGMEM Language_Str MSG_EEPROM_RESET_WARNING = u8"Are you sure? Customizations will be lost."; PROGMEM Language_Str MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; @@ -146,7 +146,7 @@ namespace Language_en { PROGMEM Language_Str MSG_AXIS_LEVELING = u8"Axis Leveling"; PROGMEM Language_Str MSG_PROBE_BED = u8"Probe Mesh"; PROGMEM Language_Str MSG_SHOW_MESH = u8"View Mesh"; - PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test"; + PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test (PLA)"; PROGMEM Language_Str MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; #if ENABLED(TOUCH_UI_LULZBOT_BIO) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h index 4fe4cb938a..fb3e909d2f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -40,7 +40,7 @@ extern tiny_timer_t refresh_timer; #if ENABLED(TOUCH_UI_LULZBOT_BIO) #include "bioprinter/screens.h" #elif ENABLED(TOUCH_UI_COCOA_PRESS) - #include "cocoapress/screens.h" + #include "cocoa_press/screens.h" #elif ENABLED(TOUCH_UI_SYNDAVER_LEVEL) #include "syndaver_level/screens.h" #else diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h index 8c0366ebeb..f7cb63125f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -36,7 +36,7 @@ namespace Theme { .height = 23, }; - constexpr PROGMEM unsigned char Extruder_Icon[] = { + constexpr PROGMEM unsigned char Extruder_Icon[69] = { 0x3F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFE, 0xC0, 0x00, 0x03, @@ -68,12 +68,12 @@ namespace Theme { .filter = BILINEAR, .wrapx = BORDER, .wrapy = BORDER, - .RAMG_offset = 8100, + .RAMG_offset = 8069, .width = 32, .height = 23, }; - constexpr PROGMEM unsigned char Bed_Heat_Icon[] = { + constexpr PROGMEM unsigned char Bed_Heat_Icon[92] = { 0x01, 0x81, 0x81, 0x80, 0x01, 0x81, 0x81, 0x80, 0x00, 0xC0, 0xC0, 0xC0, @@ -105,12 +105,12 @@ namespace Theme { .filter = BILINEAR, .wrapx = BORDER, .wrapy = BORDER, - .RAMG_offset = 8300, + .RAMG_offset = 8161, .width = 32, .height = 32, }; - constexpr PROGMEM unsigned char Fan_Icon[] = { + constexpr PROGMEM unsigned char Fan_Icon[128] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x1F, @@ -151,12 +151,12 @@ namespace Theme { .filter = BILINEAR, .wrapx = BORDER, .wrapy = BORDER, - .RAMG_offset = 9000, + .RAMG_offset = 8289, .width = 50, .height = 20, }; - constexpr PROGMEM unsigned char TD_Icon[] = { + constexpr PROGMEM unsigned char TD_Icon[140] = { 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, // Thumb Drive Widget 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x03, 0x80, @@ -179,5 +179,55 @@ namespace Theme { 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00 }; - constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; + constexpr PROGMEM bitmap_info_t File_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8429, + .width = 25, + .height = 32, + }; + + const unsigned char File_Icon[128] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x40, 0x03, 0x00, 0x00, + 0x40, 0x02, 0x80, 0x00, 0x40, 0x02, 0x40, 0x00, 0x40, 0x02, 0x20, 0x00, + 0x40, 0x02, 0x10, 0x00, 0x40, 0x02, 0x08, 0x00, 0x40, 0x02, 0x04, 0x00, + 0x40, 0x02, 0x02, 0x00, 0x40, 0x03, 0xFF, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, + 0x7F, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00 + }; + + constexpr PROGMEM bitmap_info_t Clock_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8557, + .width = 32, + .height = 32, + }; + + const unsigned char Clock_Icon[128] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7E, 0x7E, 0x00, + 0x00, 0xE0, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x07, 0x01, 0x00, 0xE0, + 0x0C, 0x01, 0x80, 0x70, 0x0C, 0x01, 0x80, 0x30, 0x18, 0x01, 0x80, 0x18, + 0x30, 0x01, 0x80, 0x08, 0x30, 0x01, 0x80, 0x0C, 0x20, 0x01, 0x80, 0x0C, + 0x60, 0x01, 0x80, 0x04, 0x60, 0x01, 0x80, 0x06, 0x60, 0x01, 0x80, 0x06, + 0x60, 0x01, 0xFF, 0x06, 0x60, 0x01, 0xFF, 0x06, 0x60, 0x00, 0x00, 0x06, + 0x60, 0x00, 0x00, 0x06, 0x60, 0x00, 0x00, 0x04, 0x20, 0x00, 0x00, 0x0C, + 0x30, 0x00, 0x00, 0x0C, 0x30, 0x00, 0x00, 0x08, 0x18, 0x00, 0x00, 0x18, + 0x0C, 0x00, 0x00, 0x30, 0x0E, 0x00, 0x00, 0x70, 0x07, 0x00, 0x00, 0xE0, + 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x07, 0x00, 0x00, 0x7F, 0xFE, 0x00, + 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00 + }; + + constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; }; // namespace Theme diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 8d8b0e59e4..5efd74b8df 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -190,7 +190,11 @@ namespace ExtUI { void setHostResponse(const uint8_t); #endif - inline void simulateUserClick() { ui.lcd_clicked = true; } + inline void simulateUserClick() { + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + ui.lcd_clicked = true; + #endif + } #if ENABLED(PRINTCOUNTER) char* getFailedPrints_str(char buffer[21]); From 82193b092367f23069129a42c37e9c46654ff4af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Krzysztof=20B=C5=82a=C5=BCewicz?= Date: Wed, 7 Jul 2021 04:10:40 +0200 Subject: [PATCH 0354/2168] =?UTF-8?q?=E2=9C=A8=20DWIN=20LCD=20for=20BTT=20?= =?UTF-8?q?SKR=20Mini=20E3=20(#22288)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 6 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 78 ++++++++++++------- 3 files changed, 56 insertions(+), 30 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 833fe0d227..a9ad5018e8 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1078,7 +1078,11 @@ #if ENABLED(DWIN_CREALITY_LCD) #define SERIAL_CATCHALL 0 #ifndef LCD_SERIAL_PORT - #define LCD_SERIAL_PORT 3 // Creality 4.x board + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) + #define LCD_SERIAL_PORT 1 + #else + #define LCD_SERIAL_PORT 3 // Creality 4.x board + #endif #endif #endif diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 4719dd8111..970a402b30 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -202,7 +202,7 @@ #define EXP1_10_PIN P2_08 #if ENABLED(DWIN_CREALITY_LCD) - #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16, and LCD_SERIAL_PORT 1. Comment out this line to continue." + #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." #define BEEPER_PIN EXP1_10_PIN #define BTN_EN1 EXP1_03_PIN diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 5850f11ef0..8f305542a9 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -117,14 +117,14 @@ /** * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 - * _____ _____ - * 5V | 1 2 | GND 5V | 1 2 | GND - * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PB5 (BEEPER) (BTN_ENC) PA15 | 9 10| PB5 (BEEPER) - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND 5V | 1 2 | GND + * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) + * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) + * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) + * (BTN_ENC) PB6 | 9 10 | PB5 (BEEPER) (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) + * ------ ------ + * EXP1 EXP1 */ #ifdef SKR_MINI_E3_V2 #define EXP1_9 PA15 @@ -134,7 +134,28 @@ #define EXP1_3 PB7 #endif -#if HAS_WIRED_LCD +#if ENABLED(DWIN_CREALITY_LCD) + /** + * ------ ------ ------ + * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC + * A | 3 4 | B A | 3 4 | B B | 4 3 | A + * | 5 6 TX BEEP | 5 6 ENT ENT | 6 5 | BEEP + * | 7 8 | RX TX | 7 8 | RX RX | 8 7 | TX + * BEEP | 9 10 | ENT | 9 10 | | 10 9 | + * ------ ------ ------ + * EXP1 DWIN DWIN (plug) + * + * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. + */ + + #error "DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. Comment out this line to continue." + + #define BEEPER_PIN EXP1_9 + #define BTN_EN1 EXP1_3 + #define BTN_EN2 PB8 + #define BTN_ENC PB5 + +#elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -184,19 +205,19 @@ * TFTGLCD_PANEL_SPI display pinout * * Board Display - * _____ _____ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) - * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * - * Board Adapter Display - * _________ + * Board Display + * * EXP1-1 ----------- EXP1-10 * EXP1-2 ----------- EXP1-9 * SPI1-4 ----------- EXP1-6 @@ -223,17 +244,18 @@ #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." - /** FYSETC TFT TFT81050 display pinout + /** + * FYSETC TFT TFT81050 display pinout * * Board Display - * _____ _____ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * ______ ______ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * From 094caadf9471a51a877bcc61f40081266fdc19d3 Mon Sep 17 00:00:00 2001 From: Mihai Date: Wed, 7 Jul 2021 07:10:35 +0300 Subject: [PATCH 0355/2168] =?UTF-8?q?=E2=9C=A8=20Enable=20'M20=20L'=20with?= =?UTF-8?q?=20LONG=5FFILENAME=5FHOST=5FSUPPORT=20(#22271)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/sd/M20.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 92 +++++++++++++++++++++++------------- Marlin/src/sd/cardreader.h | 9 +++- 3 files changed, 68 insertions(+), 35 deletions(-) diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp index 7ac4affdae..5731838338 100644 --- a/Marlin/src/gcode/sd/M20.cpp +++ b/Marlin/src/gcode/sd/M20.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M20() { if (card.flag.mounted) { SERIAL_ECHOLNPGM(STR_BEGIN_FILE_LIST); - card.ls(); + card.ls(TERN_(LONG_FILENAME_HOST_SUPPORT, parser.boolval('L'))); SERIAL_ECHOLNPGM(STR_END_FILE_LIST); } else diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 19b2f04bfd..bcb0317990 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -258,54 +258,82 @@ void CardReader::selectByName(SdFile dir, const char * const match) { } } -// -// Recursive method to print all files within a folder in flat -// DOS 8.3 format. This style of listing is the most compatible -// with legacy hosts. -// -// This method recurses to unlimited depth and lists every -// G-code file within the given parent. If the hierarchy is -// very deep this can blow up the stack, so a 'depth' parameter -// (as with printListingJSON) would be a good addition. -// -void CardReader::printListing(SdFile parent, const char * const prepend/*=nullptr*/) { +/** + * Recursive method to print all files within a folder in flat + * DOS 8.3 format. This style of listing is the most compatible + * with legacy hosts. + * + * This method recurses to unlimited depth and lists all G-code + * files within the given parent. If the hierarchy is very deep + * this can blow up the stack, so a 'depth' parameter would be a + * good addition. + */ +void CardReader::printListing( + SdFile parent + OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames/*=false*/) + , const char * const prepend/*=nullptr*/ + OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong/*=nullptr*/) +) { dir_t p; while (parent.readDir(&p, longFilename) > 0) { if (DIR_IS_SUBDIR(&p)) { - // Get the short name for the item, which we know is a folder - char dosFilename[FILENAME_LENGTH]; + size_t lenPrepend = prepend ? strlen(prepend) + 1 : 0; + // Allocate enough stack space for the full path including / separator + char path[lenPrepend + FILENAME_LENGTH]; + if (prepend) { + strcpy(path, prepend); + path[lenPrepend - 1] = '/'; + } + char* dosFilename = path + lenPrepend; createFilename(dosFilename, p); - // Allocate enough stack space for the full path to a folder, trailing slash, and nul - const bool prepend_is_empty = (!prepend || prepend[0] == '\0'); - const int len = (prepend_is_empty ? 1 : strlen(prepend)) + strlen(dosFilename) + 1 + 1; - char path[len]; - - // Append the FOLDERNAME12/ to the passed string. - // It contains the full path to the "parent" argument. - // We now have the full path to the item in this folder. - strcpy(path, prepend_is_empty ? "/" : prepend); // root slash if prepend is empty - strcat(path, dosFilename); // FILENAME_LENGTH characters maximum - strcat(path, "/"); // 1 character - - // Serial.print(path); - // Get a new directory object using the full path // and dive recursively into it. SdFile child; // child.close() in destructor if (child.open(&parent, dosFilename, O_READ)) - printListing(child, path); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + if (includeLongNames) { + size_t lenPrependLong = prependLong ? strlen(prependLong) + 1 : 0; + // Allocate enough stack space for the full long path including / separator + char pathLong[lenPrependLong + strlen(longFilename) + 1]; + if (prependLong) { + strcpy(pathLong, prependLong); + pathLong[lenPrependLong - 1] = '/'; + } + strcpy(pathLong + lenPrependLong, longFilename); + printListing(child, /*includeLongNames=*/true, path, pathLong); + } + else + #endif + printListing(child, path); else { SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); return; } } else if (is_dir_or_gcode(p)) { - if (prepend) SERIAL_ECHO(prepend); + if (prepend) { + SERIAL_ECHO(prepend); + SERIAL_CHAR('/'); + } SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); - SERIAL_ECHOLN(p.fileSize); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + if (!includeLongNames) + #endif + SERIAL_ECHOLN(p.fileSize); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + else { + SERIAL_ECHO(p.fileSize); + SERIAL_CHAR(' '); + if (prependLong) { + SERIAL_ECHO(prependLong); + SERIAL_CHAR('/'); + } + SERIAL_ECHOLN(longFilename[0] ? longFilename : "???"); + } + #endif } } } @@ -313,10 +341,10 @@ void CardReader::printListing(SdFile parent, const char * const prepend/*=nullpt // // List all files on the SD card // -void CardReader::ls() { +void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=false*/)) { if (flag.mounted) { root.rewind(); - printListing(root); + printListing(root OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 943cdae741..66cb97baeb 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -199,7 +199,7 @@ public: FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } #endif - static void ls(); + static void ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames=false)); #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); @@ -330,7 +330,12 @@ private: static int countItems(SdFile dir); static void selectByIndex(SdFile dir, const uint8_t index); static void selectByName(SdFile dir, const char * const match); - static void printListing(SdFile parent, const char * const prepend=nullptr); + static void printListing( + SdFile parent + OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames=false) + , const char * const prepend=nullptr + OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong=nullptr) + ); #if ENABLED(SDCARD_SORT_ALPHA) static void flush_presort(); From 9642a3689544716610ed78ace36548505460d82f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 8 Jul 2021 00:56:59 +0000 Subject: [PATCH 0356/2168] [cron] Bump distribution date (2021-07-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index eb2f9f9a14..e63dd350c7 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2019-07-10" +//#define STRING_DISTRIBUTION_DATE "2021-07-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9c9e2d3ee2..cc1653a5b1 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 "2021-07-07" + #define STRING_DISTRIBUTION_DATE "2021-07-08" #endif /** From 0d5db6aa75268740037bcaafa51759ebc353ec34 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Thu, 8 Jul 2021 00:41:33 -0400 Subject: [PATCH 0357/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20redundant=20heat?= =?UTF-8?q?er=20/=20sensor=20pin=20assignments=20(#22309)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 4 ++-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 2 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- 7 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 568086e066..3930279c94 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -192,7 +192,7 @@ #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") #define FAN_PIN RAMPS_D9_PIN #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index f7e566e2d6..ba53032a2a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -65,7 +65,7 @@ #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 #if TEMP_SENSOR_PROBE #define TEMP_PROBE_PIN TEMP_1_PIN #elif TEMP_SENSOR_CHAMBER @@ -92,7 +92,7 @@ #ifndef HEATER_0_PIN #define HEATER_0_PIN P2_07 #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN P2_04 #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index f998ecde4e..68e1389841 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -202,7 +202,7 @@ // #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN P2_06 #endif diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index c25f676a08..fe7daa8cda 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -217,7 +217,7 @@ #define FAN1_PIN RAMPS_D8_PIN #elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index b13b5e72a0..fb143fa8bc 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -219,7 +219,7 @@ #define FAN1_PIN RAMPS_D8_PIN #elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 + #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN #else #define HEATER_1_PIN MOSFET_D_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 0e2aee9e99..0a6186cf57 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -105,7 +105,7 @@ #ifndef HEATER_0_PIN #define HEATER_0_PIN PC3 #endif -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #ifndef FAN1_PIN #define FAN1_PIN PB0 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index d465bb23c7..a9dfc367bf 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -210,7 +210,7 @@ #define TEMP_0_PIN PA2 // TH0 #define TEMP_1_PIN PA3 // TH1 -#if HOTENDS == 1 +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #if TEMP_SENSOR_PROBE #define TEMP_PROBE_PIN TEMP_1_PIN #elif TEMP_SENSOR_CHAMBER From 20b3403ee845113f0818265a5c03e72781b82074 Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Thu, 8 Jul 2021 06:44:07 +0200 Subject: [PATCH 0358/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Hungarian=20l?= =?UTF-8?q?anguage=20(#22307)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_hu.h | 68 ++++++++++++++++++++------- 1 file changed, 51 insertions(+), 17 deletions(-) diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 0c73d9a85a..ebbc4b2df7 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -26,11 +26,11 @@ * * LCD Menu Messages. See also https://marlinfw.org/docs/development/lcd_language.html * Hungarian translation by AntoszHUN. I am constantly improving and updating the translation. - * Translation last updated: 23/05/2021 - 20:45 + * Translation last updated: 07/07/2021 - 11:20 * * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html * A Magyar fordítást készítette: AntoszHUN. A fordítást folyamatosan javítom és frissítem. - * A Fordítás utolsó frissítése: 2021.05.23. - 20:45 + * A Fordítás utolsó frissítése: 2021.07.07. - 11:20 */ namespace Language_hu { @@ -66,6 +66,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X kezdöpont"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y kezdöpont"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z kezdöpont"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Kezdö ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Kezdö ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Kezdö ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-igazítás"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ismétlés: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Pontosság csökken!"); @@ -79,6 +82,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Elektromos segéd"); @@ -259,6 +265,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_X = _UxGT("X mozgás"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y mozgás"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z mozgás"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Mozgás ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Mozgás ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Mozgás ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Adagoló"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Adagoló *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); @@ -267,9 +276,10 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.001mm"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.01mm"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 0.1mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.025mm"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.254mm"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 2.54mm"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Mozgáá 25.4mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Sebesség"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z ágy"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Fej"); @@ -321,16 +331,22 @@ namespace Language_hu { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); - PROGMEM Language_Str MSG_VA_JERK = LCD_STR_A _UxGT(" Ránt. seb."); - PROGMEM Language_Str MSG_VB_JERK = LCD_STR_B _UxGT(" Ránt. seb."); - PROGMEM Language_Str MSG_VC_JERK = LCD_STR_C _UxGT(" Ránt. seb."); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Seb.") LCD_STR_A _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Seb.") LCD_STR_B _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Seb.") LCD_STR_C _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Seb.") LCD_STR_I _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Seb.") LCD_STR_J _UxGT("-Rántás"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Seb.") LCD_STR_K _UxGT("-Rántás"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("E ránt. seb."); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max sebesség ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max sebesség ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max sebesség ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max sebesség ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Seb. ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max Seb. ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max Seb. ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max Seb. ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max Seb. ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max Seb. ") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Seb. ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max sebesség *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Min sebesség"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); @@ -338,6 +354,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max gyors. ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max gyors. ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max gyors. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max gyors. ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max gyors. ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max gyors. ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max gyors. ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max gyorsulás *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Visszahúzás"); @@ -345,11 +364,14 @@ namespace Language_hu { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max frekvencia"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min elötolás"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" lépés/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" lépés/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Lépés/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Lépés/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*lépés/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*Lépés/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); PROGMEM Language_Str MSG_MOTION = _UxGT("Mozgatások"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Nyomtatószál"); @@ -481,6 +503,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Mikrolépés ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Mikrolépés ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Mikrolépés ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); @@ -524,8 +549,8 @@ namespace Language_hu { PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló szintezés"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Háló szintezés kész"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); @@ -561,6 +586,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X meghajtó %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y meghajtó %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Meghajtó %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); @@ -678,6 +706,9 @@ namespace Language_hu { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); @@ -705,6 +736,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Kártya"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Lemez"); } #if FAN_COUNT == 1 From a90b864a3b1bfc51c5163fcb7bbb0fbb6dedf250 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Wed, 7 Jul 2021 21:45:15 -0700 Subject: [PATCH 0359/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Einsy=20RAMBo=20?= =?UTF-8?q?FAN1=5FPIN=20(#22305)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index fb7743605f..de50657b74 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -135,9 +135,9 @@ #ifndef FAN1_PIN #ifdef MK3_FAN_PINS - #define FAN_PIN -1 + #define FAN1_PIN -1 #else - #define FAN_PIN 6 + #define FAN1_PIN 6 #endif #endif From 504c569f9c2c74c569e5b5b687024825d19acae0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jul 2021 22:46:05 -0500 Subject: [PATCH 0360/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20M20=20?= =?UTF-8?q?L?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Fix `printListing` after #22271 --- Marlin/src/sd/cardreader.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index bcb0317990..ba23421951 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -302,11 +302,13 @@ void CardReader::printListing( pathLong[lenPrependLong - 1] = '/'; } strcpy(pathLong + lenPrependLong, longFilename); - printListing(child, /*includeLongNames=*/true, path, pathLong); + printListing(child, true, path, pathLong); } else + printListing(child, false, path); + #else + printListing(child, path); #endif - printListing(child, path); else { SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); return; From de0fc0874441a077150d4d915c550987c9d0de70 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jul 2021 23:34:24 -0500 Subject: [PATCH 0361/2168] =?UTF-8?q?=F0=9F=91=BD=EF=B8=8F=20Update=20FLAS?= =?UTF-8?q?H=5FEEPROM=5FEMULATION=20include?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/eeprom_flash.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index dfeae9e9e5..68356ebee0 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -27,10 +27,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/eeprom_api.h" - -// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 -// Use EEPROM.h for compatibility, for now. -#include +#include "utility/stm32_eeprom.h" /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that From edc037355f5c2b16aa0d9cb0f14bced679776c30 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 9 Jul 2021 00:58:56 +0000 Subject: [PATCH 0362/2168] [cron] Bump distribution date (2021-07-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e63dd350c7..dffab6e600 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-08" +//#define STRING_DISTRIBUTION_DATE "2021-07-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cc1653a5b1..2ee567cc61 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 "2021-07-08" + #define STRING_DISTRIBUTION_DATE "2021-07-09" #endif /** From cc1145302b31eab07cc51870b5c37f32da1d368c Mon Sep 17 00:00:00 2001 From: Skruppy Date: Fri, 9 Jul 2021 04:55:34 +0200 Subject: [PATCH 0363/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20AVR=20DELAY=5FUS?= =?UTF-8?q?=20int=20overflow=20(#22268)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/Delay.h | 80 ++++++++++++++++++++++------------- 1 file changed, 51 insertions(+), 29 deletions(-) diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index f7e01ad25c..3174968c1b 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -97,43 +97,65 @@ void calibrate_delay_loop(); #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL)) #elif defined(__AVR__) - - #define nop() __asm__ __volatile__("nop;\n\t":::) - - FORCE_INLINE static void __delay_4cycles(uint8_t cy) { - __asm__ __volatile__( - L("1") - A("dec %[cnt]") - A("nop") - A("brne 1b") - : [cnt] "+r"(cy) // output: +r means input+output - : // input: - : "cc" // clobbers: - ); + FORCE_INLINE static void __delay_up_to_3c(uint8_t cycles) { + switch (cycles) { + case 3: + __asm__ __volatile__(A("RJMP .+0") A("NOP")); + break; + case 2: + __asm__ __volatile__(A("RJMP .+0")); + break; + case 1: + __asm__ __volatile__(A("NOP")); + break; + } } // Delay in cycles - FORCE_INLINE static void DELAY_CYCLES(uint16_t x) { - - if (__builtin_constant_p(x)) { - #define MAXNOPS 4 - - if (x <= (MAXNOPS)) { - switch (x) { case 4: nop(); case 3: nop(); case 2: nop(); case 1: nop(); } + FORCE_INLINE static void DELAY_CYCLES(uint16_t cycles) { + if (__builtin_constant_p(cycles)) { + if (cycles <= 3) { + __delay_up_to_3c(cycles); + } + else if (cycles == 4) { + __delay_up_to_3c(2); + __delay_up_to_3c(2); } else { - const uint32_t rem = (x) % (MAXNOPS); - switch (rem) { case 3: nop(); case 2: nop(); case 1: nop(); } - if ((x = (x) / (MAXNOPS))) - __delay_4cycles(x); // if need more then 4 nop loop is more optimal - } + cycles -= 1 + 4; // Compensate for the first LDI (1) and the first round (4) + __delay_up_to_3c(cycles % 4); - #undef MAXNOPS + cycles /= 4; + // The following code burns [1 + 4 * (rounds+1)] cycles + uint16_t dummy; + __asm__ __volatile__( + // "manually" load counter from constants, otherwise the compiler may optimize this part away + A("LDI %A[rounds], %[l]") // 1c + A("LDI %B[rounds], %[h]") // 1c (compensating the non branching BRCC) + L("1") + A("SBIW %[rounds], 1") // 2c + A("BRCC 1b") // 2c when branching, else 1c (end of loop) + : // Outputs ... + [rounds] "=w" (dummy) // Restrict to a wo (=) 16 bit register pair (w) + : // Inputs ... + [l] "M" (cycles%256), // Restrict to 0..255 constant (M) + [h] "M" (cycles/256) // Restrict to 0..255 constant (M) + :// Clobbers ... + "cc" // Indicate we are modifying flags like Carry (cc) + ); + } + } + else { + __asm__ __volatile__( + L("1") + A("SBIW %[cycles], 4") // 2c + A("BRCC 1b") // 2c when branching, else 1c (end of loop) + : [cycles] "+w" (cycles) // output: Restrict to a rw (+) 16 bit register pair (w) + : // input: - + : "cc" // clobbers: We are modifying flags like Carry (cc) + ); } - else if ((x >>= 2)) - __delay_4cycles(x); } - #undef nop // Delay in microseconds #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) From 2fa24a637d8b6c2ebba92d6e9a3f0eeecf581402 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jul 2021 23:02:20 -0500 Subject: [PATCH 0364/2168] Revert FLASH_EEPROM_EMULATION include --- Marlin/src/HAL/STM32/eeprom_flash.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 68356ebee0..dfeae9e9e5 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -27,7 +27,10 @@ #if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/eeprom_api.h" -#include "utility/stm32_eeprom.h" + +// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 +// Use EEPROM.h for compatibility, for now. +#include /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that From 79405ce2afd2a3d36ecb70274ec7a5355a7765c8 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Thu, 8 Jul 2021 21:48:11 -0700 Subject: [PATCH 0365/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20manage=5Fheaters?= =?UTF-8?q?=20recursion=20on=20servo=20move=20(#22313)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to e297748b22 --- Marlin/src/module/temperature.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 83187259ff..3b3c769866 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1236,6 +1236,10 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { void Temperature::manage_heater() { if (marlin_state == MF_INITIALIZING) return watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! + static bool no_reentry = false; // Prevent recursion + if (no_reentry) return; + REMEMBER(mh, no_reentry, true); + #if ENABLED(EMERGENCY_PARSER) if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); From e7e1c514022131529167d7f97044159a5cb798f6 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Sat, 10 Jul 2021 04:06:10 +0800 Subject: [PATCH 0366/2168] =?UTF-8?q?=F0=9F=90=9B=20Fixes=20for=20BTT=20Oc?= =?UTF-8?q?topus=20(#22314)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c | 2 ++ .../PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c index 2ad0bb864c..a4f8f696ee 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c @@ -232,6 +232,7 @@ const PinMap PinMap_PWM[] = { const PinMap PinMap_UART_TX[] = { // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, @@ -248,6 +249,7 @@ const PinMap PinMap_UART_TX[] = { const PinMap PinMap_UART_RX[] = { // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h index 4305c81a45..f512a311e3 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h @@ -150,7 +150,7 @@ extern "C" { // PWM resolution //#define PWM_RESOLUTION 12 -#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans +#define PWM_FREQUENCY 1000 // >= 20 Khz => inaudible noise for fans #define PWM_MAX_DUTY_CYCLE 255 // SPI Definitions From cd55b5f5cc5756dde086b6adfc575162505dca4a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jul 2021 16:02:27 -0500 Subject: [PATCH 0367/2168] =?UTF-8?q?=F0=9F=93=8C=20Require=20U8glib-HAL@~?= =?UTF-8?q?0.5.0=20(#22324)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp | 2 +- Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp | 2 +- Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp | 2 +- Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp | 2 +- Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp | 2 +- Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h | 2 +- Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp | 2 +- Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp | 2 +- .../src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 2 +- .../src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp | 2 +- Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp | 2 +- Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp | 2 +- Marlin/src/lcd/dogm/HAL_LCD_com_defines.h | 2 +- Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h | 2 +- Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_an.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_bg.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_ca.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_cz.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_da.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_de.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_el.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_en.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_es.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_eu.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_fi.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_fr.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_gl.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_hr.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_hu.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_it.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_nl.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_pl.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_pt.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_ro.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_ru.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_sk.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_test.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_tr.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_uk.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_vi.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h | 2 +- Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h | 2 +- Marlin/src/lcd/dogm/marlinui_DOGM.h | 2 +- Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp | 2 +- Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp | 2 +- Marlin/src/lcd/dogm/u8g_fontutf8.h | 2 +- Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h | 2 +- buildroot/share/fonts/genallfont.sh | 2 +- buildroot/share/fonts/uxggenpages.sh | 2 +- ini/features.ini | 2 +- 55 files changed, 55 insertions(+), 55 deletions(-) diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index cb95a48ccc..9d928e7af3 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -62,7 +62,7 @@ #include "../shared/Marduino.h" #include "../shared/Delay.h" -#include +#include uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock; volatile uint8_t *u8g_outData, *u8g_outClock; diff --git a/Marlin/src/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 index d07da15ad8..fcfcef88be 100644 --- a/Marlin/src/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 @@ -60,7 +60,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../../MarlinCore.h" diff --git a/Marlin/src/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 index d01cd4dd6b..65bfd4f4e2 100644 --- a/Marlin/src/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 @@ -62,7 +62,7 @@ #include "../../../inc/MarlinConfig.h" #include "../../shared/Delay.h" -#include +#include #include "u8g_com_HAL_DUE_sw_spi_shared.h" diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp index 890546af58..2b13c182d0 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp @@ -64,7 +64,7 @@ #include "../../shared/Marduino.h" #include "../../shared/Delay.h" -#include +#include #if ENABLED(FYSETC_MINI_12864) #define SPISEND_SW_DUE u8g_spiSend_sw_DUE_mode_3 diff --git a/Marlin/src/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 index 4fb7a6e2c3..904924793b 100644 --- a/Marlin/src/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 @@ -62,7 +62,7 @@ #include "../../../inc/MarlinConfig.h" #include "../../shared/Delay.h" -#include +#include #include "u8g_com_HAL_DUE_sw_spi_shared.h" diff --git a/Marlin/src/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 index f076c503ca..45231fd091 100644 --- a/Marlin/src/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 @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" #include "../../shared/Marduino.h" -#include +#include void u8g_SetPIOutput_DUE(u8g_t *u8g, uint8_t pin_index); void u8g_SetPILevel_DUE(u8g_t *u8g, uint8_t pin_index, uint8_t level); diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index b1eea13d57..0118f92847 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -59,7 +59,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../shared/HAL_SPI.h" #ifndef LCD_SPI_SPEED diff --git a/Marlin/src/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 index 6f7efba4ae..bf76eaf0f4 100644 --- a/Marlin/src/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 @@ -79,7 +79,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #define I2C_SLA (0x3C*2) //#define I2C_CMD_MODE 0x080 diff --git a/Marlin/src/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 index 0b0626de79..ce7b338019 100644 --- a/Marlin/src/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 @@ -59,7 +59,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "../../shared/HAL_SPI.h" #include "../../shared/Delay.h" diff --git a/Marlin/src/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 index 61211d9d88..039fa6769b 100644 --- a/Marlin/src/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 @@ -59,7 +59,7 @@ #if ENABLED(U8GLIB_ST7920) -#include +#include #include #include "../../shared/Delay.h" #include "../../shared/HAL_SPI.h" diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index 7f38ec54af..3308d03e79 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -71,7 +71,7 @@ #include #include -#include +#include 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 ) { diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 784a80c29f..f1cd6b3730 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -22,7 +22,7 @@ #if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) -#include +#include #include "../../shared/HAL_SPI.h" #ifndef LCD_SPI_SPEED diff --git a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h index 8a707ab41a..98a8f0a98a 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -23,7 +23,7 @@ // Use this file to select the com driver for device drivers that are NOT in the U8G library -#include +#include #ifndef U8G_HAL_LINKS // Defined by LPC1768/9 environments in platform.ini diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h index cd9cb3cdc9..524ff18778 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h @@ -32,7 +32,7 @@ X Font ascent = 6 descent=-2 Max Font ascent = 7 descent=-2 */ -#include +#include const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_6x9") = { 0x00,0x06,0x09,0x00,0xFE,0x06,0x02,0x0F,0x03,0x84,0x01,0xFF,0xFE,0x07,0xFE,0x06, 0xFE,0x05,0x07,0x07,0x00,0x00,0x00,0x40,0xF0,0xC8,0x88,0x98,0x78,0x10,0x05,0x07, diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index b4b615da4d..0a7ece8601 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -16,7 +16,7 @@ * along with this program. If not, see . * */ -#include +#include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_an.h b/Marlin/src/lcd/dogm/fontdata/langdata_an.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_an.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_an.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h index c506f87933..8d5d7e8321 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_8_144_149[96] U8G_FONT_SECTION("fontpage_8_144_149") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0x95,0x00,0x07,0xFF,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h index 754459d9af..e6894a8d30 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_140_141[47] U8G_FONT_SECTION("fontpage_2_140_141") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8D,0x00,0x0A,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_da.h b/Marlin/src/lcd/dogm/fontdata/langdata_da.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_da.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_da.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_de.h b/Marlin/src/lcd/dogm/fontdata/langdata_de.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_de.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_de.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el.h b/Marlin/src/lcd/dogm/fontdata/langdata_el.h index 4b545f2284..f949f28ca6 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h index 4b545f2284..f949f28ca6 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_en.h b/Marlin/src/lcd/dogm/fontdata/langdata_en.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_en.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_en.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_es.h b/Marlin/src/lcd/dogm/fontdata/langdata_es.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_es.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_es.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h index cdb2cc7d1a..e5430834ad 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_135_135[31] U8G_FONT_SECTION("fontpage_2_135_135") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h index 8c15a3890a..eb43cbea0f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_241_241[31] U8G_FONT_SECTION("fontpage_2_241_241") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xF1,0xF1,0x00,0x08,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_it.h b/Marlin/src/lcd/dogm/fontdata/langdata_it.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_it.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_it.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h index 01316d4c13..4d0ec6ab4f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_97_161_164[65] U8G_FONT_SECTION("fontpage_97_161_164") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA1,0xA4,0x00,0x07,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h index 6b48434a6f..23c84d6573 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_344_240_240[34] U8G_FONT_SECTION("fontpage_344_240_240") = { 0x00,0x0B,0x0D,0x00,0xFD,0x00,0x00,0x00,0x00,0x00,0xF0,0xF0,0x00,0x09,0xFE,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h index 926f075295..11163d9177 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_132_133[45] U8G_FONT_SECTION("fontpage_2_132_133") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x07,0xFE,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h index ffda82764f..7989690f1f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h index 4edd6e74e3..617119dde3 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_8_144_168[348] U8G_FONT_SECTION("fontpage_8_144_168") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0xA8,0x00,0x0A,0xFE,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h index 491006e05a..152d74bbda 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_140_143[79] U8G_FONT_SECTION("fontpage_2_140_143") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8F,0x00,0x0A,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_test.h b/Marlin/src/lcd/dogm/fontdata/langdata_test.h index c397d8b4b9..ca6e369eb1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_test.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_test.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_8_128_255[1677] U8G_FONT_SECTION("fontpage_8_128_255") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x80,0xFF,0x00,0x0A,0xFE,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h index a4068e10d0..aeb1124cf2 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_158_159[49] U8G_FONT_SECTION("fontpage_2_158_159") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9E,0x9F,0x00,0x0A,0xFE,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h index 47ec93992f..fe409d4e3c 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_8_134_134[30] U8G_FONT_SECTION("fontpage_8_134_134") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h index a8a0c5c121..998ae44af1 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_2_131_131[31] U8G_FONT_SECTION("fontpage_2_131_131") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h index 491d480a01..8d74ba4414 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9D,0x9D,0x00,0x07,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h index 8eee544ec8..51344936be 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h @@ -3,7 +3,7 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBF,0xBF,0x00,0x05,0x00,0x00, diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.h b/Marlin/src/lcd/dogm/marlinui_DOGM.h index e3ceb63f96..328b69b93b 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.h +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.h @@ -27,7 +27,7 @@ #include "../../inc/MarlinConfigPre.h" -#include +#include #include "HAL_LCD_class_defines.h" //#define ALTERNATIVE_LCD diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp index 7b4c470afe..2a21bd67ca 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp @@ -24,7 +24,7 @@ #if HAS_MARLINUI_U8GLIB #include "HAL_LCD_com_defines.h" -#include +#include #define WIDTH 128 #define HEIGHT 64 diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp index 84c10dbb4d..fda090338c 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -57,7 +57,7 @@ #if HAS_MARLINUI_U8GLIB -#include +#include #include "HAL_LCD_com_defines.h" #define WIDTH 128 diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.h b/Marlin/src/lcd/dogm/u8g_fontutf8.h index 34e365cf95..d7ea618de0 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.h +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.h @@ -8,7 +8,7 @@ */ #pragma once -#include +#include #include "../fontutils.h" // the macro to indicate a UTF-8 string diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h index e8a48299cb..446bfcfd42 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h @@ -35,7 +35,7 @@ #define PAGE_HEIGHT 16 // 256 byte framebuffer //#define PAGE_HEIGHT 32 // 512 byte framebuffer -#include +#include void ST7920_SWSPI_SND_8BIT(uint8_t val); diff --git a/buildroot/share/fonts/genallfont.sh b/buildroot/share/fonts/genallfont.sh index 0a66990212..d5cad54361 100755 --- a/buildroot/share/fonts/genallfont.sh +++ b/buildroot/share/fonts/genallfont.sh @@ -119,7 +119,7 @@ if [ 1 = 1 ]; then * along with this program. If not, see . * */ -#include +#include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH diff --git a/buildroot/share/fonts/uxggenpages.sh b/buildroot/share/fonts/uxggenpages.sh index a99fd99024..047d3ae661 100755 --- a/buildroot/share/fonts/uxggenpages.sh +++ b/buildroot/share/fonts/uxggenpages.sh @@ -169,7 +169,7 @@ cat <fontutf8-data.h * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#include $TMPA #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {$TMPB}; diff --git a/ini/features.ini b/ini/features.ini index 5a1b48804d..2d9d7ab063 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -36,7 +36,7 @@ USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 HAS_WIRED_LCD = src_filter=+ HAS_MARLINUI_HD44780 = src_filter=+ -HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.5 +HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.5.0 src_filter=+ HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + HAS_FSMC_TFT = src_filter=+ + From 6cbd21d0d46cc366e8b0ec84cc9a531485adf465 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 9 Jul 2021 23:07:55 +0200 Subject: [PATCH 0368/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20French=20lang?= =?UTF-8?q?uage=20(#22323)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_fr.h | 70 ++++++++++++++++++++++++--- 1 file changed, 64 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 5dbec298d4..78a649f626 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -60,6 +60,9 @@ namespace Language_fr { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origine X auto"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origine Z auto"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Origine ") LCD_STR_I _UxGT(" auto"); + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Origine ") LCD_STR_J _UxGT(" auto"); + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Origine ") LCD_STR_K _UxGT(" auto"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Align. Z auto"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origine XYZ..."); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Clic pour commencer"); @@ -67,6 +70,12 @@ namespace Language_fr { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Mise à niveau OK!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Hauteur lissée"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Régl. décal origine"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Régler origine"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assistant Molettes"); @@ -228,14 +237,21 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Déplacer X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Déplacer Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Déplacer Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudeur"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudeur *"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Déplacer ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Déplacer ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Déplacer ") LCD_STR_K; + PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Déplacer %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Déplacer 0.001\""); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Déplacer 0.01\""); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Déplacer 0.1\""); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Déplacer 1\""); PROGMEM Language_Str MSG_SPEED = _UxGT("Vitesse"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Lit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Buse"); @@ -270,11 +286,31 @@ namespace Language_fr { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT(" jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT(" jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT(" jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT(" jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT(" jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT(" jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve jerk"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Vélocité"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vit. Max ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vit. Max ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vit. Max ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vit. Max ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vit. Max ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vit. Max ") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vit. Max ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vit. Max *"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vit. Min"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vmin course"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accélération"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Accél. ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Accél. ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Accél. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max Accél. ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max Accél. ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max Accél. ") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Accél. ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Accél. *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acc.rétraction"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acc.course"); PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); @@ -283,6 +319,9 @@ namespace Language_fr { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pas/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pas/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pas/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pas/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Température"); @@ -402,6 +441,12 @@ namespace Language_fr { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Décalage X"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Décalage Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Décalage Z"); + PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); + PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); @@ -444,6 +489,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Niveau bilinéaire"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Niveau lit unifié"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Niveau par grille"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Niveau terminé"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Stats. imprimante"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Infos carte"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistances"); @@ -476,10 +522,13 @@ namespace Language_fr { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alim."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver " AXIS4_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver " AXIS5_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver " AXIS6_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); @@ -576,6 +625,12 @@ namespace Language_fr { PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop activé"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Réinit."); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dans:"); + 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Lissage"); @@ -601,4 +656,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Coin bas droit"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibration terminée"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Échec de l'étalonnage"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("Carte SD"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("Clé USB"); } From 26bfc267977ddc444513c793c18f76847e23310e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jul 2021 17:09:58 -0500 Subject: [PATCH 0369/2168] =?UTF-8?q?=F0=9F=8E=A8=20Check=20flags=20withou?= =?UTF-8?q?t=20ENABLED?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/feature/dac/dac_mcp4728.cpp | 2 +- Marlin/src/feature/dac/stepper_dac.cpp | 2 +- Marlin/src/feature/joystick.h | 6 +-- Marlin/src/feature/powerloss.h | 12 +++--- Marlin/src/feature/tmc_util.h | 2 +- Marlin/src/gcode/calibrate/G33.cpp | 2 +- Marlin/src/gcode/calibrate/G34.cpp | 8 ++-- .../src/gcode/feature/digipot/M907-M910.cpp | 6 +-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 42 +++++++++---------- Marlin/src/gcode/queue.h | 2 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 2 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 4 +- Marlin/src/lcd/dwin/e3v2/dwin.h | 12 +++--- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 2 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 4 +- .../generic/advanced_settings_menu.cpp | 2 +- .../generic/leveling_menu.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 16 +++---- Marlin/src/lcd/marlinui.h | 10 ++--- Marlin/src/lcd/menu/menu_advanced.cpp | 4 +- Marlin/src/module/settings.cpp | 4 +- Marlin/src/module/temperature.h | 14 +++---- Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 2 +- Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h | 2 +- .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 2 +- Marlin/src/sd/cardreader.cpp | 2 +- 31 files changed, 90 insertions(+), 90 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index dc9fbb2ba7..18965bcbb9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -135,7 +135,7 @@ #include "module/servo.h" #endif -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "feature/dac/stepper_dac.h" #endif @@ -1355,7 +1355,7 @@ void setup() { SETUP_RUN(digipot_i2c.init()); #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC SETUP_RUN(stepper_dac.init()); #endif diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index e144390c8d..e1ed013cf2 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -307,7 +307,7 @@ void unified_bed_leveling::G29() { const uint8_t p_val = parser.byteval('P'); const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); - #if ENABLED(HAS_MULTI_HOTEND) + #if HAS_MULTI_HOTEND const uint8_t old_tool_index = active_extruder; #endif diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index ddbaced086..1278d1bec8 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -32,7 +32,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "dac_mcp4728.h" diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 3abaece443..6d03808b82 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "stepper_dac.h" #include "../../MarlinCore.h" // for SP_X_LBL... diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index d1c4fbd314..91bf6bdc00 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -32,13 +32,13 @@ class Joystick { friend class Temperature; private: - #if ENABLED(HAS_JOY_ADC_X) + #if HAS_JOY_ADC_X static temp_info_t x; #endif - #if ENABLED(HAS_JOY_ADC_Y) + #if HAS_JOY_ADC_Y static temp_info_t y; #endif - #if ENABLED(HAS_JOY_ADC_Z) + #if HAS_JOY_ADC_Z static temp_info_t z; #endif public: diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 55180e5390..d3ecc6c9cc 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -64,13 +64,13 @@ typedef struct { Repeat stored_repeat; #endif - #if ENABLED(HAS_HOME_OFFSET) + #if HAS_HOME_OFFSET xyz_pos_t home_offset; #endif - #if ENABLED(HAS_POSITION_SHIFT) + #if HAS_POSITION_SHIFT xyz_pos_t position_shift; #endif - #if ENABLED(HAS_MULTI_EXTRUDER) + #if HAS_MULTI_EXTRUDER uint8_t active_extruder; #endif @@ -78,13 +78,13 @@ typedef struct { float filament_size[EXTRUDERS]; #endif - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND celsius_t target_temperature[HOTENDS]; #endif - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED celsius_t target_temperature_bed; #endif - #if ENABLED(HAS_FAN) + #if HAS_FAN uint8_t fan_speed[FAN_COUNT]; #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 741b840ec7..4753f78d91 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -363,7 +363,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); struct motion_state_t { xy_ulong_t acceleration; - #if ENABLED(HAS_CLASSIC_JERK) + #if HAS_CLASSIC_JERK xy_float_t jerk_state; #endif }; diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 14ac53aeba..0737c91668 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -63,7 +63,7 @@ enum CalEnum : char { // the 7 main calibration points - #define LOOP_CAL_RAD(VAR) LOOP_CAL_PT(VAR, __A, _7P_STEP) #define LOOP_CAL_ACT(VAR, _4P, _OP) LOOP_CAL_PT(VAR, _OP ? _AB : __A, _4P ? _4P_STEP : _7P_STEP) -#if ENABLED(HAS_MULTI_HOTEND) +#if HAS_MULTI_HOTEND const uint8_t old_tool_index = active_extruder; #endif diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 956960866d..f335a12311 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -81,11 +81,11 @@ void GcodeSuite::G34() { const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); const uint32_t previous_current = stepper.motor_current_setting[Z_AXIS]; stepper.set_digipot_current(1, target_current); - #elif ENABLED(HAS_MOTOR_CURRENT_DAC) + #elif HAS_MOTOR_CURRENT_DAC const float target_current = parser.floatval('S', GANTRY_CALIBRATION_CURRENT); const float previous_current = dac_amps(Z_AXIS, target_current); stepper_dac.set_current_value(Z_AXIS, target_current); - #elif ENABLED(HAS_MOTOR_CURRENT_I2C) + #elif HAS_MOTOR_CURRENT_I2C const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT); previous_current = dac_amps(Z_AXIS); digipot_i2c.set_current(Z_AXIS, target_current) @@ -127,9 +127,9 @@ void GcodeSuite::G34() { stepper.set_digipot_current(Z_AXIS, previous_current); #elif HAS_MOTOR_CURRENT_PWM stepper.set_digipot_current(1, previous_current); - #elif ENABLED(HAS_MOTOR_CURRENT_DAC) + #elif HAS_MOTOR_CURRENT_DAC stepper_dac.set_current_value(Z_AXIS, previous_current); - #elif ENABLED(HAS_MOTOR_CURRENT_I2C) + #elif HAS_MOTOR_CURRENT_I2C digipot_i2c.set_current(Z_AXIS, previous_current) #elif HAS_TRINAMIC_CONFIG #if AXIS_IS_TMC(Z) diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index 118ad21564..bd741f8a64 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -34,7 +34,7 @@ #include "../../../feature/digipot/digipot.h" #endif -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "../../../feature/dac/stepper_dac.h" #endif @@ -73,7 +73,7 @@ void GcodeSuite::M907() { #endif #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC if (parser.seenval('S')) { const float dac_percent = parser.value_float(); LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent); @@ -92,7 +92,7 @@ void GcodeSuite::M907() { TERN_(HAS_MOTOR_CURRENT_DAC, stepper_dac.set_current_value(parser.byteval('P', -1), parser.ushortval('S', 0))); } - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC void GcodeSuite::M909() { stepper_dac.print_values(); } void GcodeSuite::M910() { stepper_dac.commit_eeprom(); } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index ac3b5010b9..0f66c4035e 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -908,7 +908,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) case 908: M908(); break; // M908: Control digital trimpot directly. - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC case 909: M909(); break; // M909: Print digipot/DAC current value case 910: M910(); break; // M910: Commit digipot/DAC value to external EEPROM #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 752a3da9dc..6f889e8558 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -524,7 +524,7 @@ private: static void G38(const int8_t subcode); #endif - #if ENABLED(HAS_MESH) + #if HAS_MESH static void G42(); #endif @@ -557,7 +557,7 @@ private: static void G425(); #endif - #if ENABLED(HAS_RESUME_CONTINUE) + #if HAS_RESUME_CONTINUE static void M0_M1(); #endif @@ -612,7 +612,7 @@ private: static void M31(); #if ENABLED(SDSUPPORT) - #if ENABLED(HAS_MEDIA_SUBCALLS) + #if HAS_MEDIA_SUBCALLS static void M32(); #endif #if ENABLED(LONG_FILENAME_HOST_SUPPORT) @@ -743,7 +743,7 @@ private: static void M149(); #endif - #if ENABLED(HAS_COLOR_LEDS) + #if HAS_COLOR_LEDS static void M150(); #endif @@ -777,7 +777,7 @@ private: static void M204(); static void M205(); - #if ENABLED(HAS_M206_COMMAND) + #if HAS_M206_COMMAND static void M206(); #endif @@ -791,11 +791,11 @@ private: static void M211(); - #if ENABLED(HAS_MULTI_EXTRUDER) + #if HAS_MULTI_EXTRUDER static void M217(); #endif - #if ENABLED(HAS_HOTEND_OFFSET) + #if HAS_HOTEND_OFFSET static void M218(); #endif @@ -813,7 +813,7 @@ private: static void M240(); #endif - #if ENABLED(HAS_LCD_CONTRAST) + #if HAS_LCD_CONTRAST static void M250(); #endif @@ -833,7 +833,7 @@ private: static void M290(); #endif - #if ENABLED(HAS_BUZZER) + #if HAS_BUZZER static void M300(); #endif @@ -845,7 +845,7 @@ private: static void M302(); #endif - #if ENABLED(HAS_PID_HEATING) + #if HAS_PID_HEATING static void M303(); #endif @@ -853,7 +853,7 @@ private: static void M304(); #endif - #if ENABLED(HAS_USER_THERMISTORS) + #if HAS_USER_THERMISTORS static void M305(); #endif @@ -894,7 +894,7 @@ private: static void M402(); #endif - #if ENABLED(HAS_PRUSA_MMU2) + #if HAS_PRUSA_MMU2 static void M403(); #endif @@ -905,11 +905,11 @@ private: static void M407(); #endif - #if ENABLED(HAS_FILAMENT_SENSOR) + #if HAS_FILAMENT_SENSOR static void M412(); #endif - #if ENABLED(HAS_MULTI_LANGUAGE) + #if HAS_MULTI_LANGUAGE static void M414(); #endif @@ -922,11 +922,11 @@ private: static void M425(); #endif - #if ENABLED(HAS_M206_COMMAND) + #if HAS_M206_COMMAND static void M428(); #endif - #if ENABLED(HAS_POWER_MONITOR) + #if HAS_POWER_MONITOR static void M430(); #endif @@ -977,11 +977,11 @@ private: static void M603(); #endif - #if ENABLED(HAS_DUPLICATION_MODE) + #if HAS_DUPLICATION_MODE static void M605(); #endif - #if ENABLED(IS_KINEMATIC) + #if IS_KINEMATIC static void M665(); #endif @@ -1006,7 +1006,7 @@ private: static void M810_819(); #endif - #if ENABLED(HAS_BED_PROBE) + #if HAS_BED_PROBE static void M851(); #endif @@ -1039,7 +1039,7 @@ private: #if HAS_TRINAMIC_CONFIG static void M122(); static void M906(); - #if ENABLED(HAS_STEALTHCHOP) + #if HAS_STEALTHCHOP static void M569(); #endif #if ENABLED(MONITOR_DRIVER_STATUS) @@ -1066,7 +1066,7 @@ private: static void M907(); #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) static void M908(); - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC static void M909(); static void M910(); #endif diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index ea99ce7a2d..3474a402c3 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -59,7 +59,7 @@ public: struct CommandLine { char buffer[MAX_CMD_SIZE]; //!< The command buffer bool skip_ok; //!< Skip sending ok when command is processed? - #if ENABLED(HAS_MULTI_SERIAL) + #if HAS_MULTI_SERIAL serial_index_t port; //!< Serial port the command was received on #endif }; diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 2f8b5f67e2..c76857b6bb 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -536,7 +536,7 @@ void ST7920_Lite_Status_Screen::draw_heat_icon(const bool whichIcon, const bool static struct { bool E1_show_target : 1; bool E2_show_target : 1; - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED bool bed_show_target : 1; #endif } display_state = { diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 777b56ac0e..9aea68dfcb 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -182,10 +182,10 @@ static uint8_t _card_percent = 0; static uint16_t _remain_time = 0; #if ENABLED(PAUSE_HEAT) - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND uint16_t resume_hotend_temp = 0; #endif - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED uint16_t resume_bed_temp = 0; #endif #endif diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index ad210db27d..0272748cd5 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -255,13 +255,13 @@ extern char print_filename[16]; extern millis_t dwin_heat_time; typedef struct { - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND celsius_t E_Temp = 0; #endif - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED celsius_t Bed_Temp = 0; #endif - #if ENABLED(HAS_FAN) + #if HAS_FAN int16_t Fan_speed = 0; #endif int16_t print_speed = 100; @@ -344,13 +344,13 @@ void HMI_Move_E(); void HMI_Zoffset(); -#if ENABLED(HAS_HOTEND) +#if HAS_HOTEND void HMI_ETemp(); #endif -#if ENABLED(HAS_HEATED_BED) +#if HAS_HEATED_BED void HMI_BedTemp(); #endif -#if ENABLED(HAS_FAN) +#if HAS_FAN void HMI_FanSpeed(); #endif diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 2e8df757eb..57ecc4bb65 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -622,7 +622,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr DEBUG_ECHOLNPGM("HandlePreheat"); uint8_t e_temp = 0; - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED uint8_t bed_temp = 0; #endif const uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 7d8581c9f3..c60d6e8bc4 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -35,7 +35,7 @@ #include "../../ui_api.h" #include "../../../marlinui.h" -#if ENABLED(HAS_STEALTHCHOP) +#if HAS_STEALTHCHOP #include "../../../../module/stepper/trinamic.h" #endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index aabe6fc531..0ee3828387 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -37,7 +37,7 @@ #include "../../../../gcode/gcode.h" -#if ENABLED(HAS_STEALTHCHOP) +#if HAS_STEALTHCHOP #include "../../../../module/stepper/trinamic.h" #include "../../../../module/stepper/indirection.h" #endif @@ -396,7 +396,7 @@ void DGUSScreenHandler::Z_offset_select(DGUS_VP_Variable &var, void *val_ptr) { void DGUSScreenHandler::GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { - #if ENABLED(HAS_BED_PROBE) + #if HAS_BED_PROBE int32_t value = swap32(*(int32_t *)val_ptr); float Offset = value / 100.0f; DEBUG_ECHOLNPAIR_F("\nget int6 offset >> ", value, 6); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index 58a7112d01..503abbdb05 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -122,7 +122,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(ZOffsetScreen); break; #endif case 3: GOTO_SCREEN(StepsScreen); break; - #if ENABLED(HAS_MULTI_HOTEND) + #if HAS_MULTI_HOTEND case 4: GOTO_SCREEN(NozzleOffsetScreen); break; #endif case 5: GOTO_SCREEN(MaxVelocityScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 797bb37996..acbc179891 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -106,7 +106,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) case 2: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; #endif - #if ENABLED(HAS_BED_PROBE) + #if HAS_BED_PROBE case 3: #ifndef BED_LEVELING_COMMANDS #define BED_LEVELING_COMMANDS "G29" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index c9172d5887..e3efb14c28 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -49,7 +49,7 @@ static lv_obj_t *labelPause, *labelStop, *labelOperat; static lv_obj_t *bar1, *bar1ValueText; static lv_obj_t *buttonPause, *buttonOperat, *buttonStop, *buttonExt1, *buttonExt2, *buttonBedstate, *buttonFanstate, *buttonZpos; -#if ENABLED(HAS_MULTI_EXTRUDER) +#if HAS_MULTI_EXTRUDER static lv_obj_t *labelExt2; #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 00b785e680..df73527812 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -178,10 +178,10 @@ namespace ExtUI { #if HAS_HEATED_BED case BED: thermalManager.reset_bed_idle_timer(); return; #endif - #if ENABLED(HAS_HEATED_CHAMBER) + #if HAS_HEATED_CHAMBER case CHAMBER: return; // Chamber has no idle timer #endif - #if ENABLED(HAS_COOLER) + #if HAS_COOLER case COOLER: return; // Cooler has no idle timer #endif default: @@ -241,10 +241,10 @@ namespace ExtUI { bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED case BED: return thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out; #endif - #if ENABLED(HAS_HEATED_CHAMBER) + #if HAS_HEATED_CHAMBER case CHAMBER: return false; // Chamber has no idle timer #endif default: @@ -264,10 +264,10 @@ namespace ExtUI { celsius_float_t getActualTemp_celsius(const heater_t heater) { switch (heater) { - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degBed()); #endif - #if ENABLED(HAS_HEATED_CHAMBER) + #if HAS_HEATED_CHAMBER case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degChamber()); #endif default: return GET_TEMP_ADJUSTMENT(thermalManager.degHotend(heater - H0)); @@ -280,10 +280,10 @@ namespace ExtUI { celsius_float_t getTargetTemp_celsius(const heater_t heater) { switch (heater) { - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED case BED: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetBed()); #endif - #if ENABLED(HAS_HEATED_CHAMBER) + #if HAS_HEATED_CHAMBER case CHAMBER: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetChamber()); #endif default: return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(heater - H0)); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 7531fae674..56ef741b54 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -111,13 +111,13 @@ #if PREHEAT_COUNT typedef struct { - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND celsius_t hotend_temp; #endif - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED celsius_t bed_temp; #endif - #if ENABLED(HAS_FAN) + #if HAS_FAN uint16_t fan_speed; #endif } preheat_t; @@ -135,12 +135,12 @@ static int8_t constexpr e_index = 0; #endif static millis_t start_time; - #if ENABLED(IS_KINEMATIC) + #if IS_KINEMATIC static xyze_pos_t all_axes_destination; #endif public: static float menu_scale; - #if ENABLED(IS_KINEMATIC) + #if IS_KINEMATIC static float offset; #endif template diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index a6719f1847..4ae38edf24 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -58,7 +58,7 @@ void menu_tmc(); void menu_backlash(); -#if ENABLED(HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_DAC #include "../../feature/dac/stepper_dac.h" @@ -590,7 +590,7 @@ void menu_advanced_settings() { SUBMENU(MSG_BACKLASH, menu_backlash); #endif - #if ENABLED(HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_DAC SUBMENU(MSG_DRIVE_STRENGTH, menu_dac); #endif #if HAS_MOTOR_CURRENT_PWM diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 27ba7cbc75..8c3e9fb75c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3818,10 +3818,10 @@ void MarlinSettings::reset() { SERIAL_CHAR(' ', 'B'); // B (maps to E1 by default) SERIAL_ECHOLN(stepper.motor_current_setting[4]); #endif - #elif ENABLED(HAS_MOTOR_CURRENT_I2C) // i2c-based has any number of values + #elif HAS_MOTOR_CURRENT_I2C // i2c-based has any number of values // Values sent over i2c are not stored. // Indexes map directly to drivers, not axes. - #elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z (I J K) E + #elif HAS_MOTOR_CURRENT_DAC // DAC-based has 4 values, for X Y Z (I J K) E // Values sent over i2c are not stored. Uses indirect mapping. #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 26c1dca8af..c8d085133c 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -340,16 +340,16 @@ class Temperature { static const celsius_t hotend_maxtemp[HOTENDS]; static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } #endif - #if ENABLED(HAS_HEATED_BED) + #if HAS_HEATED_BED static bed_info_t temp_bed; #endif - #if ENABLED(HAS_TEMP_PROBE) + #if HAS_TEMP_PROBE static probe_info_t temp_probe; #endif - #if ENABLED(HAS_TEMP_CHAMBER) + #if HAS_TEMP_CHAMBER static chamber_info_t temp_chamber; #endif - #if ENABLED(HAS_TEMP_COOLER) + #if HAS_TEMP_COOLER static cooler_info_t temp_cooler; #endif #if HAS_TEMP_REDUNDANT @@ -450,7 +450,7 @@ class Temperature { static lpq_ptr_t lpq_ptr; #endif - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND static temp_range_t temp_range[HOTENDS]; #endif @@ -486,7 +486,7 @@ class Temperature { static millis_t preheat_end_time[HOTENDS]; #endif - #if ENABLED(HAS_AUTO_FAN) + #if HAS_AUTO_FAN static millis_t next_auto_fan_check_ms; #endif @@ -920,7 +920,7 @@ class Temperature { static void checkExtruderAutoFans(); - #if ENABLED(HAS_HOTEND) + #if HAS_HOTEND static float get_pid_output_hotend(const uint8_t e); #endif #if ENABLED(PIDTEMPBED) diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index 07e46acfe7..8dc93c833b 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -51,7 +51,7 @@ // // DAC steppers // -#define HAS_MOTOR_CURRENT_DAC +#define HAS_MOTOR_CURRENT_DAC 1 #define DAC_STEPPER_ORDER { 0, 1, 2, 3 } diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h index 1428de31a2..5a6bba3c08 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h @@ -34,7 +34,7 @@ // // I2C based DAC like on the Printrboard REVF -#define HAS_MOTOR_CURRENT_DAC +#define HAS_MOTOR_CURRENT_DAC 1 // Channels available for DAC, For Rigidboard there are 4 #define DAC_STEPPER_ORDER { 0, 1, 2, 3 } diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index 0e6842125e..539a3bb8f3 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -141,7 +141,7 @@ #endif // NO_EXTRUDRBOARD // Enable control of stepper motor currents with the I2C based MCP4728 DAC used on Printrboard REVF -#define HAS_MOTOR_CURRENT_DAC +#define HAS_MOTOR_CURRENT_DAC 1 // Set default drive strength percents if not already defined - X, Y, Z, E axis #ifndef DAC_MOTOR_CURRENT_DEFAULT diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index ba23421951..90c39feaf8 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1153,7 +1153,7 @@ void CardReader::cdroot() { #if DISABLED(SDSORT_USES_RAM) selectFileByIndex(o1); // Pre-fetch the first entry and save it strcpy(name1, longest_filename()); // so the loop only needs one fetch - #if ENABLED(HAS_FOLDER_SORTING) + #if HAS_FOLDER_SORTING bool dir1 = flag.filenameIsDir; #endif #endif From 938d86d1c5512a39ac2527b497a0875d742d17e9 Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Fri, 9 Jul 2021 17:59:36 -0500 Subject: [PATCH 0370/2168] =?UTF-8?q?=E2=9C=A8=20MKS=20MINI12864=20V3=20fo?= =?UTF-8?q?r=20MKS=20Robin=20Nano=20V2/3=20(#22285)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 5 +++ Marlin/src/HAL/STM32F1/inc/SanityCheck.h | 2 +- Marlin/src/inc/Conditionals_LCD.h | 5 +++ Marlin/src/inc/Conditionals_post.h | 4 ++ .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 11 ++++++ .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 39 ++++++++++++++++--- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 15 ++++++- 7 files changed, 73 insertions(+), 8 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index e9a49b6056..5a38ddda0f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2414,6 +2414,11 @@ // //#define MKS_MINI_12864 +// +// MKS MINI12864 V3 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// +//#define MKS_MINI_12864_V3 + // // MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout. // https://www.aliexpress.com/item/33018110072.html diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index 89ee66d646..2846155c35 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -39,7 +39,7 @@ #error "SERIAL_STATS_DROPPED_RX is not supported on the STM32F1 platform." #endif -#if ENABLED(NEOPIXEL_LED) +#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3) #error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HAL/STM32F1. Comment out this line to proceed at your own risk!" #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a9ad5018e8..6cf0b82241 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -31,6 +31,11 @@ #define MKS_MINI_12864 #endif +// MKS_MINI_12864_V3 is simply identical to FYSETC_MINI_12864_2_1 +#if ENABLED(MKS_MINI_12864_V3) + #define FYSETC_MINI_12864_2_1 +#endif + /** * General Flags that may be set below by specific LCDs * diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 2f5af2b700..f4bb862db9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -369,6 +369,10 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 195 +#elif ENABLED(MKS_MINI_12864_V3) + #define _LCD_CONTRAST_MIN 255 + #define _LCD_CONTRAST_INIT 255 + #define _LCD_CONTRAST_MAX 255 #elif ENABLED(FYSETC_MINI_12864) #define _LCD_CONTRAST_INIT 220 #elif ENABLED(ULTI_CONTROLLER) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index b482065666..127dfb7c7a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -155,6 +155,17 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 + #elif ENABLED(MKS_MINI_12864_V3) + #define ENABLE_SPI3 + #define DOGLCD_CS PA4 + #define DOGLCD_A0 PA5 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PA6 + #define NEOPIXEL_PIN PA7 + #define DOGLCD_MOSI PB15 + #define DOGLCD_SCK PB13 + #else #define LCD_PINS_D4 PA6 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 3a203aab49..3c3e604f28 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -231,10 +231,19 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT -#define SDIO_CLOCK 4500000 // 4.5 MHz -#define SD_DETECT_PIN PD12 -#define ONBOARD_SD_CS_PIN PC11 +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT + #define SDIO_CLOCK 4500000 // 4.5 MHz + #define SD_DETECT_PIN PD12 + #define ONBOARD_SD_CS_PIN PC11 +#elif SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 +#endif // // LCD / Controller @@ -291,8 +300,13 @@ #endif #if HAS_WIRED_LCD && !HAS_SPI_TFT - - // NON TFT Displays + #define BEEPER_PIN PC5 + #define BTN_ENC PE13 + #define LCD_PINS_ENABLE PD13 + #define LCD_PINS_RS PC6 + #define BTN_EN1 PE8 + #define BTN_EN2 PE11 + #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) @@ -318,6 +332,19 @@ #ifndef BEEPER_PIN #define BEEPER_PIN -1 #endif + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif #else // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 9ae2870a40..589fcf24df 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -243,7 +243,7 @@ // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) @@ -340,6 +340,19 @@ // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B //#undef SHOW_BOOTSCREEN + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif #else // !MKS_MINI_12864 From 3ba5eda0b28498a3e557669496e0d6ffec875876 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 9 Jul 2021 19:24:14 -0400 Subject: [PATCH 0371/2168] =?UTF-8?q?=F0=9F=93=BA=20ExtUI=20pause=20state?= =?UTF-8?q?=20response=20(#22164)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.h | 1 + Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 15 +++++++++++-- Marlin/src/lcd/extui/ui_api.h | 36 ++++++++++++++++++------------ Marlin/src/lcd/marlinui.cpp | 34 ++++++++++++++++++++++++++++ Marlin/src/lcd/marlinui.h | 4 ++-- 6 files changed, 73 insertions(+), 19 deletions(-) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6f889e8558..6b9d0eb47d 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -424,6 +424,7 @@ public: static uint8_t host_keepalive_interval; static void host_keepalive(); + static inline bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; } #define KEEPALIVE_STATE(N) REMEMBER(_KA_, gcode.busy_state, gcode.N) #else diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index f4bb862db9..dde5edb522 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -3266,7 +3266,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if HAS_LCD_MENU || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index df73527812..7173790262 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -102,6 +102,10 @@ #include "../../feature/host_actions.h" #endif +#if M600_PURGE_MORE_RESUMABLE + #include "../../feature/pause.h" +#endif + namespace ExtUI { static struct { uint8_t printer_killed : 1; @@ -381,7 +385,8 @@ namespace ExtUI { return !thermalManager.tooColdToExtrude(extruder - E0); } - GcodeSuite::MarlinBusyState getMachineBusyState() { return TERN0(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state); } + GcodeSuite::MarlinBusyState getHostKeepaliveState() { return TERN0(HOST_KEEPALIVE_FEATURE, gcode.busy_state); } + bool getHostKeepaliveIsPaused() { return TERN0(HOST_KEEPALIVE_FEATURE, gcode.host_keepalive_is_paused()); } #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } @@ -1025,9 +1030,15 @@ namespace ExtUI { TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); } - bool awaitingUserConfirm() { return TERN0(HAS_RESUME_CONTINUE, wait_for_user); } + bool awaitingUserConfirm() { + return TERN0(HAS_RESUME_CONTINUE, wait_for_user) || getHostKeepaliveIsPaused(); + } void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } + #if M600_PURGE_MORE_RESUMABLE + void setPauseMenuResponse(PauseMenuResponse response) { pause_menu_response = response; } + #endif + void printFile(const char *filename) { TERN(SDSUPPORT, card.openAndPrintFile(filename), UNUSED(filename)); } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 5efd74b8df..faa6c8f41a 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -45,6 +45,9 @@ #include "../../inc/MarlinConfig.h" #include "../marlinui.h" #include "../../gcode/gcode.h" +#if M600_PURGE_MORE_RESUMABLE + #include "../../feature/pause.h" +#endif namespace ExtUI { @@ -79,7 +82,8 @@ namespace ExtUI { void injectCommands(char * const); bool commandsInQueue(); - GcodeSuite::MarlinBusyState getMachineBusyState(); + GcodeSuite::MarlinBusyState getHostKeepaliveState(); + bool getHostKeepaliveIsPaused(); bool isHeaterIdle(const heater_t); bool isHeaterIdle(const extruder_t); @@ -220,14 +224,18 @@ namespace ExtUI { void setFeedrate_mm_s(const feedRate_t); void setMinFeedrate_mm_s(const feedRate_t); void setMinTravelFeedrate_mm_s(const feedRate_t); - void setPrintingAcceleration_mm_s2(const_float_t ); - void setRetractAcceleration_mm_s2(const_float_t ); - void setTravelAcceleration_mm_s2(const_float_t ); - void setFeedrate_percent(const_float_t ); + void setPrintingAcceleration_mm_s2(const_float_t); + void setRetractAcceleration_mm_s2(const_float_t); + void setTravelAcceleration_mm_s2(const_float_t); + void setFeedrate_percent(const_float_t); void setFlow_percent(const int16_t, const extruder_t); bool awaitingUserConfirm(); void setUserConfirmed(); + #if M600_PURGE_MORE_RESUMABLE + void setPauseMenuResponse(PauseMenuResponse); + #endif + #if ENABLED(LIN_ADVANCE) float getLinearAdvance_mm_mm_s(const extruder_t); void setLinearAdvance_mm_mm_s(const_float_t, const extruder_t); @@ -235,7 +243,7 @@ namespace ExtUI { #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm(); - void setJunctionDeviation_mm(const_float_t ); + void setJunctionDeviation_mm(const_float_t); #else float getAxisMaxJerk_mm_s(const axis_t); float getAxisMaxJerk_mm_s(const extruder_t); @@ -262,7 +270,7 @@ namespace ExtUI { #endif float getZOffset_mm(); - void setZOffset_mm(const_float_t ); + void setZOffset_mm(const_float_t); #if HAS_BED_PROBE float getProbeOffset_mm(const axis_t); @@ -274,11 +282,11 @@ namespace ExtUI { void setAxisBacklash_mm(const_float_t, const axis_t); float getBacklashCorrection_percent(); - void setBacklashCorrection_percent(const_float_t ); + void setBacklashCorrection_percent(const_float_t); #ifdef BACKLASH_SMOOTHING_MM float getBacklashSmoothing_mm(); - void setBacklashSmoothing_mm(const_float_t ); + void setBacklashSmoothing_mm(const_float_t); #endif #endif @@ -290,7 +298,7 @@ namespace ExtUI { #if HAS_FILAMENT_RUNOUT_DISTANCE float getFilamentRunoutDistance_mm(); - void setFilamentRunoutDistance_mm(const_float_t ); + void setFilamentRunoutDistance_mm(const_float_t); #endif #endif @@ -300,7 +308,7 @@ namespace ExtUI { #if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) float getCaseLightBrightness_percent(); - void setCaseLightBrightness_percent(const_float_t ); + void setCaseLightBrightness_percent(const_float_t); #endif #endif @@ -309,15 +317,15 @@ namespace ExtUI { float getPIDValues_Ki(const extruder_t); float getPIDValues_Kd(const extruder_t); void setPIDValues(const_float_t, const_float_t , const_float_t , extruder_t); - void startPIDTune(const_float_t, extruder_t); + void startPIDTune(const celsius_t, extruder_t); #endif #if ENABLED(PIDTEMPBED) float getBedPIDValues_Kp(); float getBedPIDValues_Ki(); float getBedPIDValues_Kd(); - void setBedPIDValues(const_float_t, const_float_t , const_float_t ); - void startBedPIDTune(const_float_t ); + void setBedPIDValues(const_float_t, const_float_t , const_float_t); + void startBedPIDTune(const celsius_t); #endif /** diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 6741de3e40..0cb476c04b 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1661,6 +1661,40 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif +#if BOTH(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) + + void MarlinUI::pause_show_message( + const PauseMessage message, + const PauseMode mode/*=PAUSE_MODE_SAME*/, + const uint8_t extruder/*=active_extruder*/ + ) { + if (mode == PAUSE_MODE_SAME) + return; + pause_mode = mode; + switch (message) { + case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); + case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); + case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); + case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING)); + case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); + case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); + case PAUSE_MESSAGE_PURGE: + #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_CONT_PURGE)); + #else + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); + #endif + case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); + case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT)); + case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); + case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_OPTION_HEADER)); + case PAUSE_MESSAGE_STATUS: + default: break; + } + } + +#endif + #if ENABLED(EEPROM_SETTINGS) #if HAS_LCD_MENU diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 56ef741b54..bf7215d383 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -55,7 +55,7 @@ #include "../module/printcounter.h" #endif -#if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) +#if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) #include "../feature/pause.h" #include "../module/motion.h" // for active_extruder #endif @@ -551,7 +551,7 @@ public: static inline bool use_click() { return false; } #endif - #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static inline void _pause_show_message() {} From e487900069368003c7feb1d23ba7c73fe4f1ee7f Mon Sep 17 00:00:00 2001 From: Skruppy Date: Sat, 10 Jul 2021 01:25:47 +0200 Subject: [PATCH 0372/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20HAS=5FKILL=20&&?= =?UTF-8?q?=20SOFT=5FRESET=5FON=5FKILL=20soft=20reset=20button=20logic=20(?= =?UTF-8?q?#22269)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 18965bcbb9..51ed99f975 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -890,11 +890,11 @@ void minkill(const bool steppers_off/*=false*/) { #if EITHER(HAS_KILL, SOFT_RESET_ON_KILL) // Wait for both KILL and ENC to be released - while (TERN0(HAS_KILL, !kill_state()) || TERN0(SOFT_RESET_ON_KILL, !ui.button_pressed())) + while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed())) watchdog_refresh(); - // Wait for either KILL or ENC press - while (TERN1(HAS_KILL, kill_state()) && TERN1(SOFT_RESET_ON_KILL, ui.button_pressed())) + // Wait for either KILL or ENC to be pressed again + while (TERN1(HAS_KILL, !kill_state()) && TERN1(SOFT_RESET_ON_KILL, !ui.button_pressed())) watchdog_refresh(); // Reboot the board From 6547b16c455a420651ed5116818b43f3e279830c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 10 Jul 2021 00:56:46 +0000 Subject: [PATCH 0373/2168] [cron] Bump distribution date (2021-07-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index dffab6e600..6c92ec78e8 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-09" +//#define STRING_DISTRIBUTION_DATE "2021-07-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2ee567cc61..9e0161b88a 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 "2021-07-09" + #define STRING_DISTRIBUTION_DATE "2021-07-10" #endif /** From bd60d779041b05d844102237109c3fd98d56f891 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jul 2021 22:24:43 -0500 Subject: [PATCH 0374/2168] =?UTF-8?q?=F0=9F=8E=A8=20Strip=20trailing=20whi?= =?UTF-8?q?tespace?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 2 +- .../extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py | 2 +- .../extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py | 4 ++-- Marlin/src/lcd/language/language_hu.h | 2 +- Marlin/src/lcd/lcdprint.cpp | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 2 +- 8 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5a38ddda0f..576e401ce0 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2416,7 +2416,7 @@ // // MKS MINI12864 V3 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. -// +// //#define MKS_MINI_12864_V3 // diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 726eb2cc39..f6ed227539 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -370,7 +370,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (mark_as_selected(row, style & SS_INVERT)) { pixel_len_t n = LCD_PIXEL_WIDTH; // pixel width of string allowed - + const int plen = pstr ? calculateWidth(pstr) : 0, vlen = vstr ? utf8_strlen(vstr) : 0; if (style & SS_CENTER) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py index 25919c3c4d..6aa8947b98 100755 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py @@ -31,7 +31,7 @@ if __name__ == "__main__": args = parser.parse_args() varname = os.path.splitext(os.path.basename(args.input))[0]; - + with open(args.input, "rb") as in_file: data = in_file.read() if args.deflate: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py index 5908f5bf17..74be574300 100755 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py @@ -29,13 +29,13 @@ class WriteSource: self.mode = mode self.offset = 8 self.byte = 0 - + def finish_byte(self): if self.offset != 8: self.values.append(self.byte) self.offset = 8 self.byte = 0 - + def add_bits_to_byte(self, value, size = 1): self.offset -= size self.byte = self.byte | value << self.offset diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index ebbc4b2df7..d4ff151f57 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -736,7 +736,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); - + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Kártya"); PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Lemez"); } diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index c421ef1a03..eef27dbdb4 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -86,7 +86,7 @@ int calculateWidth(PGM_P const pstr) { const uint8_t prop = 2; uint8_t *p = (uint8_t*)pstr; int n = 0; - + do { wchar_t ch; p = get_utf8_value_cb(p, read_byte_rom, &ch); diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 3c3e604f28..7bbc2b26da 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -332,7 +332,7 @@ #ifndef BEEPER_PIN #define BEEPER_PIN -1 #endif - + #elif ENABLED(MKS_MINI_12864_V3) #define DOGLCD_CS PD13 #define DOGLCD_A0 PC6 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 589fcf24df..091a336232 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -340,7 +340,7 @@ // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B //#undef SHOW_BOOTSCREEN - + #elif ENABLED(MKS_MINI_12864_V3) #define DOGLCD_CS PD13 #define DOGLCD_A0 PC6 From 95f96fec13eecafede6751a8b97828859005e95a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 11 Jul 2021 01:03:04 +0000 Subject: [PATCH 0375/2168] [cron] Bump distribution date (2021-07-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6c92ec78e8..014669f45d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-10" +//#define STRING_DISTRIBUTION_DATE "2021-07-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9e0161b88a..fc73e30033 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 "2021-07-10" + #define STRING_DISTRIBUTION_DATE "2021-07-11" #endif /** From ec84770c22e1097ed794441dac60dbb3294a0c87 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 11 Jul 2021 13:18:16 -0500 Subject: [PATCH 0376/2168] =?UTF-8?q?=F0=9F=9A=B8=20Limit=20LCD=20delta=20?= =?UTF-8?q?endstop=20adjustment=20like=20M666?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit In reference to #22325 --- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 195afecc1b..e6d23b1fae 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -105,7 +105,7 @@ void lcd_delta_settings() { START_MENU(); BACK_ITEM(MSG_DELTA_CALIBRATE); EDIT_ITEM(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10, delta_height + 10, _recalc_delta_settings); - #define EDIT_ENDSTOP_ADJ(LABEL,N) EDIT_ITEM_P(float43, PSTR(LABEL), &delta_endstop_adj.N, -5, 5, _recalc_delta_settings) + #define EDIT_ENDSTOP_ADJ(LABEL,N) EDIT_ITEM_P(float43, PSTR(LABEL), &delta_endstop_adj.N, -5, 0, _recalc_delta_settings) EDIT_ENDSTOP_ADJ("Ex", a); EDIT_ENDSTOP_ADJ("Ey", b); EDIT_ENDSTOP_ADJ("Ez", c); From 01ae1ced386c71bde6ae75137200ff23bd187cbb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 11 Jul 2021 18:25:51 -0500 Subject: [PATCH 0377/2168] =?UTF-8?q?=F0=9F=9A=B8=20M666:=20Fix=20value=20?= =?UTF-8?q?filter,=20add=20report=20(#22337)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit In reference to #22325 --- Marlin/src/gcode/calibrate/M666.cpp | 74 +++++++++++++------ .../src/gcode/feature/controllerfan/M710.cpp | 4 +- Marlin/src/module/settings.cpp | 43 +++-------- 3 files changed, 62 insertions(+), 59 deletions(-) diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 8ff51f0e3f..872344e4e9 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -27,30 +27,72 @@ #include "../gcode.h" #if ENABLED(DELTA) - #include "../../module/delta.h" #include "../../module/motion.h" +#else + #include "../../module/endstops.h" +#endif - #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) - #include "../../core/debug_out.h" +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../core/debug_out.h" + +void M666_report(const bool forReplay=true) { + if (!forReplay) { SERIAL_ECHOLNPGM("; Endstop adjustment:"); SERIAL_ECHO_START(); } + #if ENABLED(DELTA) + SERIAL_ECHOLNPAIR_P( + PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) + , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) + , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) + ); + #else + SERIAL_ECHOPGM(" M666"); + #if ENABLED(X_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + #if NUM_Z_STEPPER_DRIVERS >= 3 + SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + #if NUM_Z_STEPPER_DRIVERS >= 4 + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); + #endif + #else + SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); + #endif + #endif + #endif +} + +#if ENABLED(DELTA) /** * M666: Set delta endstop adjustment */ void GcodeSuite::M666() { DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING)); + bool is_err = false, is_set = false; LOOP_LINEAR_AXES(i) { if (parser.seen(AXIS_CHAR(i))) { + is_set = true; const float v = parser.value_linear_units(); - if (v * Z_HOME_DIR <= 0) delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", delta_endstop_adj[i]); + if (v > 0) + is_err = true; + else { + delta_endstop_adj[i] = v; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); + } } } + if (is_err) SERIAL_ECHOLNPAIR("?M666 offsets must be <= 0"); + if (!is_set) M666_report(); } -#elif HAS_EXTRA_ENDSTOPS - - #include "../../module/endstops.h" +#else /** * M666: Set Dual Endstops offsets for X, Y, and/or Z. @@ -81,21 +123,7 @@ #endif } #endif - if (!parser.seen("XYZ")) { - auto echo_adj = [](PGM_P const label, const_float_t value) { SERIAL_ECHOPAIR_P(label, value); }; - SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): "); - #if ENABLED(X_DUAL_ENDSTOPS) - echo_adj(PSTR(" X2:"), endstops.x2_endstop_adj); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - echo_adj(PSTR(" Y2:"), endstops.y2_endstop_adj); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #define _ECHO_ZADJ(N) echo_adj(PSTR(" Z" STRINGIFY(N) ":"), endstops.z##N##_endstop_adj); - REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _ECHO_ZADJ) - #endif - SERIAL_EOL(); - } + if (!parser.seen("XYZ")) M666_report(); } #endif // HAS_EXTRA_ENDSTOPS diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index cc450732ba..aa382a3ea9 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -27,7 +27,7 @@ #include "../../gcode.h" #include "../../../feature/controllerfan.h" -void M710_report(const bool forReplay) { +void M710_report(const bool forReplay=true) { if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } SERIAL_ECHOLNPAIR(" M710" " S", int(controllerFan.settings.active_speed), @@ -75,7 +75,7 @@ void GcodeSuite::M710() { if (seenD) controllerFan.settings.duration = parser.value_ushort(); if (!(seenR || seenS || seenI || seenA || seenD)) - M710_report(false); + M710_report(); } #endif // CONTROLLER_FAN_EDITABLE diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8c3e9fb75c..cc4d69f581 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -130,7 +130,7 @@ #include "../feature/controllerfan.h" #if ENABLED(CONTROLLER_FAN_EDITABLE) - void M710_report(const bool forReplay); + void M710_report(const bool forReplay=true); #endif #if ENABLED(CASE_LIGHT_ENABLE) @@ -168,6 +168,10 @@ void M554_report(); #endif +#if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + void M666_report(const bool forReplay=true); +#endif + #define _EN_ITEM(N) , E##N typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t; @@ -3302,14 +3306,6 @@ void MarlinSettings::reset() { #elif ENABLED(DELTA) - CONFIG_ECHO_HEADING("Endstop adjustment:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) - , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) - , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) - ); - CONFIG_ECHO_HEADING("Delta settings: L R H S XYZ ABC"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( @@ -3325,32 +3321,11 @@ void MarlinSettings::reset() { , PSTR(" C"), LINEAR_UNIT(delta_diagonal_rod_trim.c) ); - #elif HAS_EXTRA_ENDSTOPS + #endif - CONFIG_ECHO_HEADING("Endstop adjustment:"); - CONFIG_ECHO_START(); - SERIAL_ECHOPGM(" M666"); - #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #if NUM_Z_STEPPER_DRIVERS >= 3 - SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - #if NUM_Z_STEPPER_DRIVERS >= 4 - CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); - #endif - #else - SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); - #endif - #endif - - #endif // [XYZ]_DUAL_ENDSTOPS + #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + M666_report(forReplay); + #endif #if PREHEAT_COUNT From 4b63578a10b1443ab60a68a62421fc81be9e86a3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 12 Jul 2021 00:56:59 +0000 Subject: [PATCH 0378/2168] [cron] Bump distribution date (2021-07-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 014669f45d..c2df42881a 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-11" +//#define STRING_DISTRIBUTION_DATE "2021-07-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fc73e30033..b8a83e02ca 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 "2021-07-11" + #define STRING_DISTRIBUTION_DATE "2021-07-12" #endif /** From 2f6c8e1176202a014c2a038846cb0403cd2cafe0 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 11 Jul 2021 18:41:33 -0700 Subject: [PATCH 0379/2168] =?UTF-8?q?=E2=9C=A8=20Add=20TEMP=5FSENSOR=5FBOA?= =?UTF-8?q?RD=20(#22279)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 15 +- Marlin/Configuration_adv.h | 40 +++-- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/core/language.h | 3 + Marlin/src/feature/controllerfan.cpp | 11 +- Marlin/src/inc/Conditionals_adv.h | 23 +++ Marlin/src/inc/Conditionals_post.h | 91 +++++++----- Marlin/src/inc/SanityCheck.h | 124 +++++++++------- Marlin/src/module/temperature.cpp | 137 ++++++++++++++---- Marlin/src/module/temperature.h | 41 +++++- Marlin/src/module/thermistor/thermistors.h | 18 +++ Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 2 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 +- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 9 +- Marlin/src/pins/sam/pins_DUE3DOM_MINI.h | 2 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 1 + 16 files changed, 372 insertions(+), 151 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 576e401ce0..bdeb8d8501 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -474,7 +474,7 @@ * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x * - * Custom/Dummy/Other Thermos + * Custom/Dummy/Other Thermal Sensors * ------ * 0 : not used * 1000 : Custom - Specify parameters in Configuration_adv.h @@ -496,6 +496,7 @@ #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 #define TEMP_SENSOR_COOLER 0 +#define TEMP_SENSOR_BOARD 0 #define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 @@ -528,17 +529,11 @@ * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting * the Bed sensor (-1) will disable bed heating/monitoring. * - * Use the following to select temp sensors: - * -5 : Cooler - * -4 : Probe - * -3 : not used - * -2 : Chamber - * -1 : Bed - * 0-7 : E0 through E7 + * For selecting source/target use: COOLER, PROBE, BOARD, CHAMBER, BED, E0, E1, E2, E3, E4, E5, E6, E7 */ #if TEMP_SENSOR_REDUNDANT - #define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading. - #define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for. + #define TEMP_SENSOR_REDUNDANT_SOURCE E1 // The sensor that will provide the redundant reading. + #define TEMP_SENSOR_REDUNDANT_TARGET E0 // The sensor that we are providing a redundant reading for. #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. #endif diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6a7219383b..e99e1f7c09 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -125,6 +125,12 @@ #define PROBE_BETA 3950 // Beta value #endif +#if TEMP_SENSOR_BOARD == 1000 + #define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BOARD_BETA 3950 // Beta value +#endif + #if TEMP_SENSOR_REDUNDANT == 1000 #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C @@ -224,6 +230,18 @@ #endif #endif +// +// Motherboard Sensor options +// +#if TEMP_SENSOR_BOARD + #define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below. + #define BOARD_MINTEMP 8 // (°C) + #define BOARD_MAXTEMP 70 // (°C) + #ifndef TEMP_BOARD_PIN + //#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file. + #endif +#endif + // // Laser Coolant Flow Meter // @@ -480,16 +498,20 @@ */ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) - //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan - //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered - //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. - #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) - #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled - #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled - #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors - //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings + //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan + //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered + //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. + #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) + #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled + #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled + #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors + + // Use TEMP_SENSOR_BOARD as a trigger for enabling the controller fan + //#define CONTROLLER_FAN_MIN_BOARD_TEMP 40 // (°C) Turn on the fan if the board reaches this temperature + + //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings #if ENABLED(CONTROLLER_FAN_EDITABLE) - #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu + #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu #endif #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 51ed99f975..92965c743e 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1168,10 +1168,10 @@ void setup() { SETUP_RUN(HAL_init()); // Init and disable SPI thermocouples; this is still needed - #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0) + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable #endif - #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 8e97ec66a9..8de8397593 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -231,6 +231,9 @@ #define STR_HEATER_BED "bed" #define STR_HEATER_CHAMBER "chamber" #define STR_COOLER "cooler" +#define STR_MOTHERBOARD "motherboard" +#define STR_PROBE "probe" +#define STR_REDUNDANT "redundant " #define STR_LASER_TEMP "laser temperature" #define STR_STOPPED_HEATER ", system stopped! Heater_ID: " diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 0206467752..35f567fa8f 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,9 +76,14 @@ void ControllerFan::update() { ) ); - // If any of the drivers or the heated bed are enabled... - if (motor_on || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0)) - lastMotorOn = ms; //... set time to NOW so the fan will turn on + // If any triggers for the controller fan are true... + // - At least one stepper driver is enabled + // - The heated bed is enabled + // - TEMP_SENSOR_BOARD is reporting >= CONTROLLER_FAN_MIN_BOARD_TEMP + if ( motor_on + || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0) + || TERN0(HAS_CONTROLLER_FAN_MIN_BOARD_TEMP, thermalManager.wholeDegBoard() >= CONTROLLER_FAN_MIN_BOARD_TEMP) + ) lastMotorOn = ms; //... set time to NOW so the fan will turn on // Fan Settings. Set fan > 0: // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index f88d28e1a1..33ed0dad38 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -125,6 +125,29 @@ #undef THERMAL_PROTECTION_COOLER #endif +// Usurp a sensor to do redundant readings +#if TEMP_SENSOR_REDUNDANT + #define REDUNDANT_TEMP_MATCH(M,N) (TEMP_SENSOR_REDUNDANT_##M == HID_##N) +#else + #define REDUNDANT_TEMP_MATCH(...) 0 +#endif + +// Temperature sensor IDs +#define HID_REDUNDANT -6 +#define HID_COOLER -5 +#define HID_PROBE -4 +#define HID_BOARD -3 +#define HID_CHAMBER -2 +#define HID_BED -1 +#define HID_E0 0 +#define HID_E1 1 +#define HID_E2 2 +#define HID_E3 3 +#define HID_E4 4 +#define HID_E5 5 +#define HID_E6 6 +#define HID_E7 7 + #if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index dde5edb522..d62debf755 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -532,84 +532,84 @@ // Usurp a sensor to do redundant readings #if TEMP_SENSOR_REDUNDANT #ifndef TEMP_SENSOR_REDUNDANT_SOURCE - #define TEMP_SENSOR_REDUNDANT_SOURCE 1 + #define TEMP_SENSOR_REDUNDANT_SOURCE E1 #endif #ifndef TEMP_SENSOR_REDUNDANT_TARGET - #define TEMP_SENSOR_REDUNDANT_TARGET 0 + #define TEMP_SENSOR_REDUNDANT_TARGET E0 #endif #if !PIN_EXISTS(TEMP_REDUNDANT) #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 #endif - #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 + #if REDUNDANT_TEMP_MATCH(SOURCE, COOLER) #if !PIN_EXISTS(TEMP_COOLER) #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 + #elif REDUNDANT_TEMP_MATCH(SOURCE, PROBE) #if !PIN_EXISTS(TEMP_PROBE) #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 + #elif REDUNDANT_TEMP_MATCH(SOURCE, CHAMBER) #if !PIN_EXISTS(TEMP_CHAMBER) #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 + #elif REDUNDANT_TEMP_MATCH(SOURCE, BED) #if !PIN_EXISTS(TEMP_BED) #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_BED_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E0) #if !PIN_EXISTS(TEMP_0) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E0 requires TEMP_0_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_0_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E1) #if !PIN_EXISTS(TEMP_1) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E1 requires TEMP_1_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_1_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E2) #if !PIN_EXISTS(TEMP_2) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E2 requires TEMP_2_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_2_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E3) #if !PIN_EXISTS(TEMP_3) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E3 requires TEMP_3_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_3_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E4) #if !PIN_EXISTS(TEMP_4) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E4 requires TEMP_4_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_4_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E5) #if !PIN_EXISTS(TEMP_5) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E5 requires TEMP_5_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_5_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E6) #if !PIN_EXISTS(TEMP_6) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E6 requires TEMP_6_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_6_PIN #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E7) #if !PIN_EXISTS(TEMP_7) - #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to E7 requires TEMP_7_PIN." #else #define TEMP_REDUNDANT_PIN TEMP_7_PIN #endif @@ -699,7 +699,7 @@ #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 #if TEMP_SENSOR_REDUNDANT == -5 - #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif @@ -707,7 +707,7 @@ #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #elif TEMP_SENSOR_REDUNDANT == -3 - #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif @@ -715,7 +715,7 @@ #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 #elif TEMP_SENSOR_REDUNDANT == -2 - #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." #endif @@ -725,13 +725,13 @@ #endif // mimic setting up the source TEMP_SENSOR - #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #if REDUNDANT_TEMP_MATCH(SOURCE, E0) #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX #ifndef MAX31865_SENSOR_WIRES_0 #define MAX31865_SENSOR_WIRES_0 2 #endif - #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #elif REDUNDANT_TEMP_MATCH(SOURCE, E1) #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX #ifndef MAX31865_SENSOR_WIRES_1 @@ -780,7 +780,7 @@ #if HAS_MAX_TC // Translate old _SS, _CS, _SCK, _DO, _DI, _MISO, and _MOSI PIN defines. - #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) #if !PIN_EXISTS(TEMP_0_CS) // SS, CS #if PIN_EXISTS(MAX6675_SS) @@ -849,7 +849,7 @@ #endif // TEMP_SENSOR_0_IS_MAX_TC - #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) #if !PIN_EXISTS(TEMP_1_CS) // SS2, CS2 #if PIN_EXISTS(MAX6675_SS2) @@ -2584,6 +2584,9 @@ #if HAS_ADC_TEST(COOLER) #define HAS_TEMP_ADC_COOLER 1 #endif +#if HAS_ADC_TEST(BOARD) + #define HAS_TEMP_ADC_BOARD 1 +#endif #if HAS_ADC_TEST(REDUNDANT) #define HAS_TEMP_ADC_REDUNDANT 1 #endif @@ -2604,6 +2607,9 @@ #if HAS_TEMP(COOLER) #define HAS_TEMP_COOLER 1 #endif +#if HAS_TEMP(BOARD) + #define HAS_TEMP_BOARD 1 +#endif #if HAS_TEMP(REDUNDANT) #define HAS_TEMP_REDUNDANT 1 #endif @@ -2675,7 +2681,8 @@ #if HAS_HEATED_BED || HAS_TEMP_CHAMBER #define BED_OR_CHAMBER 1 #endif -#if HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE || HAS_TEMP_COOLER + +#if HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE || HAS_TEMP_COOLER || HAS_TEMP_BOARD #define HAS_TEMP_SENSOR 1 #endif @@ -2813,9 +2820,6 @@ #endif #undef _NOT_E_AUTO #undef _HAS_FAN -#if PIN_EXISTS(CONTROLLER_FAN) - #define HAS_CONTROLLER_FAN 1 -#endif #if BED_OR_CHAMBER || HAS_FAN0 #define BED_OR_CHAMBER_OR_FAN 1 @@ -2892,6 +2896,27 @@ #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default #endif +/** + * Controller Fan Settings + */ +#if PIN_EXISTS(CONTROLLER_FAN) + #define HAS_CONTROLLER_FAN 1 + #if CONTROLLER_FAN_MIN_BOARD_TEMP + #define HAS_CONTROLLER_FAN_MIN_BOARD_TEMP 1 + #endif +#endif + +#if HAS_CONTROLLER_FAN + #if ENABLED(CONTROLLER_FAN_USE_BOARD_TEMP) + #define HAS_CONTROLLER_FAN_BOARD_TEMP_TRIGGER 1 + #ifndef CONTROLLER_FAN_TRIGGER_TEMP + #define CONTROLLER_FAN_TRIGGER_TEMP 30 + #endif + #else + #undef CONTROLLER_FAN_TRIGGER_TEMP + #endif +#endif + // Servos #if PIN_EXISTS(SERVO0) && NUM_SERVOS > 0 #define HAS_SERVO_0 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f416ca88bd..ae4aba14db 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -583,6 +583,10 @@ #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." #elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" +#elif MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) + #warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." +#elif MOTHERBOARD == BOARD_BTT_SKR_E3_TURBO && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) + #warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." #endif constexpr float arm[] = AXIS_RELATIVE_MODES; @@ -1959,6 +1963,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_CHAMBER 1000 requires CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS and CHAMBER_BETA in Configuration_adv.h." #elif TEMP_SENSOR_PROBE_IS_CUSTOM && !(defined(PROBE_PULLUP_RESISTOR_OHMS) && defined(PROBE_RESISTANCE_25C_OHMS) && defined(PROBE_BETA)) #error "TEMP_SENSOR_PROBE 1000 requires PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS and PROBE_BETA in Configuration_adv.h." +#elif TEMP_SENSOR_BOARD_IS_CUSTOM && !(defined(BOARD_PULLUP_RESISTOR_OHMS) && defined(BOARD_RESISTANCE_25C_OHMS) && defined(BOARD_BETA)) + #error "TEMP_SENSOR_BOARD 1000 requires BOARD_PULLUP_RESISTOR_OHMS, BOARD_RESISTANCE_25C_OHMS and BOARD_BETA in Configuration_adv.h." #elif TEMP_SENSOR_REDUNDANT_IS_CUSTOM && !(defined(REDUNDANT_PULLUP_RESISTOR_OHMS) && defined(REDUNDANT_RESISTANCE_25C_OHMS) && defined(REDUNDANT_BETA)) #error "TEMP_SENSOR_REDUNDANT 1000 requires REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS and REDUNDANT_BETA in Configuration_adv.h." #endif @@ -1966,14 +1972,14 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Required MAX31865 settings */ -#if TEMP_SENSOR_0_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 0) +#if TEMP_SENSOR_0_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && REDUNDANT_TEMP_MATCH(SOURCE, E0)) #if !defined(MAX31865_SENSOR_WIRES_0) || !WITHIN(MAX31865_SENSOR_WIRES_0, 2, 4) #error "MAX31865_SENSOR_WIRES_0 must be defined as an integer between 2 and 4." #elif !defined(MAX31865_SENSOR_OHMS_0) || !defined(MAX31865_CALIBRATION_OHMS_0) #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." #endif #endif -#if TEMP_SENSOR_1_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && TEMP_SENSOR_REDUNDANT_SOURCE == 1) +#if TEMP_SENSOR_1_IS_MAX31865 || (TEMP_SENSOR_REDUNDANT_IS_MAX31865 && REDUNDANT_TEMP_MATCH(SOURCE, E1)) #if !defined(MAX31865_SENSOR_WIRES_1) || !WITHIN(MAX31865_SENSOR_WIRES_1, 2, 4) #error "MAX31865_SENSOR_WIRES_1 must be defined as an integer between 2 and 4." #elif !defined(MAX31865_SENSOR_OHMS_1) || !defined(MAX31865_CALIBRATION_OHMS_1) @@ -1989,62 +1995,58 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_SOURCE." #elif !defined(TEMP_SENSOR_REDUNDANT_TARGET) #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_TARGET." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == TEMP_SENSOR_REDUNDANT_TARGET + #elif REDUNDANT_TEMP_MATCH(SOURCE, TEMP_SENSOR_REDUNDANT_TARGET) #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be the same as TEMP_SENSOR_REDUNDANT_TARGET." - #elif TEMP_SENSOR_REDUNDANT_SOURCE < -5 || TEMP_SENSOR_REDUNDANT_SOURCE > 7 - #error "TEMP_SENSOR_REDUNDANT_SOURCE must be between -5 and 7." - #elif TEMP_SENSOR_REDUNDANT_TARGET < -5 || TEMP_SENSOR_REDUNDANT_TARGET > 7 - #error "TEMP_SENSOR_REDUNDANT_TARGET must be between -5 and 7." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -3 - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be -3 (not used)." - #elif TEMP_SENSOR_REDUNDANT_TARGET == -3 - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be -3 (not used)." #elif HAS_MULTI_HOTEND && TEMP_SENSOR_REDUNDANT_SOURCE < HOTENDS - #error "TEMP_SENSOR_REDUNDANT_SOURCE must be after the last TEMP_SENSOR used with a hotend; you can't use a sensor in the middle of two hotends." + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be after the last used hotend TEMP_SENSOR." #endif - #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 && HAS_HOTEND - #error "TEMP_SENSOR_REDUNDANT_SOURCE can not be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -5 && HAS_TEMP_COOLER - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Cooler (-5): TEMP_SENSOR_COOLER has already defined the sensor." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 && HAS_TEMP_PROBE - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Probe (-4): TEMP_SENSOR_PROBE has already defined the sensor." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 && HAS_TEMP_CHAMBER - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Chamber (-2): TEMP_SENSOR_CHAMBER has already defined the sensor." - #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 && HAS_TEMP_BED - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Bed (-1): TEMP_SENSOR_BED has already defined the sensor." + #if REDUNDANT_TEMP_MATCH(SOURCE, E0) && HAS_HOTEND + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." + #elif REDUNDANT_TEMP_MATCH(SOURCE, COOLER) && HAS_TEMP_COOLER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be COOLER. TEMP_SENSOR_COOLER is in use." + #elif REDUNDANT_TEMP_MATCH(SOURCE, PROBE) && HAS_TEMP_PROBE + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be PROBE. TEMP_SENSOR_PROBE is in use." + #elif REDUNDANT_TEMP_MATCH(SOURCE, BOARD) && HAS_TEMP_BOARD + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be BOARD. TEMP_SENSOR_BOARD is in use." + #elif REDUNDANT_TEMP_MATCH(SOURCE, CHAMBER) && HAS_TEMP_CHAMBER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be CHAMBER. TEMP_SENSOR_CHAMBER is in use." + #elif REDUNDANT_TEMP_MATCH(SOURCE, BED) && HAS_TEMP_BED + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be BED. TEMP_SENSOR_BED is in use." #endif - #if TEMP_SENSOR_REDUNDANT_TARGET == 0 && !PIN_EXISTS(TEMP_0) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E0 (0): requires TEMP_0_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 1 && !PIN_EXISTS(TEMP_1) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E1 (1): requires TEMP_1_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 2 && !PIN_EXISTS(TEMP_2) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E2 (2): requires TEMP_2_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 3 && !PIN_EXISTS(TEMP_3) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E3 (3): requires TEMP_3_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 4 && !PIN_EXISTS(TEMP_4) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E4 (4): requires TEMP_4_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 5 && !PIN_EXISTS(TEMP_5) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E5 (5): requires TEMP_5_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 6 && !PIN_EXISTS(TEMP_6) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E6 (6): requires TEMP_6_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == 7 && !PIN_EXISTS(TEMP_7) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E7 (7): requires TEMP_7_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && !PIN_EXISTS(TEMP_BED) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Bed (-1): requires TEMP_BED_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && !PIN_EXISTS(TEMP_CHAMBER) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Chamber (-2): requires TEMP_CHAMBER_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && !PIN_EXISTS(TEMP_PROBE) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Probe (-4): requires TEMP_PROBE_PIN" - #elif TEMP_SENSOR_REDUNDANT_TARGET == -5 && !PIN_EXISTS(TEMP_COOLER) - #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Cooler (-5): requires TEMP_COOLER_PIN" + #if REDUNDANT_TEMP_MATCH(TARGET, E0) && !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E0 without TEMP_0_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E1) && !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E1 without TEMP_1_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E2) && !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E2 without TEMP_2_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E3) && !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E3 without TEMP_3_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E4) && !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E4 without TEMP_4_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E5) && !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E5 without TEMP_5_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E6) && !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E6 without TEMP_6_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, E7) && !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E7 without TEMP_7_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, BED) && !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be BED without TEMP_BED_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, CHAMBER) && !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be CHAMBER without TEMP_CHAMBER_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, BOARD) && !PIN_EXISTS(TEMP_BOARD) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be BOARD without TEMP_BOARD_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, PROBE) && !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be PROBE without TEMP_PROBE_PIN defined." + #elif REDUNDANT_TEMP_MATCH(TARGET, COOLER) && !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be COOLER without TEMP_COOLER_PIN defined." #endif - #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 && !PIN_EXISTS(TEMP_0_CS) - #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 0 requires TEMP_0_CS_PIN." - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 && !PIN_EXISTS(TEMP_1_CS) - #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 1 requires TEMP_1_CS_PIN." + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0) && !PIN_EXISTS(TEMP_0_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E0 requires TEMP_0_CS_PIN." + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1) && !PIN_EXISTS(TEMP_1_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E1 requires TEMP_1_CS_PIN." #endif #endif @@ -2209,6 +2211,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif +#if TEMP_SENSOR_PROBE + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_PROBE requires TEMP_PROBE_PIN." + #elif !HAS_TEMP_ADC_PROBE + #error "TEMP_PROBE_PIN must be an ADC pin." + #elif DISABLED(FIX_MOUNTED_PROBE) + #error "TEMP_SENSOR_PROBE shouldn't be set without FIX_MOUNTED_PROBE." + #endif +#endif + +#if TEMP_SENSOR_BOARD + #if !PIN_EXISTS(TEMP_BOARD) + #error "TEMP_SENSOR_BOARD requires TEMP_BOARD_PIN." + #elif !HAS_TEMP_ADC_BOARD + #error "TEMP_BOARD_PIN must be an ADC pin." + #elif ENABLED(THERMAL_PROTECTION_BOARD) && (!defined(BOARD_MINTEMP) || !defined(BOARD_MAXTEMP)) + #error "THERMAL_PROTECTION_BOARD requires BOARD_MINTEMP and BOARD_MAXTEMP." + #endif +#elif CONTROLLER_FAN_MIN_BOARD_TEMP + #error "CONTROLLER_FAN_MIN_BOARD_TEMP requires TEMP_SENSOR_BOARD." +#endif + #if ENABLED(LASER_COOLANT_FLOW_METER) && !(PIN_EXISTS(FLOWMETER) && ENABLED(LASER_FEATURE)) #error "LASER_COOLANT_FLOW_METER requires FLOWMETER_PIN and LASER_FEATURE." #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 3b3c769866..0a72b2b467 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -58,8 +58,8 @@ #endif // MAX TC related macros -#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) -#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && TEMP_SENSOR_REDUNDANT_SOURCE == n)) +#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library // If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. @@ -262,7 +262,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif #if HAS_TEMP_REDUNDANT - redundant_temp_info_t Temperature::temp_redundant; + redundant_info_t Temperature::temp_redundant; #endif #if ENABLED(AUTO_POWER_E_FANS) @@ -436,6 +436,14 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, probe_info_t Temperature::temp_probe; // = { 0 } #endif +#if HAS_TEMP_BOARD + board_info_t Temperature::temp_board; // = { 0 } + #if ENABLED(THERMAL_PROTECTION_BOARD) + int16_t Temperature::mintemp_raw_BOARD = TEMP_SENSOR_BOARD_RAW_LO_TEMP, + Temperature::maxtemp_raw_BOARD = TEMP_SENSOR_COOLER_RAW_HI_TEMP; + #endif +#endif + #if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; celsius_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; @@ -937,14 +945,26 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms SERIAL_ERROR_START(); SERIAL_ECHOPGM_P(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); - if (heater_id >= 0) - SERIAL_ECHO(heater_id); - else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER)) - SERIAL_ECHOPGM(STR_HEATER_CHAMBER); - else if (TERN0(HAS_COOLER, heater_id == H_COOLER)) - SERIAL_ECHOPGM(STR_COOLER); - else - SERIAL_ECHOPGM(STR_HEATER_BED); + + heater_id_t real_heater_id = heater_id; + + #if HAS_TEMP_REDUNDANT + if (heater_id == H_REDUNDANT) { + SERIAL_ECHOPGM(STR_REDUNDANT); // print redundant and cascade to print target, too. + real_heater_id = (heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET; + } + #endif + + switch (real_heater_id) { + OPTCODE(HAS_TEMP_COOLER, case H_COOLER: SERIAL_ECHOPGM(STR_COOLER); break) + OPTCODE(HAS_TEMP_PROBE, case H_PROBE: SERIAL_ECHOPGM(STR_PROBE); break) + OPTCODE(HAS_TEMP_BOARD, case H_BOARD: SERIAL_ECHOPGM(STR_MOTHERBOARD); break) + OPTCODE(HAS_TEMP_CHAMBER, case H_CHAMBER: SERIAL_ECHOPGM(STR_HEATER_CHAMBER); break) + OPTCODE(HAS_TEMP_BED, case H_BED: SERIAL_ECHOPGM(STR_HEATER_BED); break) + default: + if (real_heater_id >= 0) + SERIAL_ECHOLNPAIR("E", real_heater_id); + } SERIAL_EOL(); } @@ -1663,6 +1683,9 @@ void Temperature::manage_heater() { #if TEMP_SENSOR_PROBE_IS_CUSTOM { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, #endif + #if TEMP_SENSOR_BOARD_IS_CUSTOM + { true, 0, 0, BOARD_PULLUP_RESISTOR_OHMS, BOARD_RESISTANCE_25C_OHMS, 0, 0, BOARD_BETA, 0 }, + #endif #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM { true, 0, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, #endif @@ -1698,6 +1721,7 @@ void Temperature::manage_heater() { TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? PSTR("COOLER") :) TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? PSTR("PROBE") :) + TERN_(TEMP_SENSOR_BOARD_IS_CUSTOM, t_index == CTI_BOARD ? PSTR("BOARD") :) TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? PSTR("REDUNDANT") :) nullptr ); @@ -1933,14 +1957,32 @@ void Temperature::manage_heater() { } #endif // HAS_TEMP_PROBE +#if HAS_TEMP_BOARD + // For motherboard temperature measurement. + celsius_float_t Temperature::analog_to_celsius_board(const int16_t raw) { + #if TEMP_SENSOR_BOARD_IS_CUSTOM + return user_thermistor_to_deg_c(CTI_BOARD, raw); + #elif TEMP_SENSOR_BOARD_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_BOARD, TEMPTABLE_BOARD_LEN); + #elif TEMP_SENSOR_BOARD_IS_AD595 + return TEMP_AD595(raw); + #elif TEMP_SENSOR_BOARD_IS_AD8495 + return TEMP_AD8495(raw); + #else + UNUSED(raw); + return 0; + #endif + } +#endif // HAS_TEMP_BOARD + #if HAS_TEMP_REDUNDANT // For redundant temperature measurement. celsius_float_t Temperature::analog_to_celsius_redundant(const int16_t raw) { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0) return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature((uint16_t)raw), raw * 0.25); - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1) return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature((uint16_t)raw), raw * 0.25); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); @@ -1983,6 +2025,7 @@ void Temperature::updateTemperaturesFromRawValues() { TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_TEMP_BOARD, temp_board.celsius = analog_to_celsius_board(temp_board.raw)); TERN_(HAS_TEMP_REDUNDANT, temp_redundant.celsius = analog_to_celsius_redundant(temp_redundant.raw)); TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); @@ -2030,23 +2073,28 @@ void Temperature::updateTemperaturesFromRawValues() { #endif // HAS_HOTEND + #define TP_CMP(S,A,B) (TEMPDIR(S) < 0 ? ((A)<(B)) : ((A)>(B))) #if ENABLED(THERMAL_PROTECTION_BED) - #define BEDCMP(A,B) (TEMPDIR(BED) < 0 ? ((A)<(B)) : ((A)>(B))) - if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); - if (temp_bed.target > 0 && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); + if (TP_CMP(BED, temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); + if (temp_bed.target > 0 && TP_CMP(BED, mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); #endif #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) - #define CHAMBERCMP(A,B) (TEMPDIR(CHAMBER) < 0 ? ((A)<(B)) : ((A)>(B))) - if (CHAMBERCMP(temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); - if (temp_chamber.target > 0 && CHAMBERCMP(mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); + if (TP_CMP(CHAMBER, temp_chamber.raw, maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); + if (temp_chamber.target > 0 && TP_CMP(CHAMBER, mintemp_raw_CHAMBER, temp_chamber.raw)) min_temp_error(H_CHAMBER); #endif #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) - #define COOLERCMP(A,B) (TEMPDIR(COOLER) < 0 ? ((A)<(B)) : ((A)>(B))) - if (cutter.unitPower > 0 && COOLERCMP(temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); - if (COOLERCMP(mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); + if (cutter.unitPower > 0 && TP_CMP(COOLER, temp_cooler.raw, maxtemp_raw_COOLER)) max_temp_error(H_COOLER); + if (TP_CMP(COOLER, mintemp_raw_COOLER, temp_cooler.raw)) min_temp_error(H_COOLER); #endif + + #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + if (TP_CMP(BOARD, temp_board.raw, maxtemp_raw_BOARD)) max_temp_error(H_BOARD); + if (TP_CMP(BOARD, mintemp_raw_BOARD, temp_board.raw)) min_temp_error(H_BOARD); + #endif + #undef TP_CMP + } // Temperature::updateTemperaturesFromRawValues /** @@ -2275,6 +2323,9 @@ void Temperature::init() { #if HAS_TEMP_ADC_PROBE HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif + #if HAS_TEMP_ADC_BOARD + HAL_ANALOG_SELECT(TEMP_BOARD_PIN); + #endif #if HAS_TEMP_ADC_REDUNDANT HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); #endif @@ -2388,6 +2439,7 @@ void Temperature::init() { #endif #endif // HAS_HOTEND + // TODO: combine these into the macros above #if HAS_HEATED_BED while (analog_to_celsius_bed(mintemp_raw_BED) < BED_MINTEMP) mintemp_raw_BED += TEMPDIR(BED) * (OVERSAMPLENR); while (analog_to_celsius_bed(maxtemp_raw_BED) > BED_MAXTEMP) maxtemp_raw_BED -= TEMPDIR(BED) * (OVERSAMPLENR); @@ -2403,15 +2455,22 @@ void Temperature::init() { while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif + #if HAS_TEMP_BOARD + while (analog_to_celsius_board(mintemp_raw_BOARD) > BOARD_MINTEMP) mintemp_raw_BOARD += TEMPDIR(BOARD) * (OVERSAMPLENR); + while (analog_to_celsius_board(maxtemp_raw_BOARD) < BOARD_MAXTEMP) maxtemp_raw_BOARD -= TEMPDIR(BOARD) * (OVERSAMPLENR); + #endif + #if HAS_TEMP_REDUNDANT temp_redundant.target = &( - #if TEMP_SENSOR_REDUNDANT_TARGET == -5 && HAS_TEMP_COOLER + #if REDUNDANT_TEMP_MATCH(TARGET, COOLER) && HAS_TEMP_COOLER temp_cooler - #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && HAS_TEMP_PROBE + #elif REDUNDANT_TEMP_MATCH(TARGET, PROBE) && HAS_TEMP_PROBE temp_probe - #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && HAS_TEMP_CHAMBER + #elif REDUNDANT_TEMP_MATCH(TARGET, BOARD) && HAS_TEMP_BOARD + temp_board + #elif REDUNDANT_TEMP_MATCH(TARGET, CHAMBER) && HAS_TEMP_CHAMBER temp_chamber - #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && HAS_TEMP_BED + #elif REDUNDANT_TEMP_MATCH(TARGET, BED) && HAS_TEMP_BED temp_bed #else temp_hotend[TEMP_SENSOR_REDUNDANT_TARGET] @@ -2787,6 +2846,7 @@ void Temperature::disable_all_heaters() { */ void Temperature::update_raw_temperatures() { + // TODO: can this be collapsed into a HOTEND_LOOP()? #if HAS_TEMP_ADC_0 && !TEMP_SENSOR_0_IS_MAX_TC temp_hotend[0].update(); #endif @@ -2808,6 +2868,7 @@ void Temperature::update_raw_temperatures() { TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); TERN_(HAS_TEMP_ADC_CHAMBER, temp_chamber.update()); TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); + TERN_(HAS_TEMP_ADC_BOARD, temp_board.update()); TERN_(HAS_TEMP_ADC_COOLER, temp_cooler.update()); TERN_(HAS_JOY_ADC_X, joystick.x.update()); @@ -2834,10 +2895,11 @@ void Temperature::readings_ready() { HOTEND_LOOP() temp_hotend[e].reset(); #endif - TERN_(HAS_HEATED_BED, temp_bed.reset()); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); - TERN_(HAS_TEMP_PROBE, temp_probe.reset()); - TERN_(HAS_TEMP_COOLER, temp_cooler.reset()); + TERN_(HAS_HEATED_BED, temp_bed.reset()); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); + TERN_(HAS_TEMP_PROBE, temp_probe.reset()); + TERN_(HAS_TEMP_COOLER, temp_cooler.reset()); + TERN_(HAS_TEMP_BOARD, temp_board.reset()); TERN_(HAS_TEMP_REDUNDANT, temp_redundant.reset()); TERN_(HAS_JOY_ADC_X, joystick.x.reset()); @@ -3264,6 +3326,11 @@ void Temperature::isr() { case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif + #if HAS_TEMP_ADC_BOARD + case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; + case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; + #endif + #if HAS_TEMP_ADC_REDUNDANT case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; @@ -3430,6 +3497,9 @@ void Temperature::isr() { #if HAS_TEMP_COOLER case H_COOLER: k = 'L'; break; #endif + #if HAS_TEMP_BOARD + case H_BOARD: k = 'M'; break; + #endif #if HAS_TEMP_REDUNDANT case H_REDUNDANT: k = 'R'; break; #endif @@ -3459,7 +3529,7 @@ void Temperature::isr() { OPTARG(HAS_TEMP_REDUNDANT, const bool include_r/*=false*/) ) { #if HAS_TEMP_HOTEND - print_heater_state(H_NONE, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); + print_heater_state(H_E0, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); #endif #if HAS_HEATED_BED print_heater_state(H_BED, degBed(), degTargetBed() OPTARG(SHOW_TEMP_ADC_VALUES, rawBedTemp())); @@ -3471,7 +3541,10 @@ void Temperature::isr() { print_heater_state(H_COOLER, degCooler(), TERN0(HAS_COOLER, degTargetCooler()) OPTARG(SHOW_TEMP_ADC_VALUES, rawCoolerTemp())); #endif #if HAS_TEMP_PROBE - print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp()) ); + print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp())); + #endif + #if HAS_TEMP_BOARD + print_heater_state(H_BOARD, degBoard(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawBoardTemp())); #endif #if HAS_TEMP_REDUNDANT if (include_r) print_heater_state(H_REDUNDANT, degRedundant(), degRedundantTarget() OPTARG(SHOW_TEMP_ADC_VALUES, rawRedundantTemp())); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index c8d085133c..61993c43a8 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -46,9 +46,13 @@ // Element identifiers. Positive values are hotends. Negative values are other heaters or coolers. typedef enum : int8_t { - H_NONE = -6, - H_COOLER, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, - H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 + H_REDUNDANT = HID_REDUNDANT, + H_COOLER = HID_COOLER, + H_PROBE = HID_PROBE, + H_BOARD = HID_BOARD, + H_CHAMBER = HID_CHAMBER, + H_BED = HID_BED, + H_E0 = HID_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 } heater_id_t; // PID storage @@ -105,6 +109,9 @@ enum ADCSensorState : char { #if HAS_TEMP_ADC_PROBE PrepareTemp_PROBE, MeasureTemp_PROBE, #endif + #if HAS_TEMP_ADC_BOARD + PrepareTemp_BOARD, MeasureTemp_BOARD, + #endif #if HAS_TEMP_ADC_REDUNDANT PrepareTemp_REDUNDANT, MeasureTemp_REDUNDANT, #endif @@ -192,7 +199,7 @@ typedef struct TempInfo { // A redundant temperature sensor typedef struct RedundantTempInfo : public TempInfo { temp_info_t* target; - } redundant_temp_info_t; + } redundant_info_t; #endif // A PWM heater with temperature sensor @@ -231,6 +238,9 @@ struct PIDHeaterInfo : public HeaterInfo { #elif HAS_TEMP_CHAMBER typedef temp_info_t chamber_info_t; #endif +#if HAS_TEMP_BOARD + typedef temp_info_t board_info_t; +#endif #if EITHER(HAS_COOLER, HAS_TEMP_COOLER) typedef heater_info_t cooler_info_t; #endif @@ -312,6 +322,9 @@ typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_ra #if TEMP_SENSOR_COOLER_IS_CUSTOM CTI_COOLER, #endif + #if TEMP_SENSOR_BOARD_IS_CUSTOM + CTI_BOARD, + #endif #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM CTI_REDUNDANT, #endif @@ -352,8 +365,11 @@ class Temperature { #if HAS_TEMP_COOLER static cooler_info_t temp_cooler; #endif + #if HAS_TEMP_BOARD + static board_info_t temp_board; + #endif #if HAS_TEMP_REDUNDANT - static redundant_temp_info_t temp_redundant; + static redundant_info_t temp_redundant; #endif #if ENABLED(AUTO_POWER_E_FANS) @@ -478,6 +494,10 @@ class Temperature { static int16_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif + #if HAS_TEMP_BOARD && ENABLED(THERMAL_PROTECTION_BOARD) + static int16_t mintemp_raw_BOARD, maxtemp_raw_BOARD; + #endif + #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 static uint8_t consecutive_low_temperature_error[HOTENDS]; #endif @@ -551,6 +571,9 @@ class Temperature { #if HAS_TEMP_COOLER static celsius_float_t analog_to_celsius_cooler(const int16_t raw); #endif + #if HAS_TEMP_BOARD + static celsius_float_t analog_to_celsius_board(const int16_t raw); + #endif #if HAS_TEMP_REDUNDANT static celsius_float_t analog_to_celsius_redundant(const int16_t raw); #endif @@ -787,6 +810,14 @@ class Temperature { #endif #endif + #if HAS_TEMP_BOARD + #if ENABLED(SHOW_TEMP_ADC_VALUES) + static inline int16_t rawBoardTemp() { return temp_board.raw; } + #endif + static inline celsius_float_t degBoard() { return temp_board.celsius; } + static inline celsius_t wholeDegBoard() { return static_cast(degBoard() + 0.5f); } + #endif + #if HAS_TEMP_REDUNDANT #if ENABLED(SHOW_TEMP_ADC_VALUES) static inline int16_t rawRedundantTemp() { return temp_redundant.raw; } diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index a6cd7c86df..9351fa6eb1 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -51,6 +51,7 @@ || TEMP_SENSOR_IS(n, CHAMBER) \ || TEMP_SENSOR_IS(n, COOLER) \ || TEMP_SENSOR_IS(n, PROBE) \ + || TEMP_SENSOR_IS(n, BOARD) \ || TEMP_SENSOR_IS(n, REDUNDANT) ) typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; @@ -305,6 +306,13 @@ typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; #define TEMPTABLE_PROBE_LEN 0 #endif +#if TEMP_SENSOR_BOARD > 0 + #define TEMPTABLE_BOARD TT_NAME(TEMP_SENSOR_BOARD) + #define TEMPTABLE_BOARD_LEN COUNT(TEMPTABLE_BOARD) +#else + #define TEMPTABLE_BOARD_LEN 0 +#endif + #if TEMP_SENSOR_REDUNDANT > 0 #define TEMPTABLE_REDUNDANT TT_NAME(TEMP_SENSOR_REDUNDANT) #define TEMPTABLE_REDUNDANT_LEN COUNT(TEMPTABLE_REDUNDANT) @@ -319,6 +327,7 @@ static_assert(255 > TEMPTABLE_0_LEN || 255 > TEMPTABLE_1_LEN || 255 > TEMPTABLE_ || 255 > TEMPTABLE_CHAMBER_LEN || 255 > TEMPTABLE_COOLER_LEN || 255 > TEMPTABLE_PROBE_LEN + || 255 > TEMPTABLE_BOARD_LEN || 255 > TEMPTABLE_REDUNDANT_LEN , "Temperature conversion tables over 255 entries need special consideration." ); @@ -513,6 +522,15 @@ static_assert(255 > TEMPTABLE_0_LEN || 255 > TEMPTABLE_1_LEN || 255 > TEMPTABLE_ #define TEMP_SENSOR_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif +#ifndef TEMP_SENSOR_BOARD_RAW_HI_TEMP + #if TT_REVRAW(BOARD) + #define TEMP_SENSOR_BOARD_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_BOARD_RAW_LO_TEMP 0 + #else + #define TEMP_SENSOR_BOARD_RAW_HI_TEMP 0 + #define TEMP_SENSOR_BOARD_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #endif +#endif #ifndef TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP #if TT_REVRAW(REDUNDANT) #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index ba53032a2a..bb4c0e8000 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -65,7 +65,7 @@ #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN #endif -#if HOTENDS == 1 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 +#if HOTENDS == 1 && !REDUNDANT_TEMP_MATCH(SOURCE, E1) #if TEMP_SENSOR_PROBE #define TEMP_PROBE_PIN TEMP_1_PIN #elif TEMP_SENSOR_CHAMBER diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 970a402b30..e99c15e70e 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -165,8 +165,8 @@ // #define TEMP_0_PIN P0_24 #define TEMP_1_PIN P0_23 -//#define TEMP_2_PIN P1_30 // Onboard thermistor #define TEMP_BED_PIN P0_25 +#define TEMP_BOARD_PIN P1_30 // Onboard thermistor, NTC100K // // Heaters / Fans diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index de50657b74..5be2bba25c 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -114,10 +114,11 @@ // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input -#define TEMP_PROBE_PIN 3 // Analog Input +#define TEMP_0_PIN 0 // Analog Input, Header J2 +#define TEMP_1_PIN 1 // Analog Input, Header J3 +#define TEMP_BOARD_PIN TEMP_1_PIN // Analog Input, Header J3 +#define TEMP_BED_PIN 2 // Analog Input, Header J6 +#define TEMP_PROBE_PIN 3 // Analog Input, Header J15 // // Heaters / Fans diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index bc0d29b00a..7754fa9329 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -68,8 +68,8 @@ // #define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) #define TEMP_1_PIN 2 // Analog Input (unused) -#define TEMP_2_PIN 5 // Analog Input (OnBoard thermistor beta 3950) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) +#define TEMP_BOARD_PIN 5 // Analog Input (OnBoard thermistor beta 3950) // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 408048bfe2..866d94924a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -161,6 +161,7 @@ // #define TEMP_0_PIN PA2 // T0 <-> E0 #define TEMP_1_PIN PA0 // T1 <-> E1 +#define TEMP_BOARD_PIN TEMP_1_PIN // Onboard sensor shared with T1 #define TEMP_BED_PIN PA1 // T2 <-> Bed #define TEMP_PROBE_PIN PC3 // Shares J4 connector with PD1 From 37cf94b888d5866cab914166ef246f14969a2cb4 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Sun, 11 Jul 2021 20:45:47 -0500 Subject: [PATCH 0380/2168] =?UTF-8?q?=F0=9F=94=A8=20Update=20LPC176x=20pla?= =?UTF-8?q?tform=20to=200.2.8=20(#22333)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/lpc176x.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/lpc176x.ini b/ini/lpc176x.ini index 450585b01a..3c5f43764b 100644 --- a/ini/lpc176x.ini +++ b/ini/lpc176x.ini @@ -14,7 +14,7 @@ # [common_LPC] platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.3.zip -platform_packages = framework-arduino-lpc176x@^0.2.6 +platform_packages = framework-arduino-lpc176x@^0.2.8 board = nxp_lpc1768 lib_ldf_mode = off lib_compat_mode = strict From c8ee056cc63c5cb996b70c3336aae9be52f8cc85 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 11 Jul 2021 22:13:58 -0700 Subject: [PATCH 0381/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Consolidate=20PS?= =?UTF-8?q?U=5FCONTROL=20(#22304)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 9 +- Marlin/src/MarlinCore.h | 19 -- Marlin/src/feature/power.cpp | 273 ++++++++++++++---------- Marlin/src/feature/power.h | 25 ++- Marlin/src/gcode/control/M80_M81.cpp | 30 +-- Marlin/src/lcd/marlinui.cpp | 12 +- Marlin/src/lcd/menu/menu_led.cpp | 11 +- Marlin/src/lcd/menu/menu_main.cpp | 6 +- Marlin/src/module/stepper/indirection.h | 2 +- ini/features.ini | 2 +- 10 files changed, 212 insertions(+), 177 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 92965c743e..1752c2ba10 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -236,6 +236,10 @@ #include "feature/stepper_driver_safety.h" #endif +#if ENABLED(PSU_CONTROL) + #include "feature/power.h" +#endif + PGMSTR(M112_KILL_STR, "M112 Shutdown"); MarlinState marlin_state = MF_INITIALIZING; @@ -883,7 +887,7 @@ void minkill(const bool steppers_off/*=false*/) { // Power off all steppers (for M112) or just the E steppers steppers_off ? disable_all_steppers() : disable_e_steppers(); - TERN_(PSU_CONTROL, PSU_OFF()); + TERN_(PSU_CONTROL, powerManager.power_off()); TERN_(HAS_SUICIDE, suicide()); @@ -1189,8 +1193,7 @@ void setup() { #if ENABLED(PSU_CONTROL) SETUP_LOG("PSU_CONTROL"); - powersupply_on = ENABLED(PSU_DEFAULT_OFF); - if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON(); + powerManager.init(); #endif #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 243811d7fb..d7ab11d046 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -81,25 +81,6 @@ extern bool wait_for_heatup; void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); #endif -#if ENABLED(PSU_CONTROL) - extern bool powersupply_on; - #define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); powersupply_on = true; }while(0) - #define PSU_PIN_OFF() do{ OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); powersupply_on = false; }while(0) - #if ENABLED(AUTO_POWER_CONTROL) - #define PSU_ON() powerManager.power_on() - #define PSU_OFF() powerManager.power_off() - #define PSU_OFF_SOON() powerManager.power_off_soon() - #else - #define PSU_ON() PSU_PIN_ON() - #if ENABLED(PS_OFF_SOUND) - #define PSU_OFF() do{ BUZZ(1000, 659); PSU_PIN_OFF(); }while(0) - #else - #define PSU_OFF() PSU_PIN_OFF() - #endif - #define PSU_OFF_SOON PSU_OFF - #endif -#endif - bool pin_is_protected(const pin_t pin); #if HAS_SUICIDE diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 9b173d6ee7..9070fd7946 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -26,10 +26,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(AUTO_POWER_CONTROL) - #include "power.h" -#include "../module/temperature.h" #include "../module/stepper/indirection.h" #include "../MarlinCore.h" @@ -41,133 +38,179 @@ #include "../gcode/gcode.h" #endif -#if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) - #include "controllerfan.h" -#endif - Power powerManager; +bool Power::psu_on; -millis_t Power::lastPowerOn; - -bool Power::is_power_needed() { - - if (printJobOngoing() || printingIsPaused()) return true; - - #if ENABLED(AUTO_POWER_FANS) - FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; - #endif - - #if ENABLED(AUTO_POWER_E_FANS) - HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; - #endif +#if ENABLED(AUTO_POWER_CONTROL) + #include "../module/temperature.h" #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) - if (controllerFan.state()) return true; + #include "controllerfan.h" #endif - if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed)) - return true; - - if (TERN0(AUTO_POWER_COOLER_FAN, thermalManager.coolerfan_speed)) - return true; - - // If any of the drivers or the bed are enabled... - if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON - #if HAS_X2_ENABLE - || X2_ENABLE_READ() == X_ENABLE_ON - #endif - #if HAS_Y2_ENABLE - || Y2_ENABLE_READ() == Y_ENABLE_ON - #endif - #if HAS_Z2_ENABLE - || Z2_ENABLE_READ() == Z_ENABLE_ON - #endif - #if E_STEPPERS - #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == E_ENABLE_ON - REPEAT(E_STEPPERS, _OR_ENABLED_E) - #endif - ) return true; - - #if HAS_HOTEND - HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; - #endif - - if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; - - #if HAS_HOTEND && AUTO_POWER_E_TEMP - HOTEND_LOOP() if (thermalManager.degHotend(e) >= (AUTO_POWER_E_TEMP)) return true; - #endif - - #if HAS_HEATED_CHAMBER && AUTO_POWER_CHAMBER_TEMP - if (thermalManager.degChamber() >= (AUTO_POWER_CHAMBER_TEMP)) return true; - #endif - - #if HAS_COOLER && AUTO_POWER_COOLER_TEMP - if (thermalManager.degCooler() >= (AUTO_POWER_COOLER_TEMP)) return true; - #endif - - return false; -} - -#ifndef POWER_TIMEOUT - #define POWER_TIMEOUT 0 + millis_t Power::lastPowerOn; #endif -void Power::check(const bool pause) { - static bool _pause = false; - static millis_t nextPowerCheck = 0; - const millis_t now = millis(); - #if POWER_TIMEOUT > 0 - if (pause != _pause) { - lastPowerOn = now + !now; - _pause = pause; - } - if (pause) return; - #endif - if (ELAPSED(now, nextPowerCheck)) { - nextPowerCheck = now + 2500UL; - if (is_power_needed()) - power_on(); - else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) - power_off(); - } +/** + * Initialize pins & state for the power manager. + * + */ +void Power::init(){ + psu_on = ENABLED(PSU_DEFAULT_OFF); // Set opposite state to get full power_off/on + TERN(PSU_DEFAULT_OFF, power_off(), power_on()); } +/** + * Power on if the power is currently off. + * Restores stepper drivers and processes any PSU_POWERUP_GCODE. + * + */ void Power::power_on() { - const millis_t now = millis(); - lastPowerOn = now + !now; - if (!powersupply_on) { - PSU_PIN_ON(); - safe_delay(PSU_POWERUP_DELAY); - restore_stepper_drivers(); - TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); - #ifdef PSU_POWERUP_GCODE - GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWERUP_GCODE)); - #endif - } -} + #if ENABLED(AUTO_POWER_CONTROL) + const millis_t now = millis(); + lastPowerOn = now + !now; + #endif -void Power::power_off() { - if (powersupply_on) { - #ifdef PSU_POWEROFF_GCODE - GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWEROFF_GCODE)); - #endif + if (psu_on) return; - #if ENABLED(PS_OFF_SOUND) - BUZZ(1000, 659); - #endif + OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); + psu_on = true; + safe_delay(PSU_POWERUP_DELAY); + restore_stepper_drivers(); + TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); - PSU_PIN_OFF(); - } -} - -void Power::power_off_soon() { - #if POWER_OFF_DELAY - lastPowerOn = millis() - SEC_TO_MS(POWER_TIMEOUT) + SEC_TO_MS(POWER_OFF_DELAY); - //if (!lastPowerOn) ++lastPowerOn; - #else - power_off(); + #ifdef PSU_POWERUP_GCODE + GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWERUP_GCODE)); #endif } +/** + * Power off if the power is currently on. + * Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled. + * + */ +void Power::power_off() { + if (!psu_on) return; + + #ifdef PSU_POWEROFF_GCODE + GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWEROFF_GCODE)); + #endif + + #if ENABLED(PS_OFF_SOUND) + BUZZ(1000, 659); + #endif + + OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); + psu_on = false; +} + + +#if ENABLED(AUTO_POWER_CONTROL) + + #ifndef POWER_TIMEOUT + #define POWER_TIMEOUT 0 + #endif + + /** + * Check all conditions that would signal power needing to be on. + * + * @returns bool if power is needed + */ + bool Power::is_power_needed() { + + if (printJobOngoing() || printingIsPaused()) return true; + + #if ENABLED(AUTO_POWER_FANS) + FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; + #endif + + #if ENABLED(AUTO_POWER_E_FANS) + HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; + #endif + + #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + if (controllerFan.state()) return true; + #endif + + if (TERN0(AUTO_POWER_CHAMBER_FAN, thermalManager.chamberfan_speed)) + return true; + + if (TERN0(AUTO_POWER_COOLER_FAN, thermalManager.coolerfan_speed)) + return true; + + // If any of the drivers or the bed are enabled... + if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON + #if HAS_X2_ENABLE + || X2_ENABLE_READ() == X_ENABLE_ON + #endif + #if HAS_Y2_ENABLE + || Y2_ENABLE_READ() == Y_ENABLE_ON + #endif + #if HAS_Z2_ENABLE + || Z2_ENABLE_READ() == Z_ENABLE_ON + #endif + #if E_STEPPERS + #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == E_ENABLE_ON + REPEAT(E_STEPPERS, _OR_ENABLED_E) + #endif + ) return true; + + #if HAS_HOTEND + HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #endif + + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; + + #if HAS_HOTEND && AUTO_POWER_E_TEMP + HOTEND_LOOP() if (thermalManager.degHotend(e) >= (AUTO_POWER_E_TEMP)) return true; + #endif + + #if HAS_HEATED_CHAMBER && AUTO_POWER_CHAMBER_TEMP + if (thermalManager.degChamber() >= (AUTO_POWER_CHAMBER_TEMP)) return true; + #endif + + #if HAS_COOLER && AUTO_POWER_COOLER_TEMP + if (thermalManager.degCooler() >= (AUTO_POWER_COOLER_TEMP)) return true; + #endif + + return false; + } + + /** + * Check if we should power off automatically (POWER_TIMEOUT elapsed, !is_power_needed). + * + * @param pause pause the 'timer' + */ + void Power::check(const bool pause) { + static millis_t nextPowerCheck = 0; + const millis_t now = millis(); + #if POWER_TIMEOUT > 0 + static bool _pause = false; + if (pause != _pause) { + lastPowerOn = now + !now; + _pause = pause; + } + if (pause) return; + #endif + if (ELAPSED(now, nextPowerCheck)) { + nextPowerCheck = now + 2500UL; + if (is_power_needed()) + power_on(); + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) + power_off(); + } + } + + #if POWER_OFF_DELAY > 0 + + /** + * Power off with a delay. Power off is triggered by check() after the delay. + * + */ + void Power::power_off_soon() { + lastPowerOn = millis() - SEC_TO_MS(POWER_TIMEOUT) + SEC_TO_MS(POWER_OFF_DELAY); + } + + #endif + #endif // AUTO_POWER_CONTROL diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index bca5432946..7f5a97e6df 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -25,17 +25,32 @@ * power.h - power control */ -#include "../core/millis_t.h" +#if ENABLED(AUTO_POWER_CONTROL) + #include "../core/millis_t.h" +#endif class Power { public: - static void check(const bool pause); + static bool psu_on; + + static void init(); static void power_on(); static void power_off(); + + #if ENABLED(AUTO_POWER_CONTROL) && POWER_OFF_DELAY > 0 static void power_off_soon(); - private: - static millis_t lastPowerOn; - static bool is_power_needed(); + #else + static inline void power_off_soon() { power_off(); } + #endif + + #if ENABLED(AUTO_POWER_CONTROL) + static void check(const bool pause); + + private: + static millis_t lastPowerOn; + static bool is_power_needed(); + + #endif }; extern Power powerManager; diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 1b5ea2f7ef..9640c72006 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -29,25 +29,17 @@ #include "../../inc/MarlinConfig.h" +#if ENABLED(PSU_CONTROL) + #include "../queue.h" + #include "../../feature/power.h" +#endif + #if HAS_SUICIDE #include "../../MarlinCore.h" #endif #if ENABLED(PSU_CONTROL) - #if ENABLED(AUTO_POWER_CONTROL) - #include "../../feature/power.h" - #else - void restore_stepper_drivers(); - #endif - - // Could be moved to a feature, but this is all the data - bool powersupply_on; - - #if HAS_TRINAMIC_CONFIG - #include "../../feature/tmc_util.h" - #endif - /** * M80 : Turn on the Power Supply * M80 S : Report the current state and exit @@ -56,11 +48,11 @@ // S: Report the current power supply state and exit if (parser.seen('S')) { - SERIAL_ECHOPGM_P(powersupply_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); + SERIAL_ECHOPGM_P(powerManager.psu_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); return; } - PSU_ON(); + powerManager.power_on(); /** * If you have a switch on suicide pin, this is useful @@ -71,12 +63,6 @@ OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); #endif - #if DISABLED(AUTO_POWER_CONTROL) - safe_delay(PSU_POWERUP_DELAY); - restore_stepper_drivers(); - TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); - #endif - TERN_(HAS_LCD_MENU, ui.reset_status()); } @@ -106,7 +92,7 @@ void GcodeSuite::M81() { #if HAS_SUICIDE suicide(); #elif ENABLED(PSU_CONTROL) - PSU_OFF_SOON(); + powerManager.power_off_soon(); #endif LCD_MESSAGEPGM_P(PSTR(MACHINE_NAME " " STR_OFF ".")); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 0cb476c04b..206bae925a 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -158,6 +158,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #include "../feature/power_monitor.h" #endif + #if ENABLED(PSU_CONTROL) && defined(LED_BACKLIGHT_TIMEOUT) + #include "../feature/power.h" + #endif + #if HAS_ENCODER_ACTION volatile uint8_t MarlinUI::buttons; #if HAS_SLOW_BUTTONS @@ -826,8 +830,8 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; static uint16_t max_display_update_time = 0; millis_t ms = millis(); - #ifdef LED_BACKLIGHT_TIMEOUT - leds.update_timeout(powersupply_on); + #if ENABLED(PSU_CONTROL) && defined(LED_BACKLIGHT_TIMEOUT) + leds.update_timeout(powerManager.psu_on); #endif #if HAS_LCD_MENU @@ -976,8 +980,8 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; refresh(LCDVIEW_REDRAW_NOW); - #ifdef LED_BACKLIGHT_TIMEOUT - if (!powersupply_on) leds.reset_timeout(ms); + #if ENABLED(PSU_CONTROL) && defined(LED_BACKLIGHT_TIMEOUT) + if (!powerManager.psu_on) leds.reset_timeout(ms); #endif } diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 284e80c931..3261ecc658 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -30,6 +30,10 @@ #include "menu_item.h" +#if ENABLED(PSU_CONTROL) + #include "../../feature/power.h" +#endif + #if ENABLED(LED_CONTROL_MENU) #include "../../feature/leds/leds.h" @@ -125,12 +129,7 @@ void menu_led() { BACK_ITEM(MSG_MAIN); #if ENABLED(LED_CONTROL_MENU) - #if ENABLED(PSU_CONTROL) - extern bool powersupply_on; - #else - constexpr bool powersupply_on = true; - #endif - if (powersupply_on) { + if (TERN1(PSU_CONTROL, powerManager.psu_on)) { editable.state = leds.lights_on; EDIT_ITEM(bool, MSG_LEDS, &editable.state, leds.toggle); } diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 6f32ef1d60..8fce2038a3 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -35,6 +35,10 @@ #include "../../module/stepper.h" #include "../../sd/cardreader.h" +#if ENABLED(PSU_CONTROL) + #include "../../feature/power.h" +#endif + #if HAS_GAMES && DISABLED(LCD_INFO_MENU) #include "game/game.h" #endif @@ -385,7 +389,7 @@ void menu_main() { // Switch power on/off // #if ENABLED(PSU_CONTROL) - if (powersupply_on) + if (powerManager.psu_on) #if ENABLED(PS_OFF_CONFIRM) CONFIRM_ITEM(MSG_SWITCH_PS_OFF, MSG_YES, MSG_NO, diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 08d0be0b31..beba03699e 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -44,7 +44,7 @@ #include "trinamic.h" #endif -void restore_stepper_drivers(); // Called by PSU_ON +void restore_stepper_drivers(); // Called by powerManager.power_on() void reset_stepper_drivers(); // Called by settings.load / settings.reset // X Stepper diff --git a/ini/features.ini b/ini/features.ini index 2d9d7ab063..bf8342e545 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -128,7 +128,7 @@ HAS_PRUSA_MMU1 = src_filter=+ HAS_PRUSA_MMU2 = src_filter=+ + PASSWORD_FEATURE = src_filter=+ + ADVANCED_PAUSE_FEATURE = src_filter=+ + + -AUTO_POWER_CONTROL = src_filter=+ +PSU_CONTROL = src_filter=+ HAS_POWER_MONITOR = src_filter=+ + POWER_LOSS_RECOVERY = src_filter=+ + PROBE_TEMP_COMPENSATION = src_filter=+ + From 2c6a053ce174f2404d8eeb3917fc303115b7614a Mon Sep 17 00:00:00 2001 From: ellensp Date: Mon, 12 Jul 2021 17:15:48 +1200 Subject: [PATCH 0382/2168] =?UTF-8?q?=F0=9F=8E=A8=20Optional=20Custom=20Bu?= =?UTF-8?q?tton=20description=20(#22336)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 113 ++++++++++++++++++++++++++++---------- 1 file changed, 83 insertions(+), 30 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1752c2ba10..8b5f83f2a4 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -526,95 +526,148 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(CUSTOM_USER_BUTTONS) // Handle a custom user button if defined const bool printer_not_busy = !printingIsActive(); - #define HAS_CUSTOM_USER_BUTTON(N) (PIN_EXISTS(BUTTON##N) && defined(BUTTON##N##_HIT_STATE) && defined(BUTTON##N##_GCODE) && defined(BUTTON##N##_DESC)) - #define CHECK_CUSTOM_USER_BUTTON(N) do{ \ + const millis_t ms = millis(); + #define HAS_CUSTOM_USER_BUTTON(N) (PIN_EXISTS(BUTTON##N) && defined(BUTTON##N##_HIT_STATE) && defined(BUTTON##N##_GCODE)) + #define HAS_BETTER_USER_BUTTON(N) HAS_CUSTOM_USER_BUTTON(N) && defined(BUTTON##N##_DESC) + #define _CHECK_CUSTOM_USER_BUTTON(N, CODE) do{ \ constexpr millis_t CUB_DEBOUNCE_DELAY_##N = 250UL; \ static millis_t next_cub_ms_##N; \ if (BUTTON##N##_HIT_STATE == READ(BUTTON##N##_PIN) \ && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy)) { \ - const millis_t ms = millis(); \ if (ELAPSED(ms, next_cub_ms_##N)) { \ next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ - if (strlen(BUTTON##N##_DESC)) \ - LCD_MESSAGEPGM_P(PSTR(BUTTON##N##_DESC)); \ + CODE; \ queue.inject_P(PSTR(BUTTON##N##_GCODE)); \ } \ } \ }while(0) - #if HAS_CUSTOM_USER_BUTTON(1) + #define CHECK_CUSTOM_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, NOOP) + #define CHECK_BETTER_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, if (strlen(BUTTON##N##_DESC)) LCD_MESSAGEPGM_P(PSTR(BUTTON##N##_DESC))) + + #if HAS_BETTER_USER_BUTTON(1) + CHECK_BETTER_USER_BUTTON(1); + #elif HAS_CUSTOM_USER_BUTTON(1) CHECK_CUSTOM_USER_BUTTON(1); #endif - #if HAS_CUSTOM_USER_BUTTON(2) + #if HAS_BETTER_USER_BUTTON(2) + CHECK_BETTER_USER_BUTTON(2); + #elif HAS_CUSTOM_USER_BUTTON(2) CHECK_CUSTOM_USER_BUTTON(2); #endif - #if HAS_CUSTOM_USER_BUTTON(3) + #if HAS_BETTER_USER_BUTTON(3) + CHECK_BETTER_USER_BUTTON(3); + #elif HAS_CUSTOM_USER_BUTTON(3) CHECK_CUSTOM_USER_BUTTON(3); #endif - #if HAS_CUSTOM_USER_BUTTON(4) + #if HAS_BETTER_USER_BUTTON(4) + CHECK_BETTER_USER_BUTTON(4); + #elif HAS_CUSTOM_USER_BUTTON(4) CHECK_CUSTOM_USER_BUTTON(4); #endif - #if HAS_CUSTOM_USER_BUTTON(5) + #if HAS_BETTER_USER_BUTTON(5) + CHECK_BETTER_USER_BUTTON(5); + #elif HAS_CUSTOM_USER_BUTTON(5) CHECK_CUSTOM_USER_BUTTON(5); #endif - #if HAS_CUSTOM_USER_BUTTON(6) + #if HAS_BETTER_USER_BUTTON(6) + CHECK_BETTER_USER_BUTTON(6); + #elif HAS_CUSTOM_USER_BUTTON(6) CHECK_CUSTOM_USER_BUTTON(6); #endif - #if HAS_CUSTOM_USER_BUTTON(7) + #if HAS_BETTER_USER_BUTTON(7) + CHECK_BETTER_USER_BUTTON(7); + #elif HAS_CUSTOM_USER_BUTTON(7) CHECK_CUSTOM_USER_BUTTON(7); #endif - #if HAS_CUSTOM_USER_BUTTON(8) + #if HAS_BETTER_USER_BUTTON(8) + CHECK_BETTER_USER_BUTTON(8); + #elif HAS_CUSTOM_USER_BUTTON(8) CHECK_CUSTOM_USER_BUTTON(8); #endif - #if HAS_CUSTOM_USER_BUTTON(9) + #if HAS_BETTER_USER_BUTTON(9) + CHECK_BETTER_USER_BUTTON(9); + #elif HAS_CUSTOM_USER_BUTTON(9) CHECK_CUSTOM_USER_BUTTON(9); #endif - #if HAS_CUSTOM_USER_BUTTON(10) + #if HAS_BETTER_USER_BUTTON(10) + CHECK_BETTER_USER_BUTTON(10); + #elif HAS_CUSTOM_USER_BUTTON(10) CHECK_CUSTOM_USER_BUTTON(10); #endif - #if HAS_CUSTOM_USER_BUTTON(11) + #if HAS_BETTER_USER_BUTTON(11) + CHECK_BETTER_USER_BUTTON(11); + #elif HAS_CUSTOM_USER_BUTTON(11) CHECK_CUSTOM_USER_BUTTON(11); #endif - #if HAS_CUSTOM_USER_BUTTON(12) + #if HAS_BETTER_USER_BUTTON(12) + CHECK_BETTER_USER_BUTTON(12); + #elif HAS_CUSTOM_USER_BUTTON(12) CHECK_CUSTOM_USER_BUTTON(12); #endif - #if HAS_CUSTOM_USER_BUTTON(13) + #if HAS_BETTER_USER_BUTTON(13) + CHECK_BETTER_USER_BUTTON(13); + #elif HAS_CUSTOM_USER_BUTTON(13) CHECK_CUSTOM_USER_BUTTON(13); #endif - #if HAS_CUSTOM_USER_BUTTON(14) + #if HAS_BETTER_USER_BUTTON(14) + CHECK_BETTER_USER_BUTTON(14); + #elif HAS_CUSTOM_USER_BUTTON(14) CHECK_CUSTOM_USER_BUTTON(14); #endif - #if HAS_CUSTOM_USER_BUTTON(15) + #if HAS_BETTER_USER_BUTTON(15) + CHECK_BETTER_USER_BUTTON(15); + #elif HAS_CUSTOM_USER_BUTTON(15) CHECK_CUSTOM_USER_BUTTON(15); #endif - #if HAS_CUSTOM_USER_BUTTON(16) + #if HAS_BETTER_USER_BUTTON(16) + CHECK_BETTER_USER_BUTTON(16); + #elif HAS_CUSTOM_USER_BUTTON(16) CHECK_CUSTOM_USER_BUTTON(16); #endif - #if HAS_CUSTOM_USER_BUTTON(17) + #if HAS_BETTER_USER_BUTTON(17) + CHECK_BETTER_USER_BUTTON(17); + #elif HAS_CUSTOM_USER_BUTTON(17) CHECK_CUSTOM_USER_BUTTON(17); #endif - #if HAS_CUSTOM_USER_BUTTON(18) + #if HAS_BETTER_USER_BUTTON(18) + CHECK_BETTER_USER_BUTTON(18); + #elif HAS_CUSTOM_USER_BUTTON(18) CHECK_CUSTOM_USER_BUTTON(18); #endif - #if HAS_CUSTOM_USER_BUTTON(19) + #if HAS_BETTER_USER_BUTTON(19) + CHECK_BETTER_USER_BUTTON(19); + #elif HAS_CUSTOM_USER_BUTTON(19) CHECK_CUSTOM_USER_BUTTON(19); #endif - #if HAS_CUSTOM_USER_BUTTON(20) + #if HAS_BETTER_USER_BUTTON(20) + CHECK_BETTER_USER_BUTTON(20); + #elif HAS_CUSTOM_USER_BUTTON(20) CHECK_CUSTOM_USER_BUTTON(20); #endif - #if HAS_CUSTOM_USER_BUTTON(21) + #if HAS_BETTER_USER_BUTTON(21) + CHECK_BETTER_USER_BUTTON(21); + #elif HAS_CUSTOM_USER_BUTTON(21) CHECK_CUSTOM_USER_BUTTON(21); #endif - #if HAS_CUSTOM_USER_BUTTON(22) + #if HAS_BETTER_USER_BUTTON(22) + CHECK_BETTER_USER_BUTTON(22); + #elif HAS_CUSTOM_USER_BUTTON(22) CHECK_CUSTOM_USER_BUTTON(22); #endif - #if HAS_CUSTOM_USER_BUTTON(23) + #if HAS_BETTER_USER_BUTTON(23) + CHECK_BETTER_USER_BUTTON(23); + #elif HAS_CUSTOM_USER_BUTTON(23) CHECK_CUSTOM_USER_BUTTON(23); #endif - #if HAS_CUSTOM_USER_BUTTON(24) + #if HAS_BETTER_USER_BUTTON(24) + CHECK_BETTER_USER_BUTTON(24); + #elif HAS_CUSTOM_USER_BUTTON(24) CHECK_CUSTOM_USER_BUTTON(24); #endif - #if HAS_CUSTOM_USER_BUTTON(25) + #if HAS_BETTER_USER_BUTTON(25) + CHECK_BETTER_USER_BUTTON(25); + #elif HAS_CUSTOM_USER_BUTTON(25) CHECK_CUSTOM_USER_BUTTON(25); #endif #endif From c0ecc6625ffbe70cf761465ddd5443ac30124cae Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Mon, 12 Jul 2021 00:22:08 -0500 Subject: [PATCH 0383/2168] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Allow=20headl?= =?UTF-8?q?ess=20Flow=20Meter=20(#22234)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/cooler.cpp | 23 ++++++++++++----------- Marlin/src/feature/cooler.h | 6 +++--- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- ini/features.ini | 3 ++- 5 files changed, 19 insertions(+), 17 deletions(-) diff --git a/Marlin/src/feature/cooler.cpp b/Marlin/src/feature/cooler.cpp index a1f25c5fad..e0f99777d1 100644 --- a/Marlin/src/feature/cooler.cpp +++ b/Marlin/src/feature/cooler.cpp @@ -22,26 +22,27 @@ #include "../inc/MarlinConfig.h" -#if HAS_COOLER +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "cooler.h" Cooler cooler; -uint8_t Cooler::mode = 0; -uint16_t Cooler::capacity; -uint16_t Cooler::load; -bool Cooler::enabled = false; +#if HAS_COOLER + uint8_t Cooler::mode = 0; + uint16_t Cooler::capacity; + uint16_t Cooler::load; + bool Cooler::enabled = false; +#endif #if ENABLED(LASER_COOLANT_FLOW_METER) bool Cooler::flowmeter = false; millis_t Cooler::flowmeter_next_ms; // = 0 volatile uint16_t Cooler::flowpulses; float Cooler::flowrate; + #if ENABLED(FLOWMETER_SAFETY) + bool Cooler::flowsafety_enabled = true; + bool Cooler::flowfault = false; + #endif #endif -#if ENABLED(FLOWMETER_SAFETY) - bool Cooler::flowsafety_enabled = true; - bool Cooler::fault = false; -#endif - -#endif // HAS_COOLER +#endif // HAS_COOLER || LASER_COOLANT_FLOW_METER diff --git a/Marlin/src/feature/cooler.h b/Marlin/src/feature/cooler.h index 9bd98d0b10..9891514e23 100644 --- a/Marlin/src/feature/cooler.h +++ b/Marlin/src/feature/cooler.h @@ -94,12 +94,12 @@ public: } #if ENABLED(FLOWMETER_SAFETY) - static bool fault; // Flag that the cooler is in a fault state - static bool flowsafety_enabled; // Flag to disable the cutter if flow rate is too low + static bool flowfault; // Flag that the cooler is in a fault state + static bool flowsafety_enabled; // Flag to disable the cutter if flow rate is too low static void flowsafety_toggle() { flowsafety_enabled = !flowsafety_enabled; } static bool check_flow_too_low() { const bool too_low = flowsafety_enabled && flowrate < (FLOWMETER_MIN_LITERS_PER_MINUTE); - if (too_low) fault = true; + flowfault = too_low; return too_low; } #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0f66c4035e..12fd231ca8 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -292,7 +292,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(FLOWMETER_SAFETY) - if (cooler.fault) { + if (cooler.flowfault) { SERIAL_ECHO_MSG(STR_FLOWMETER_FAULT); return; } diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 0a72b2b467..4a56ba66e9 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1608,7 +1608,7 @@ void Temperature::manage_heater() { #if ENABLED(FLOWMETER_SAFETY) if (cutter.enabled() && cooler.check_flow_too_low()) { cutter.disable(); - ui.flow_fault(); + TERN_(HAS_DISPLAY, ui.flow_fault()); } #endif #endif diff --git a/ini/features.ini b/ini/features.ini index bf8342e545..e397ea31e9 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -202,7 +202,8 @@ SDSUPPORT = src_filter=+ + GCODE_REPEAT_MARKERS = src_filter=+ + HAS_EXTRUDERS = src_filter=+ + + -HAS_COOLER = src_filter=+ + +HAS_COOLER = src_filter=+ +HAS_COOLER|LASER_COOLANT_FLOW_METER = src_filter=+ AUTO_REPORT_TEMPERATURES = src_filter=+ INCH_MODE_SUPPORT = src_filter=+ TEMPERATURE_UNITS_SUPPORT = src_filter=+ From 4febb2352179f3de58db2161572de4050197bd5d Mon Sep 17 00:00:00 2001 From: MKS-Sean <56996910+MKS-Sean@users.noreply.github.com> Date: Tue, 13 Jul 2021 08:17:28 +0800 Subject: [PATCH 0384/2168] =?UTF-8?q?=E2=9C=A8=20MKS=20Robin=20Nano=20v3?= =?UTF-8?q?=20+=20TFT=5FLVGL=5FUI=20+=20WiFi=20module=20(#22109)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.cpp | 14 +- Marlin/src/HAL/STM32/HAL_MinSerial.cpp | 2 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 4 +- Marlin/src/HAL/STM32/MarlinSPI.cpp | 4 +- Marlin/src/HAL/STM32/MarlinSerial.cpp | 4 +- .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 4 +- Marlin/src/HAL/STM32/Servo.cpp | 4 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 4 +- Marlin/src/HAL/STM32/eeprom_sdcard.cpp | 4 +- Marlin/src/HAL/STM32/eeprom_sram.cpp | 4 +- Marlin/src/HAL/STM32/eeprom_wired.cpp | 4 +- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +- Marlin/src/HAL/STM32/fastio.cpp | 4 +- Marlin/src/HAL/STM32/msc_sd.cpp | 14 +- Marlin/src/HAL/STM32/tft/gt911.cpp | 4 +- Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 4 +- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 4 +- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 4 +- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 4 +- Marlin/src/HAL/STM32/timers.cpp | 4 +- Marlin/src/HAL/STM32/usb_host.cpp | 4 +- Marlin/src/HAL/STM32/usb_serial.cpp | 4 +- Marlin/src/HAL/STM32/watchdog.cpp | 4 +- Marlin/src/HAL/STM32F1/msc_sd.cpp | 7 +- Marlin/src/MarlinCore.cpp | 7 - Marlin/src/core/macros.h | 2 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 28 +- .../lcd/extui/mks_ui/draw_error_message.cpp | 5 +- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 4 +- .../src/lcd/extui/mks_ui/draw_ready_print.cpp | 122 ++- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 36 +- Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp | 16 +- .../lcd/extui/mks_ui/mks_hardware_test.cpp | 140 ++-- .../src/lcd/extui/mks_ui/mks_hardware_test.h | 6 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 5 +- .../lcd/extui/mks_ui/printer_operation.cpp | 37 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 33 +- .../lcd/extui/mks_ui/tft_multi_language.cpp | 34 +- Marlin/src/lcd/extui/mks_ui/wifiSerial.h | 76 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32.cpp | 352 +++++++++ .../src/lcd/extui/mks_ui/wifiSerial_STM32.h | 63 ++ ...{wifiSerial.cpp => wifiSerial_STM32F1.cpp} | 18 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32F1.h | 77 ++ Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 704 ++++++++++++------ Marlin/src/lcd/extui/mks_ui/wifi_module.h | 4 + Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 10 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 1 + .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 15 +- buildroot/tests/mks_robin_nano35 | 4 +- ini/stm32f1-maple.ini | 3 +- 51 files changed, 1271 insertions(+), 650 deletions(-) create mode 100644 Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp create mode 100644 Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h rename Marlin/src/lcd/extui/mks_ui/{wifiSerial.cpp => wifiSerial_STM32F1.cpp} (88%) create mode 100644 Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index e09b52f7db..d8035a979d 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "HAL.h" #include "usb_serial.h" @@ -91,15 +91,13 @@ void HAL_init() { USB_Hook_init(); #endif - TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler - #if HAS_SD_HOST_DRIVE - MSC_SD_init(); // Enable USB SD card access - #endif + TERN_(HAS_SD_HOST_DRIVE, MSC_SD_init()); // Enable USB SD card access #if PIN_EXISTS(USB_CONNECT) - OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection - delay(1000); // Give OS time to notice + OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection + delay(1000); // Give OS time to notice WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); #endif } @@ -167,4 +165,4 @@ void HAL_SYSTICK_Callback() { if (systick_user_callback) systick_user_callback(); } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp index 7268eed591..44fb93337d 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index bd36562de9..ba8e6bef19 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -224,4 +224,4 @@ static SPISettings spiConfig; #endif // SOFTWARE_SPI -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index 896ec1433f..41081dfb80 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(STM32H7xx) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) && !defined(STM32H7xx) #include "MarlinSPI.h" @@ -165,4 +165,4 @@ uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) return 1; } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 && !STM32H7xx diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 265e8b5ab6..d990d2f428 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -16,7 +16,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" #include "MarlinSerial.h" @@ -101,4 +101,4 @@ void MarlinSerial::_rx_complete_irq(serial_t *obj) { } } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 3353f8c36b..2ba0359cac 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -343,4 +343,4 @@ #endif // !USBD_USE_CDC_COMPOSITE #endif // SDIO_SUPPORT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index 1cf117a056..c0a64c5ea9 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -107,4 +107,4 @@ void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriori } #endif // HAS_SERVOS -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index dfeae9e9e5..05e0d4c420 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -270,4 +270,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // FLASH_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index f811468fb4..9cab90f109 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) /** * Implementation of EEPROM settings in SD Card @@ -88,4 +88,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uin } #endif // SDCARD_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 135bcabde9..c391785234 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -65,4 +65,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // SRAM_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 6aa2f1d360..3346abbe4a 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -75,4 +75,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // USE_WIRED_EEPROM -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 42eecb5e1a..eaffb8cfa4 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfigPre.h" @@ -56,4 +56,4 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } #endif // NEEDS_HARDWARE_PWM -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index 0d55579d88..5056e99d35 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -20,7 +20,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -31,4 +31,4 @@ void FastIO_init() { FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } -#endif +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index 64f2533002..98f75d89f0 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -13,21 +13,24 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) + #include "../../inc/MarlinConfigPre.h" -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && HAS_SD_HOST_DRIVE +#if HAS_SD_HOST_DRIVE #include "msc_sd.h" -#include "../shared/Marduino.h" #include "usbd_core.h" + +#include "../shared/Marduino.h" +#include "../../sd/cardreader.h" + #include #include #define BLOCK_SIZE 512 #define PRODUCT_ID 0x29 -#include "../../sd/cardreader.h" - class Sd2CardUSBMscHandler : public USBMscHandler { public: DiskIODriver* diskIODriver() { @@ -121,4 +124,5 @@ void MSC_SD_init() { USBDevice.begin(); } -#endif // __STM32F1__ && HAS_SD_HOST_DRIVE +#endif // HAS_SD_HOST_DRIVE +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index f99fa46e19..8c59a60f92 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../../inc/MarlinConfig.h" @@ -199,4 +199,4 @@ bool GT911::getPoint(int16_t *x, int16_t *y) { } #endif // TFT_TOUCH_DEVICE_GT911 -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index 87ca2dbbe1..f349eacac3 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../../inc/MarlinConfig.h" @@ -178,4 +178,4 @@ void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou } #endif // HAS_FSMC_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index f2509ce5e4..53e5bd83e0 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../../inc/MarlinConfig.h" @@ -384,4 +384,4 @@ void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou } #endif // HAS_LTDC_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 6bfce81f1a..4e3f894a52 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../../inc/MarlinConfig.h" @@ -240,4 +240,4 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun } #endif // HAS_SPI_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index dffeb6aaf7..d50c24d177 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../../inc/MarlinConfig.h" @@ -167,4 +167,4 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { } #endif // HAS_TFT_XPT2046 -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 03353c2ca3..7806198180 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -319,4 +319,4 @@ static constexpr bool verify_no_timer_conflicts() { // when hovering over it, making it easy to identify the conflicting timers. static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict."); -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index 8fa49ccbcc..e45ab560e6 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -20,7 +20,7 @@ * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfig.h" @@ -114,4 +114,4 @@ uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t b } #endif // USE_OTG_USB_HOST && USBHOST -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 705d649ff5..0e23175fc0 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -16,7 +16,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfigPre.h" @@ -51,4 +51,4 @@ void USB_Hook_init() { } #endif // EMERGENCY_PARSER && USBD_USE_CDC -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index aad0a79a0c..09b403e7f2 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #include "../../inc/MarlinConfigPre.h" @@ -46,4 +46,4 @@ void HAL_watchdog_refresh() { } #endif // USE_WATCHDOG -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index 7725b2c324..f490c83ed8 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -13,9 +13,11 @@ * along with this program. If not, see . * */ +#ifdef __STM32F1__ + #include "../../inc/MarlinConfigPre.h" -#if defined(__STM32F1__) && HAS_SD_HOST_DRIVE +#if HAS_SD_HOST_DRIVE #include "msc_sd.h" #include "SPI.h" @@ -92,4 +94,5 @@ void MSC_SD_init() { #endif } -#endif // __STM32F1__ && HAS_SD_HOST_DRIVE +#endif // HAS_SD_HOST_DRIVE +#endif // __STM32F1__ diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8b5f83f2a4..c595e8b136 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1213,13 +1213,6 @@ void setup() { #endif #endif - #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) - mks_esp_wifi_init(); - WIFISERIAL.begin(WIFI_BAUDRATE); - serial_connect_timeout = millis() + 1000UL; - while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #endif - TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime SETUP_RUN(HAL_init()); diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 05640bce87..abcd7b9480 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -442,7 +442,7 @@ return contains(str, '/') ? findLastPos(findStringEnd(str), '/') : str; } - // Find the first occurence of a character in a string (or return the last position in the string) + // Find the first occurrence of a character in a string (or return the last position in the string) constexpr const char* findFirst(const char *str, const char ch) { return *str == ch || *str == 0 ? (str + 1) : findFirst(str + 1, ch); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 8ae7a150f8..339b337e55 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -288,7 +288,7 @@ // Remove compiler warning on an unused variable #ifndef UNUSED - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) + #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) #define UNUSED(X) (void)X #else #define UNUSED(x) ((void)(x)) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 6d207b86a7..3f2cd32c73 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -61,7 +61,7 @@ static lv_obj_t *scr, *tempText1, *filament_bar; extern uint8_t sel_id; extern bool once_flag, gcode_preview_over; extern int upload_result; -extern uint32_t upload_time; +extern uint32_t upload_time_sec; extern uint32_t upload_size; extern bool temps_update_flag; @@ -406,28 +406,24 @@ void lv_draw_dialog(uint8_t type) { char buf[200]; int _index = 0; - strcpy(buf, DIALOG_UPLOAD_FINISH_EN); + strcpy_P(buf, PSTR(DIALOG_UPLOAD_FINISH_EN)); _index = strlen(buf); - buf[_index] = '\n'; - _index++; - strcat(buf, DIALOG_UPLOAD_SIZE_EN); + buf[_index++] = '\n'; + strcat_P(buf, PSTR(DIALOG_UPLOAD_SIZE_EN)); _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d KBytes\n", (int)(upload_size / 1024)); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d KBytes\n"), (int)(upload_size / 1024)); - strcat(buf, DIALOG_UPLOAD_TIME_EN); + strcat_P(buf, PSTR(DIALOG_UPLOAD_TIME_EN)); _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d s\n", (int)upload_time); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d s\n"), (int)upload_time_sec); - strcat(buf, DIALOG_UPLOAD_SPEED_EN); + strcat_P(buf, PSTR(DIALOG_UPLOAD_SPEED_EN)); _index = strlen(buf); - buf[_index] = ':'; - _index++; - sprintf(&buf[_index], " %d KBytes/s\n", (int)(upload_size / upload_time / 1024)); + buf[_index++] = ':'; + sprintf_P(&buf[_index], PSTR(" %d KBytes/s\n"), (int)(upload_size / upload_time_sec / 1024)); lv_label_set_text(labelDialog, buf); lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index 3297b9da27..7ee2617326 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -29,9 +29,12 @@ #include "tft_lvgl_configuration.h" #include "SPI_TFT.h" -#include "mks_hardware_test.h" #include "../../../inc/MarlinConfig.h" +#if ENABLED(MKS_TEST) + #include "mks_hardware_test.h" +#endif + static lv_obj_t *scr; void lv_draw_error_message(PGM_P const msg) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index e3efb14c28..e3915adeb0 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -47,14 +47,16 @@ static lv_obj_t *scr; static lv_obj_t *labelExt1, *labelFan, *labelZpos, *labelTime; static lv_obj_t *labelPause, *labelStop, *labelOperat; static lv_obj_t *bar1, *bar1ValueText; -static lv_obj_t *buttonPause, *buttonOperat, *buttonStop, *buttonExt1, *buttonExt2, *buttonBedstate, *buttonFanstate, *buttonZpos; +static lv_obj_t *buttonPause, *buttonOperat, *buttonStop, *buttonExt1, *buttonFanstate, *buttonZpos; #if HAS_MULTI_EXTRUDER static lv_obj_t *labelExt2; + static lv_obj_t *buttonExt2; #endif #if HAS_HEATED_BED static lv_obj_t* labelBed; + static lv_obj_t* buttonBedstate; #endif enum { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index 18f125b57d..83aec7613e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -27,7 +27,6 @@ #include "draw_tool.h" #include #include "tft_lvgl_configuration.h" -#include "mks_hardware_test.h" #include "draw_ui.h" #include @@ -40,6 +39,10 @@ #include "draw_touch_calibration.h" #endif +#if ENABLED(MKS_TEST) + #include "mks_hardware_test.h" +#endif + #include #define ICON_POS_Y 38 @@ -48,14 +51,16 @@ extern lv_group_t* g; static lv_obj_t *scr; -static lv_obj_t *labelExt1, *labelExt1Target, *labelFan; +static lv_obj_t *buttonExt1, *labelExt1, *buttonFanstate, *labelFan; -#if HAS_MULTI_EXTRUDER - static lv_obj_t *labelExt2, *labelExt2Target; +#if HAS_MULTI_HOTEND + static lv_obj_t *labelExt2; + static lv_obj_t *buttonExt2; #endif #if HAS_HEATED_BED - static lv_obj_t *labelBed, *labelBedTarget; + static lv_obj_t* labelBed; + static lv_obj_t* buttonBedstate; #endif #if ENABLED(MKS_TEST) @@ -136,18 +141,18 @@ void lv_draw_ready_print() { lv_obj_align(label_tool, buttonTool, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } - e1 = lv_label_create_empty(scr); - lv_obj_set_pos(e1, 20, 20); - sprintf_P(buf, PSTR("e1: %d"), thermalManager.wholeDegHotend(0)); - lv_label_set_text(e1, buf); - + #if HAS_HOTEND + e1 = lv_label_create_empty(scr); + lv_obj_set_pos(e1, 20, 20); + sprintf_P(buf, PSTR("e1: %d"), thermalManager.wholeDegHotend(0)); + lv_label_set_text(e1, buf); + #endif #if HAS_MULTI_HOTEND e2 = lv_label_create_empty(scr); lv_obj_set_pos(e2, 20, 45); sprintf_P(buf, PSTR("e1: %d"), thermalManager.wholeDegHotend(1)); lv_label_set_text(e2, buf); #endif - #if HAS_HEATED_BED bed = lv_label_create_empty(scr); lv_obj_set_pos(bed, 20, 95); @@ -178,72 +183,27 @@ void lv_draw_ready_print() { lv_label_set_text(det_info, " "); } else { - lv_big_button_create(scr, "F:/bmp_tool.bin", main_menu.tool, 20, 180, event_handler, ID_TOOL); - lv_big_button_create(scr, "F:/bmp_set.bin", main_menu.set, 180, 180, event_handler, ID_SET); - lv_big_button_create(scr, "F:/bmp_printing.bin", main_menu.print, 340, 180, event_handler, ID_PRINT); + lv_big_button_create(scr, "F:/bmp_tool.bin", main_menu.tool, 20, 150, event_handler, ID_TOOL); + lv_big_button_create(scr, "F:/bmp_set.bin", main_menu.set, 180, 150, event_handler, ID_SET); + lv_big_button_create(scr, "F:/bmp_printing.bin", main_menu.print, 340, 150, event_handler, ID_PRINT); // Monitoring - lv_obj_t *buttonExt1 = lv_big_button_create(scr, "F:/bmp_ext1_state.bin", " ", 55, ICON_POS_Y, event_handler, ID_INFO_EXT); - #if HAS_MULTI_EXTRUDER - lv_obj_t *buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 163, ICON_POS_Y, event_handler, ID_INFO_EXT); - #if HAS_HEATED_BED - lv_obj_t *buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", 271, ICON_POS_Y, event_handler, ID_INFO_BED); - #endif - #else - #if HAS_HEATED_BED - lv_obj_t *buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", 210, ICON_POS_Y, event_handler, ID_INFO_BED); - #endif + #if HAS_HOTEND + buttonExt1 = lv_big_button_create(scr, "F:/bmp_ext1_state.bin", " ", 55, ICON_POS_Y, event_handler, ID_INFO_EXT); #endif - - lv_obj_t *buttonFanstate = lv_big_button_create(scr, "F:/bmp_fan_state.bin", " ", 380, ICON_POS_Y, event_handler, ID_INFO_FAN); - - labelExt1 = lv_label_create(scr, 55, LABEL_MOD_Y, nullptr); - labelExt1Target = lv_label_create(scr, 55, LABEL_MOD_Y, nullptr); - - #if HAS_MULTI_EXTRUDER - labelExt2 = lv_label_create(scr, 163, LABEL_MOD_Y, nullptr); - labelExt2Target = lv_label_create(scr, 163, LABEL_MOD_Y, nullptr); - #if HAS_HEATED_BED - labelBed = lv_label_create(scr, 271, LABEL_MOD_Y, nullptr); - labelBedTarget = lv_label_create(scr, 271, LABEL_MOD_Y, nullptr); - #endif - #else - #if HAS_HEATED_BED - labelBed = lv_label_create(scr, 210, LABEL_MOD_Y, nullptr); - labelBedTarget = lv_label_create(scr, 210, LABEL_MOD_Y, nullptr); - #endif + #if HAS_MULTI_HOTEND + buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 163, ICON_POS_Y, event_handler, ID_INFO_EXT); #endif - - labelFan = lv_label_create(scr, 380, 80, nullptr); - - itoa(thermalManager.degHotend(0), buf, 10); - lv_label_set_text(labelExt1, buf); - lv_obj_align(labelExt1, buttonExt1, LV_ALIGN_CENTER, 0, LABEL_MOD_Y); - sprintf_P(buf, PSTR("-> %d"), thermalManager.degTargetHotend(0)); - lv_label_set_text(labelExt1Target, buf); - lv_obj_align(labelExt1Target, buttonExt1, LV_ALIGN_CENTER, 0, TARGET_LABEL_MOD_Y); - - #if HAS_MULTI_EXTRUDER - itoa(thermalManager.degHotend(1), buf, 10); - lv_label_set_text(labelExt2, buf); - lv_obj_align(labelExt2, buttonExt2, LV_ALIGN_CENTER, 0, LABEL_MOD_Y); - sprintf_P(buf, PSTR("-> %d"), thermalManager.degTargetHotend(1)); - lv_label_set_text(labelExt2Target, buf); - lv_obj_align(labelExt2Target, buttonExt2, LV_ALIGN_CENTER, 0, TARGET_LABEL_MOD_Y); - #endif - #if HAS_HEATED_BED - itoa(thermalManager.degBed(), buf, 10); - lv_label_set_text(labelBed, buf); - lv_obj_align(labelBed, buttonBedstate, LV_ALIGN_CENTER, 0, LABEL_MOD_Y); - sprintf_P(buf, PSTR("-> %d"), thermalManager.degTargetBed()); - lv_label_set_text(labelBedTarget, buf); - lv_obj_align(labelBedTarget, buttonBedstate, LV_ALIGN_CENTER, 0, TARGET_LABEL_MOD_Y); + buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", TERN(HAS_MULTI_HOTEND, 271, 210), ICON_POS_Y, event_handler, ID_INFO_BED); #endif - sprintf_P(buf, PSTR("%d%%"), (int)thermalManager.fanSpeedPercent(0)); - lv_label_set_text(labelFan, buf); - lv_obj_align(labelFan, buttonFanstate, LV_ALIGN_CENTER, 0, LABEL_MOD_Y); + TERN_(HAS_HOTEND, labelExt1 = lv_label_create_empty(scr)); + TERN_(HAS_MULTI_HOTEND, labelExt2 = lv_label_create_empty(scr)); + TERN_(HAS_HEATED_BED, labelBed = lv_label_create_empty(scr)); + TERN_(HAS_FAN, labelFan = lv_label_create_empty(scr)); + + lv_temp_refr(); } #if ENABLED(TOUCH_SCREEN_CALIBRATION) @@ -256,17 +216,25 @@ void lv_draw_ready_print() { } void lv_temp_refr() { + #if HAS_HOTEND + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); + lv_label_set_text(labelExt1, public_buf_l); + lv_obj_align(labelExt1, buttonExt1, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif + #if HAS_MULTI_HOTEND + sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); + lv_label_set_text(labelExt2, public_buf_l); + lv_obj_align(labelExt2, buttonExt2, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + #endif #if HAS_HEATED_BED sprintf(public_buf_l, printing_menu.bed_temp, thermalManager.wholeDegBed(), thermalManager.degTargetBed()); lv_label_set_text(labelBed, public_buf_l); + lv_obj_align(labelBed, buttonBedstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); #endif - - sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); - lv_label_set_text(labelExt1, public_buf_l); - - #if HAS_MULTI_EXTRUDER - sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); - lv_label_set_text(labelExt2, public_buf_l); + #if HAS_FAN + sprintf_P(public_buf_l, PSTR("%d%%"), (int)thermalManager.fanSpeedPercent(0)); + lv_label_set_text(labelFan, public_buf_l); + lv_obj_align(labelFan, buttonFanstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 727120c183..30e08e03ed 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -30,7 +30,6 @@ #include "pic_manager.h" #include "draw_ui.h" -#include "mks_hardware_test.h" #include @@ -52,6 +51,10 @@ #include "draw_touch_calibration.h" #endif +#if ENABLED(MKS_TEST) + #include "mks_hardware_test.h" +#endif + CFG_ITMES gCfgItems; UI_CFG uiCfg; DISP_STATE_STACK disp_state_stack; @@ -202,27 +205,27 @@ void ui_cfg_init() { #if ENABLED(MKS_WIFI_MODULE) memset(&wifiPara, 0, sizeof(wifiPara)); memset(&ipPara, 0, sizeof(ipPara)); - strcpy(wifiPara.ap_name, WIFI_AP_NAME); - strcpy(wifiPara.keyCode, WIFI_KEY_CODE); + strcpy_P(wifiPara.ap_name, PSTR(WIFI_AP_NAME)); + strcpy_P(wifiPara.keyCode, PSTR(WIFI_KEY_CODE)); //client - strcpy(ipPara.ip_addr, IP_ADDR); - strcpy(ipPara.mask, IP_MASK); - strcpy(ipPara.gate, IP_GATE); - strcpy(ipPara.dns, IP_DNS); + strcpy_P(ipPara.ip_addr, PSTR(IP_ADDR)); + strcpy_P(ipPara.mask, PSTR(IP_MASK)); + strcpy_P(ipPara.gate, PSTR(IP_GATE)); + strcpy_P(ipPara.dns, PSTR(IP_DNS)); ipPara.dhcp_flag = IP_DHCP_FLAG; //AP - strcpy(ipPara.dhcpd_ip, AP_IP_ADDR); - strcpy(ipPara.dhcpd_mask, AP_IP_MASK); - strcpy(ipPara.dhcpd_gate, AP_IP_GATE); - strcpy(ipPara.dhcpd_dns, AP_IP_DNS); - strcpy(ipPara.start_ip_addr, IP_START_IP); - strcpy(ipPara.end_ip_addr, IP_END_IP); + strcpy_P(ipPara.dhcpd_ip, PSTR(AP_IP_ADDR)); + strcpy_P(ipPara.dhcpd_mask, PSTR(AP_IP_MASK)); + strcpy_P(ipPara.dhcpd_gate, PSTR(AP_IP_GATE)); + strcpy_P(ipPara.dhcpd_dns, PSTR(AP_IP_DNS)); + strcpy_P(ipPara.start_ip_addr, PSTR(IP_START_IP)); + strcpy_P(ipPara.end_ip_addr, PSTR(IP_END_IP)); ipPara.dhcpd_flag = AP_IP_DHCP_FLAG; - strcpy((char*)uiCfg.cloud_hostUrl, "baizhongyun.cn"); + strcpy_P((char*)uiCfg.cloud_hostUrl, PSTR("baizhongyun.cn")); uiCfg.cloud_port = 10086; #endif @@ -1362,7 +1365,10 @@ void print_time_count() { void LV_TASK_HANDLER() { lv_task_handler(); - if (mks_test_flag == 0x1E) mks_hardware_test(); + + #if ENABLED(MKS_TEST) + if (mks_test_flag == 0x1E) mks_hardware_test(); + #endif TERN_(HAS_GCODE_PREVIEW, disp_pre_gcode(2, 36)); diff --git a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp index df48cbec0a..f3c87c03c4 100644 --- a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfigPre.h" -#if HAS_TFT_LVGL_UI +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" -#if ENABLED(MKS_WIFI_MODULE) - #include "draw_ui.h" #include "wifiSerial.h" @@ -46,15 +46,15 @@ #define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); void __irq_usart1() { - if ((USART1_BASE->CR1 & USART_CR1_RXNEIE) && (USART1_BASE->SR & USART_SR_RXNE)) - WRITE(WIFI_IO1_PIN, HIGH); + if ((USART1_BASE->CR1 & USART_CR1_RXNEIE) && (USART1_BASE->SR & USART_SR_RXNE)) + WRITE(WIFI_IO1_PIN, HIGH); - WIFISERIAL.wifi_usart_irq(USART1_BASE); + WIFISERIAL.wifi_usart_irq(USART1_BASE); } #ifdef __cplusplus } /* C-declarations for C++ */ #endif -#endif // MKS_WIFI_MODULE -#endif // HAS_TFT_LVGL_UI +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // __STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp index bcb3cdb6a2..125f8be0f6 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp @@ -27,7 +27,6 @@ #include "tft_lvgl_configuration.h" #include "draw_ready_print.h" -#include "mks_hardware_test.h" #include "draw_ui.h" #include "pic_manager.h" #include @@ -36,51 +35,47 @@ #include "../../../module/temperature.h" #include "../../../sd/cardreader.h" -uint8_t pw_det_sta, pw_off_sta, mt_det_sta, mt_det3_sta; -#if PIN_EXISTS(MT_DET_2) - uint8_t mt_det2_sta; -#endif -uint8_t endstopx1_sta, endstopx2_sta, endstopy1_sta, endstopy2_sta, endstopz1_sta, endstopz2_sta; -void test_gpio_readlevel_L() { - #if ENABLED(MKS_TEST) - volatile uint32_t itest; +#if ENABLED(MKS_TEST) + + #include "mks_hardware_test.h" + + bool pw_det_sta, pw_off_sta, mt_det_sta; + #if PIN_EXISTS(MT_DET_2) + bool mt_det2_sta; + #endif + bool endstopx1_sta, endstopx2_sta, endstopy1_sta, endstopy2_sta, endstopz1_sta, endstopz2_sta; + + void test_gpio_readlevel_L() { WRITE(WIFI_IO0_PIN, HIGH); - itest = 10000; - while (itest--); - pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 0); - pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 0); - mt_det_sta = (READ(MT_DET_1_PIN) == 0); + delay(10); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == LOW); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == LOW); + mt_det_sta = (READ(MT_DET_1_PIN) == LOW); #if PIN_EXISTS(MT_DET_2) - mt_det2_sta = (READ(MT_DET_2_PIN) == 0); + mt_det2_sta = (READ(MT_DET_2_PIN) == LOW); #endif - endstopx1_sta = (READ(X_MIN_PIN) == 0); - endstopy1_sta = (READ(Y_MIN_PIN) == 0); - endstopz1_sta = (READ(Z_MIN_PIN) == 0); - endstopz2_sta = (READ(Z_MAX_PIN) == 0); - #endif -} + endstopx1_sta = (READ(X_MIN_PIN) == LOW); + endstopy1_sta = (READ(Y_MIN_PIN) == LOW); + endstopz1_sta = (READ(Z_MIN_PIN) == LOW); + endstopz2_sta = (READ(Z_MAX_PIN) == LOW); + } -void test_gpio_readlevel_H() { - #if ENABLED(MKS_TEST) - volatile uint32_t itest; + void test_gpio_readlevel_H() { WRITE(WIFI_IO0_PIN, LOW); - itest = 10000; - while (itest--); - pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 1); - pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 1); - mt_det_sta = (READ(MT_DET_1_PIN) == 1); + delay(10); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == HIGH); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == HIGH); + mt_det_sta = (READ(MT_DET_1_PIN) == HIGH); #if PIN_EXISTS(MT_DET_2) - mt_det2_sta = (READ(MT_DET_2_PIN) == 1); + mt_det2_sta = (READ(MT_DET_2_PIN) == HIGH); #endif - endstopx1_sta = (READ(X_MIN_PIN) == 1); - endstopy1_sta = (READ(Y_MIN_PIN) == 1); - endstopz1_sta = (READ(Z_MIN_PIN) == 1); - endstopz2_sta = (READ(Z_MAX_PIN) == 1); - #endif -} + endstopx1_sta = (READ(X_MIN_PIN) == HIGH); + endstopy1_sta = (READ(Y_MIN_PIN) == HIGH); + endstopz1_sta = (READ(Z_MIN_PIN) == HIGH); + endstopz2_sta = (READ(Z_MAX_PIN) == HIGH); + } -void init_test_gpio() { - #ifdef MKS_TEST + void init_test_gpio() { SET_INPUT_PULLUP(X_MIN_PIN); SET_INPUT_PULLUP(Y_MIN_PIN); SET_INPUT_PULLUP(Z_MIN_PIN); @@ -102,7 +97,7 @@ void init_test_gpio() { SET_OUTPUT(Y_ENABLE_PIN); SET_OUTPUT(Z_ENABLE_PIN); SET_OUTPUT(E0_ENABLE_PIN); - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) SET_OUTPUT(E1_ENABLE_PIN); #endif @@ -110,11 +105,11 @@ void init_test_gpio() { WRITE(Y_ENABLE_PIN, LOW); WRITE(Z_ENABLE_PIN, LOW); WRITE(E0_ENABLE_PIN, LOW); - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(E1_ENABLE_PIN, LOW); #endif - #if MB(MKS_ROBIN_E3P) + #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) SET_INPUT_PULLUP(PA1); SET_INPUT_PULLUP(PA3); SET_INPUT_PULLUP(PC2); @@ -123,68 +118,56 @@ void init_test_gpio() { SET_INPUT_PULLUP(PE6); SET_INPUT_PULLUP(PE7); #endif - #endif -} + } -void mks_test_beeper() { - #ifdef MKS_TEST + void mks_test_beeper() { WRITE(BEEPER_PIN, HIGH); delay(100); WRITE(BEEPER_PIN, LOW); delay(100); - #endif -} + } -void mks_gpio_test() { - #if ENABLED(MKS_TEST) + void mks_gpio_test() { init_test_gpio(); test_gpio_readlevel_L(); test_gpio_readlevel_H(); test_gpio_readlevel_L(); - if ((pw_det_sta == 1) - && (pw_off_sta == 1) - && (mt_det_sta == 1) + if (pw_det_sta && pw_off_sta && mt_det_sta #if PIN_EXISTS(MT_DET_2) - && (mt_det2_sta == 1) + && mt_det2_sta #endif - #if MB(MKS_ROBIN_E3P) - && (READ(PA1) == 0) - && (READ(PA3) == 0) - && (READ(PC2) == 0) - && (READ(PD8) == 0) - && (READ(PE5) == 0) - && (READ(PE6) == 0) - && (READ(PE7) == 0) + #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) + && (READ(PA1) == LOW) + && (READ(PA3) == LOW) + && (READ(PC2) == LOW) + && (READ(PD8) == LOW) + && (READ(PE5) == LOW) + && (READ(PE6) == LOW) + && (READ(PE7) == LOW) #endif ) disp_det_ok(); else disp_det_error(); - if ( (endstopx1_sta == 1) - && (endstopy1_sta == 1) - && (endstopz1_sta == 1) - && (endstopz2_sta == 1) - ) + if (endstopx1_sta && endstopy1_sta && endstopz1_sta && endstopz2_sta) disp_Limit_ok(); else disp_Limit_error(); - #endif -} + } -void mks_hardware_test() { - #if ENABLED(MKS_TEST) + void mks_hardware_test() { if (millis() % 2000 < 1000) { WRITE(X_DIR_PIN, LOW); WRITE(Y_DIR_PIN, LOW); WRITE(Z_DIR_PIN, LOW); WRITE(E0_DIR_PIN, LOW); - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(E1_DIR_PIN, LOW); #endif thermalManager.fan_speed[0] = 255; - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(HEATER_1_PIN, HIGH); // HE1 #endif WRITE(HEATER_0_PIN, HIGH); // HE0 @@ -195,21 +178,18 @@ void mks_hardware_test() { WRITE(Y_DIR_PIN, HIGH); WRITE(Z_DIR_PIN, HIGH); WRITE(E0_DIR_PIN, HIGH); - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(E1_DIR_PIN, HIGH); #endif thermalManager.fan_speed[0] = 0; - #if !MB(MKS_ROBIN_E3P) + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(HEATER_1_PIN, LOW); // HE1 #endif WRITE(HEATER_0_PIN, LOW); // HE0 WRITE(HEATER_BED_PIN, LOW); // HOT-BED } - if ( (endstopx1_sta == 1) && (endstopx2_sta == 1) - && (endstopy1_sta == 1) && (endstopy2_sta == 1) - && (endstopz1_sta == 1) && (endstopz2_sta == 1) - ) { + if (endstopx1_sta && endstopx2_sta && endstopy1_sta && endstopy2_sta && endstopz1_sta && endstopz2_sta) { // nothing here } else { @@ -217,9 +197,9 @@ void mks_hardware_test() { if (disp_state == PRINT_READY_UI) mks_disp_test(); + } - #endif -} +#endif // MKS_TEST static const uint16_t ASCII_Table_16x24[] PROGMEM = { // Space ' ' diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h index 0e2d8096ba..1b46d4b0e6 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h @@ -24,10 +24,12 @@ #include void mks_gpio_test(); +void mks_hardware_test(); +void mks_test_get(); + void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint16_t bkColor); void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); -void mks_hardware_test(); void disp_assets_update(); void disp_assets_update_progress(const char *msg); -void mks_test_get(); + extern uint8_t mks_test_flag; diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index da7b1929ce..03e408e32a 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -27,7 +27,10 @@ #include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" -#include "mks_hardware_test.h" + +#if ENABLED(MKS_TEST) + #include "mks_hardware_test.h" +#endif #include "SPIFlashStorage.h" #include "../../../libs/W25Qxx.h" diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index b618a01957..5e359c4091 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -158,19 +158,12 @@ void filament_pin_setup() { } void filament_check() { - const int FIL_DELAY = 20; + #if ANY_PIN(MT_DET_1, MT_DET_2, MT_DET_3) + const int FIL_DELAY = 20; + #endif #if PIN_EXISTS(MT_DET_1) static int fil_det_count_1 = 0; - if (!READ(MT_DET_1_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (READ(MT_DET_1_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (fil_det_count_1 > 0) - fil_det_count_1--; - - if (!READ(MT_DET_1_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_1++; - else if (READ(MT_DET_1_PIN) && MT_DET_PIN_INVERTING) + if (READ(MT_DET_1_PIN) == MT_DET_PIN_INVERTING) fil_det_count_1++; else if (fil_det_count_1 > 0) fil_det_count_1--; @@ -178,16 +171,7 @@ void filament_check() { #if PIN_EXISTS(MT_DET_2) static int fil_det_count_2 = 0; - if (!READ(MT_DET_2_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (READ(MT_DET_2_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (fil_det_count_2 > 0) - fil_det_count_2--; - - if (!READ(MT_DET_2_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_2++; - else if (READ(MT_DET_2_PIN) && MT_DET_PIN_INVERTING) + if (READ(MT_DET_2_PIN) == MT_DET_PIN_INVERTING) fil_det_count_2++; else if (fil_det_count_2 > 0) fil_det_count_2--; @@ -195,16 +179,7 @@ void filament_check() { #if PIN_EXISTS(MT_DET_3) static int fil_det_count_3 = 0; - if (!READ(MT_DET_3_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (READ(MT_DET_3_PIN) && MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (fil_det_count_3 > 0) - fil_det_count_3--; - - if (!READ(MT_DET_3_PIN) && !MT_DET_PIN_INVERTING) - fil_det_count_3++; - else if (READ(MT_DET_3_PIN) && MT_DET_PIN_INVERTING) + if (READ(MT_DET_3_PIN) == MT_DET_PIN_INVERTING) fil_det_count_3++; else if (fil_det_count_3 > 0) fil_det_count_3--; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 84e3040e84..7f84277ef0 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -45,6 +45,14 @@ XPT2046 touch; #include "../../../feature/powerloss.h" #endif +#if HAS_SERVOS + #include "../../../module/servo.h" +#endif + +#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) + #include "../../../module/probe.h" +#endif + #if ENABLED(TOUCH_SCREEN_CALIBRATION) #include "../../tft_io/touch_calibration.h" #include "draw_touch_calibration.h" @@ -131,10 +139,9 @@ void tft_lvgl_init() { #if ENABLED(SDSUPPORT) UpdateAssets(); watchdog_refresh(); // LVGL init takes time + mks_test_get(); #endif - mks_test_get(); - touch.Init(); lv_init(); @@ -193,8 +200,12 @@ void tft_lvgl_init() { filament_pin_setup(); lv_encoder_pin_init(); - TERN_(MKS_WIFI_MODULE, mks_wifi_firmware_update()); - + #if ENABLED(MKS_WIFI_MODULE) + mks_esp_wifi_init(); + mks_wifi_firmware_update(); + #endif + TERN_(HAS_SERVOS, servo_init()); + TERN_(HAS_Z_SERVO_PROBE, probe.servo_probe_init()); bool ready = true; #if ENABLED(POWER_LOSS_RECOVERY) recovery.load(); @@ -207,16 +218,22 @@ void tft_lvgl_init() { uiCfg.print_state = REPRINTING; - strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); - card.printLongPath(public_buf_m); - strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); + #if ENABLED(LONG_FILENAME_HOST_SUPPORT) + strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); + card.printLongPath(public_buf_m); + strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); + #else + strncpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0])); + #endif lv_draw_printing(); } #endif if (ready) lv_draw_ready_print(); - if (mks_test_flag == 0x1E) mks_gpio_test(); + #if ENABLED(MKS_TEST) + if (mks_test_flag == 0x1E) mks_gpio_test(); + #endif } void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) { diff --git a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp index b34942303a..0771a31cb4 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp @@ -58,6 +58,8 @@ pause_msg_def pause_msg_menu; eeprom_def eeprom_menu; media_select_menu_def media_select_menu; +// TODO: Make all strings PSTR and update accessors for the benefit of AVR + machine_common_def machine_menu; void machine_setting_disp() { if (gCfgItems.language == LANG_SIMPLE_CHINESE) { @@ -1093,8 +1095,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_CN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_CN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_CN; - eeprom_menu.readTips = EEPROM_READ_TIPS_CN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_CN; + eeprom_menu.readTips = EEPROM_READ_TIPS_CN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_CN; break; #if 1 @@ -1337,8 +1339,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_T_CN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_T_CN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_T_CN; - eeprom_menu.readTips = EEPROM_READ_TIPS_T_CN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_T_CN; + eeprom_menu.readTips = EEPROM_READ_TIPS_T_CN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_T_CN; break; case LANG_ENGLISH: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_EN; @@ -1571,8 +1573,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_EN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_EN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_EN; - eeprom_menu.readTips = EEPROM_READ_TIPS_EN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; + eeprom_menu.readTips = EEPROM_READ_TIPS_EN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; break; case LANG_RUSSIAN: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_RU; @@ -1896,8 +1898,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_RU; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_RU; eeprom_menu.storeTips = EEPROM_STORE_TIPS_RU; - eeprom_menu.readTips = EEPROM_READ_TIPS_RU; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_RU; + eeprom_menu.readTips = EEPROM_READ_TIPS_RU; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_RU; break; case LANG_SPANISH: common_menu.dialog_confirm_title = TITLE_DIALOG_CONFIRM_SP; @@ -2133,8 +2135,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_SP; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_SP; eeprom_menu.storeTips = EEPROM_STORE_TIPS_SP; - eeprom_menu.readTips = EEPROM_READ_TIPS_SP; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_SP; + eeprom_menu.readTips = EEPROM_READ_TIPS_SP; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_SP; break; #endif // if 1 @@ -2367,8 +2369,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_FR; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_FR; eeprom_menu.storeTips = EEPROM_STORE_TIPS_FR; - eeprom_menu.readTips = EEPROM_READ_TIPS_FR; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_FR; + eeprom_menu.readTips = EEPROM_READ_TIPS_FR; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_FR; break; case LANG_ITALY: @@ -2600,8 +2602,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_IT; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_IT; eeprom_menu.storeTips = EEPROM_STORE_TIPS_IT; - eeprom_menu.readTips = EEPROM_READ_TIPS_IT; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_IT; + eeprom_menu.readTips = EEPROM_READ_TIPS_IT; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_IT; break; #endif // if 1 @@ -2836,8 +2838,8 @@ void disp_language_init() { eeprom_menu.read = EEPROM_SETTINGS_READ_EN; eeprom_menu.revert = EEPROM_SETTINGS_REVERT_EN; eeprom_menu.storeTips = EEPROM_STORE_TIPS_EN; - eeprom_menu.readTips = EEPROM_READ_TIPS_EN; - eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; + eeprom_menu.readTips = EEPROM_READ_TIPS_EN; + eeprom_menu.revertTips = EEPROM_REVERT_TIPS_EN; break; } } diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial.h index fcc35a6a65..1a3e9aae9b 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial.h +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial.h @@ -21,10 +21,6 @@ */ #pragma once -#include "tft_lvgl_configuration.h" - -#if ENABLED(MKS_WIFI_MODULE) - #ifdef SERIAL_PORT_2 #error "SERIAL_PORT_2 must be disabled with TFT_LVGL_UI* and MKS_WIFI_MODULE." #endif @@ -33,70 +29,16 @@ #define WIFI_UPLOAD_BAUDRATE 1958400 #define USART_SAFE_INSERT -#define WIFI_RX_BUF_SIZE (1024+1) +#define WIFI_RX_BUF_SIZE (1024) +#define WIFI_TX_BUF_SIZE (64) -#include -#include -#include -#include -#include -#include +#include "tft_lvgl_configuration.h" -#define DEFINE_WFSERIAL(name, n)\ - WifiSerial name(USART##n, \ - BOARD_USART##n##_TX_PIN, \ - BOARD_USART##n##_RX_PIN) - -class WifiSerial { - public: - uint8 wifiRxBuf[WIFI_RX_BUF_SIZE]; - - public: - WifiSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin); - - /* Set up/tear down */ - void begin(uint32 baud); - void begin(uint32 baud,uint8_t config); - void end(); - int available(); - int read(); - int write(uint8_t); - inline void wifi_usart_irq(usart_reg_map *regs) { - /* Handling RXNEIE and TXEIE interrupts. - * RXNE signifies availability of a byte in DR. - * - * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. - * We enable RXNEIE. - */ - if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { - #ifdef USART_SAFE_INSERT - /* If the buffer is full and the user defines USART_SAFE_INSERT, - * ignore new bytes. */ - rb_safe_insert(this->usart_device->rb, (uint8)regs->DR); - #else - /* By default, push bytes around in the ring buffer. */ - rb_push_insert(this->usart_device->rb, (uint8)regs->DR); - #endif - } - /* TXE signifies readiness to send a byte to DR. */ - if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { - if (!rb_is_empty(this->usart_device->wb)) - regs->DR=rb_remove(this->usart_device->wb); - else - regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE - } - } - - int wifi_rb_is_full(); - - struct usart_dev *usart_device; - private: - uint8 tx_pin; - uint8 rx_pin; -}; +#ifdef __STM32F1__ + #include "wifiSerial_STM32F1.h" +#else + #include "wifiSerial_STM32.h" +#endif extern WifiSerial WifiSerial1; - -#define WIFISERIAL WifiSerial1 - -#endif // MKS_WIFI_MODULE +#define WIFISERIAL WifiSerial1 diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp new file mode 100644 index 0000000000..39d8562676 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -0,0 +1,352 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) + +#include "tft_lvgl_configuration.h" + +#include "draw_ui.h" +#include "wifiSerial.h" + +WifiSerial WifiSerial1(USART1); + +void WifiSerial::setRx(uint32_t _rx) { _serial.pin_rx = digitalPinToPinName(_rx); } +void WifiSerial::setTx(uint32_t _tx) { _serial.pin_tx = digitalPinToPinName(_tx); } +void WifiSerial::setRx(PinName _rx) { _serial.pin_rx = _rx; } +void WifiSerial::setTx(PinName _tx) { _serial.pin_tx = _tx; } + +void WifiSerial::init(PinName _rx, PinName _tx) { + _serial.pin_rx = (_rx == _tx) ? NC : _rx; + _serial.pin_tx = _tx; + _serial.rx_buff = wifiRxBuf; + _serial.rx_head = 0; + _serial.rx_tail = 0; + _serial.tx_buff = wifiTxBuf; + _serial.tx_head = 0; + _serial.tx_tail = 0; +} + +WifiSerial::WifiSerial(void *peripheral) { + // If PIN_SERIALy_RX is not defined assume half-duplex + _serial.pin_rx = NC; + // If Serial is defined in variant set + // the Rx/Tx pins for com port if defined + #if defined(Serial) && defined(PIN_SERIAL_TX) + if ((void *)this == (void *)&Serial) { + #ifdef PIN_SERIAL_RX + setRx(PIN_SERIAL_RX); + #endif + setTx(PIN_SERIAL_TX); + } else + #endif + #if defined(PIN_SERIAL1_TX) && defined(USART1_BASE) + if (peripheral == USART1) { + #ifdef PIN_SERIAL1_RX + setRx(PIN_SERIAL1_RX); + #endif + setTx(PIN_SERIAL1_TX); + } else + #endif + #if defined(PIN_SERIAL2_TX) && defined(USART2_BASE) + if (peripheral == USART2) { + #ifdef PIN_SERIAL2_RX + setRx(PIN_SERIAL2_RX); + #endif + setTx(PIN_SERIAL2_TX); + } else + #endif + #if defined(PIN_SERIAL3_TX) && defined(USART3_BASE) + if (peripheral == USART3) { + #ifdef PIN_SERIAL3_RX + setRx(PIN_SERIAL3_RX); + #endif + setTx(PIN_SERIAL3_TX); + } else + #endif + #ifdef PIN_SERIAL4_TX + if (false + #ifdef USART4_BASE + || peripheral == USART4 + #elif defined(UART4_BASE) + || peripheral == UART4 + #endif + ) { + #ifdef PIN_SERIAL4_RX + setRx(PIN_SERIAL4_RX); + #endif + setTx(PIN_SERIAL4_TX); + } else + #endif + #ifdef PIN_SERIAL5_TX + if (false + #ifdef USART5_BASE + || peripheral == USART5 + #elif defined(UART5_BASE) + || peripheral == UART5 + #endif + ) { + #ifdef PIN_SERIAL5_RX + setRx(PIN_SERIAL5_RX); + #endif + setTx(PIN_SERIAL5_TX); + } else + #endif + #if defined(PIN_SERIAL6_TX) && defined(USART6_BASE) + if (peripheral == USART6) { + #ifdef PIN_SERIAL6_RX + setRx(PIN_SERIAL6_RX); + #endif + setTx(PIN_SERIAL6_TX); + } else + #endif + #ifdef PIN_SERIAL7_TX + if (false + #ifdef USART7_BASE + || peripheral == USART7 + #elif defined(UART7_BASE) + || peripheral == UART7 + #endif + ) { + #ifdef PIN_SERIAL7_RX + setRx(PIN_SERIAL7_RX); + #endif + setTx(PIN_SERIAL7_TX); + } else + #endif + #ifdef PIN_SERIAL8_TX + if (false + #ifdef USART8_BASE + || peripheral == USART8 + #elif defined(UART8_BASE) + || peripheral == UART8 + #endif + ) { + #ifdef PIN_SERIAL8_RX + setRx(PIN_SERIAL8_RX); + #endif + setTx(PIN_SERIAL8_TX); + } else + #endif + #if defined(PIN_SERIAL9_TX) && defined(UART9_BASE) + if (peripheral == UART9) { + #ifdef PIN_SERIAL9_RX + setRx(PIN_SERIAL9_RX); + #endif + setTx(PIN_SERIAL9_TX); + } else + #endif + #ifdef PIN_SERIAL10_TX + if (false + #ifdef USART10_BASE + || peripheral == USART10 + #elif defined(UART10_BASE) + || peripheral == UART10 + #endif + ) { + #ifdef PIN_SERIAL10_RX + setRx(PIN_SERIAL10_RX); + #endif + setTx(PIN_SERIAL10_TX); + } else + #endif + #if defined(PIN_SERIALLP1_TX) && defined(LPUART1_BASE) + if (peripheral == LPUART1) { + #ifdef PIN_SERIALLP1_RX + setRx(PIN_SERIALLP1_RX); + #endif + setTx(PIN_SERIALLP1_TX); + } else + #endif + // else get the pins of the first peripheral occurrence in PinMap + { + _serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX); + _serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX); + } + //if (halfDuplex == HALF_DUPLEX_ENABLED) _serial.pin_rx = NC; + init(_serial.pin_rx, _serial.pin_tx); +} + +void WifiSerial::flush() { + // If we have never written a byte, no need to flush. This special + // case is needed since there is no way to force the TXC (transmit + // complete) bit to 1 during initialization + if (!_written) return; + + while ((_serial.tx_head != _serial.tx_tail)) { + // nop, the interrupt handler will free up space for us + } + // If we get here, nothing is queued anymore (DRIE is disabled) and + // the hardware finished tranmission (TXC is set). +} + +bool WifiSerial::isHalfDuplex() const { return _serial.pin_rx == NC; } + +void WifiSerial::enableHalfDuplexRx() { + if (isHalfDuplex()) { + // In half-duplex mode we have to wait for all TX characters to + // be transmitted before we can receive data. + flush(); + if (!_rx_enabled) { + _rx_enabled = true; + uart_enable_rx(&_serial); + } + } +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +void WifiSerial::_rx_complete_irq(serial_t *obj) { + // No Parity error, read byte and store it in the buffer if there is room + unsigned char c; + + if (uart_getc(obj, &c) == 0) { + + WRITE(WIFI_IO1_PIN, HIGH); + + rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % WIFI_RX_BUF_SIZE; + + // if we should be storing the received character into the location + // just before the tail (meaning that the head would advance to the + // current location of the tail), we're about to overflow the buffer + // and so we don't write the character or advance the head. + if (i != obj->rx_tail) { + obj->rx_buff[obj->rx_head] = c; + obj->rx_head = i; + } + } +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +int WifiSerial::_tx_complete_irq(serial_t *obj) { + // If interrupts are enabled, there must be more data in the output + // buffer. Send the next byte + obj->tx_tail = (obj->tx_tail + 1) % WIFI_TX_BUF_SIZE; + + return (obj->tx_head == obj->tx_tail) ? -1 : 0; +} + +void WifiSerial::begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + +void WifiSerial::begin(unsigned long baud, byte config) { + uint32_t databits = 0, stopbits = 0, parity = 0; + + _baud = baud; + _config = config; + + // Manage databits + switch (config & 0x07) { + case 0x02: databits = 6; break; + case 0x04: databits = 7; break; + case 0x06: databits = 8; break; + default: databits = 0; break; + } + + if ((config & 0x30) == 0x30) { + parity = UART_PARITY_ODD; + databits++; + } + else if ((config & 0x20) == 0x20) { + parity = UART_PARITY_EVEN; + databits++; + } + else + parity = UART_PARITY_NONE; + + stopbits = ((config & 0x08) == 0x08) ? UART_STOPBITS_2 : UART_STOPBITS_1; + + switch (databits) { + #ifdef UART_WORDLENGTH_7B + case 7: databits = UART_WORDLENGTH_7B; break; + #endif + case 8: databits = UART_WORDLENGTH_8B; break; + case 9: databits = UART_WORDLENGTH_9B; break; + default: + case 0: Error_Handler(); break; + } + + uart_init(&_serial, (uint32_t)baud, databits, parity, stopbits); + enableHalfDuplexRx(); + if (baud == WIFI_BAUDRATE) + uart_attach_rx_callback(&_serial, _rx_complete_irq); + else + USART1->CR1 |= USART_CR1_RE; // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 +} + +void WifiSerial::end() { + // wait for transmission of outgoing data + flush(); + + uart_deinit(&_serial); + + // clear any received data + _serial.rx_head = _serial.rx_tail; +} + +int WifiSerial::available() { + return ((unsigned int)(WIFI_RX_BUF_SIZE + _serial.rx_head - _serial.rx_tail)) % WIFI_RX_BUF_SIZE; +} + +// +// I/O +// +int WifiSerial::read() { + enableHalfDuplexRx(); + // if the head isn't ahead of the tail, we don't have any characters + if (_serial.rx_head == _serial.rx_tail) return -1; + + unsigned char c = _serial.rx_buff[_serial.rx_tail]; + _serial.rx_tail = (rx_buffer_index_t)(_serial.rx_tail + 1) % WIFI_RX_BUF_SIZE; + return c; +} + +int WifiSerial::write(uint8_t c) { + _written = true; + if (isHalfDuplex()) { + if (_rx_enabled) { + _rx_enabled = false; + uart_enable_tx(&_serial); + } + } + + tx_buffer_index_t i = (_serial.tx_head + 1) % WIFI_TX_BUF_SIZE; + + // If the output buffer is full, there's nothing for it other than to + // wait for the interrupt handler to empty it a bit + while (i == _serial.tx_tail) { + // nop, the interrupt handler will free up space for us + } + + _serial.tx_buff[_serial.tx_head] = c; + _serial.tx_head = i; + + if (!serial_tx_active(&_serial)) + uart_attach_tx_callback(&_serial, _tx_complete_irq); + + return 1; +} + +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // !__STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h new file mode 100644 index 0000000000..87de27c044 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h @@ -0,0 +1,63 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include +#include "Stream.h" +#include "uart.h" + +class WifiSerial { + protected: + // Has any byte been written to the UART since begin() + bool _written; + serial_t _serial; + public: + uint8_t wifiRxBuf[WIFI_RX_BUF_SIZE]; + uint8_t wifiTxBuf[WIFI_TX_BUF_SIZE]; + WifiSerial(void *peripheral); + + // Set up / tear down + void begin(uint32_t baud); + void begin(uint32_t baud,uint8_t config); + void end(); + int available(void); + int read(void); + int write(uint8_t); + + // Interrupt handlers + static int _tx_complete_irq(serial_t *obj); + static void _rx_complete_irq(serial_t *obj); + + void flush(void); + bool isHalfDuplex(void) const; + void enableHalfDuplexRx(void); + + private: + void setRx(uint32_t _rx); + void setTx(uint32_t _tx); + void setRx(PinName _rx); + void setTx(PinName _tx); + void init(PinName _rx, PinName _tx); + bool _rx_enabled; + uint8_t _config; + unsigned long _baud; +}; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp similarity index 88% rename from Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp rename to Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp index d00fd269d8..75830ce1bd 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -19,14 +19,14 @@ * along with this program. If not, see . * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfigPre.h" -#if HAS_TFT_LVGL_UI +#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" -#if ENABLED(MKS_WIFI_MODULE) - #include "draw_ui.h" #include "wifiSerial.h" @@ -59,19 +59,19 @@ WifiSerial::WifiSerial(usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) { if (with_irq) usart_enable(usart_device); else { usart_reg_map *regs = usart_device->regs; - regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // don't change the word length etc, and 'or' in the pattern not overwrite |USART_CR1_M_8N1); + regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 regs->CR1 |= USART_CR1_UE; } } #elif STM32_MCU_SERIES == STM32_SERIES_F2 || STM32_MCU_SERIES == STM32_SERIES_F4 - #define disable_timer_if_necessary(dev, ch) ((void)0) + #define disable_timer_if_necessary(dev, ch) NOOP static void usart_enable_no_irq(usart_dev *usart_device, bool with_irq) { if (with_irq) usart_enable(usart_device); else { usart_reg_map *regs = usart_device->regs; - regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // don't change the word length etc, and 'or' in the pattern not overwrite |USART_CR1_M_8N1); + regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 regs->CR1 |= USART_CR1_UE; } } @@ -137,5 +137,5 @@ int WifiSerial::wifi_rb_is_full() { return rb_is_full(this->usart_device->rb); } -#endif // MKS_WIFI_MODULE -#endif // HAS_TFT_LVGL_UI +#endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE +#endif // __STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h new file mode 100644 index 0000000000..6af2f9743b --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include +#include +#include +#include +#include +#include + +#define DEFINE_WFSERIAL(name, n) WifiSerial name(USART##n, BOARD_USART##n##_TX_PIN, BOARD_USART##n##_RX_PIN) + +class WifiSerial { + public: + uint8 wifiRxBuf[WIFI_RX_BUF_SIZE]; + + public: + WifiSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin); + + /* Set up/tear down */ + void begin(uint32 baud); + void begin(uint32 baud,uint8_t config); + void end(); + int available(); + int read(); + int write(uint8_t); + inline void wifi_usart_irq(usart_reg_map *regs) { + /* Handling RXNEIE and TXEIE interrupts. + * RXNE signifies availability of a byte in DR. + * + * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. + * We enable RXNEIE. + */ + if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { + #ifdef USART_SAFE_INSERT + /* If the buffer is full and the user defines USART_SAFE_INSERT, + * ignore new bytes. */ + rb_safe_insert(this->usart_device->rb, (uint8)regs->DR); + #else + /* By default, push bytes around in the ring buffer. */ + rb_push_insert(this->usart_device->rb, (uint8)regs->DR); + #endif + } + /* TXE signifies readiness to send a byte to DR. */ + if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { + if (!rb_is_empty(this->usart_device->wb)) + regs->DR=rb_remove(this->usart_device->wb); + else + regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE + } + } + int wifi_rb_is_full(); + struct usart_dev *usart_device; + private: + uint8 tx_pin; + uint8 rx_pin; +}; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 52a877031f..1d136a4075 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -51,17 +51,13 @@ #define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); #define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); -#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); -#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); extern uint8_t Explore_Disk (char *path , uint8_t recu_level); extern uint8_t commands_in_queue; extern uint8_t sel_id; - -int usartFifoAvailable(SZ_USART_FIFO *fifo); -int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); -int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); volatile SZ_USART_FIFO WifiRxFifo; @@ -79,12 +75,12 @@ extern uint8_t pause_resum; uint8_t wifi_connect_flg = 0; extern volatile uint8_t get_temp_flag; -#define WIFI_MODE 2 +#define WIFI_MODE 2 #define WIFI_AP_MODE 3 int upload_result = 0; -uint32_t upload_time = 0; +uint32_t upload_time_sec = 0; uint32_t upload_size = 0; volatile WIFI_STATE wifi_link_state; @@ -120,29 +116,19 @@ extern bool flash_dma_mode; uint32_t getWifiTick() { return millis(); } uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { - if (lastTick <= curTick) - return (curTick - lastTick) * TICK_CYCLE; - else - return (0xFFFFFFFF - lastTick + curTick) * TICK_CYCLE; + return (lastTick <= curTick ? curTick - lastTick : 0xFFFFFFFF - lastTick + curTick) * TICK_CYCLE; } void wifi_delay(int n) { - uint32_t begin = getWifiTick(); - uint32_t end = begin; - while (getWifiTickDiff(begin, end) < (uint32_t)n) { + const uint32_t start = getWifiTick(); + while (getWifiTickDiff(start, getWifiTick()) < (uint32_t)n) watchdog_refresh(); - end = getWifiTick(); - } } void wifi_reset() { - uint32_t start, now; - start = getWifiTick(); - now = start; + uint32_t start = getWifiTick(); WIFI_RESET(); - while (getWifiTickDiff(start, now) < 500) - now = getWifiTick(); - + while (getWifiTickDiff(start, getWifiTick()) < 500) { /* nada */ } WIFI_SET(); } @@ -154,82 +140,83 @@ void mount_file_sys(uint8_t disk_type) { } } -#include -#include -#include - -#include -#include - -#include -#include - -#include -#include -#include -#include - -void changeFlashMode(const bool dmaMode) { - if (flash_dma_mode != dmaMode) { - flash_dma_mode = dmaMode; - if (!flash_dma_mode) { - dma_disable(DMA1, DMA_CH5); - dma_clear_isr_bits(DMA1, DMA_CH4); - } - } -} - static bool longName2DosName(const char *longName, char *dosName) { - uint8_t i; - for (i = FILENAME_LENGTH; i--;) dosName[i] = '\0'; + uint8_t i = FILENAME_LENGTH; + while (i) dosName[--i] = '\0'; + while (*longName) { uint8_t c = *longName++; if (c == '.') { // For a dot... if (i == 0) return false; strcat_P(dosName, PSTR(".GCO")); - break; + return dosName[0] != '\0'; } else { - if (c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters // Fail for illegal characters PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); - while (const uint8_t b = pgm_read_byte(p++)) if (b == c) return false; - dosName[i++] = c + (WITHIN(c, 'a', 'z') ? 'A' - 'a' : 0); // Uppercase required for 8.3 name + while (uint8_t b = pgm_read_byte(p++)) if (b == c) return false; + if (c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters + dosName[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); // Uppercase required for 8.3 name } if (i >= 5) { strcat_P(dosName, PSTR("~1.GCO")); - break; + return dosName[0] != '\0'; } } return dosName[0] != '\0'; // Return true if any name was set } -static int storeRcvData(volatile uint8_t *bufToCpy, int32_t len) { - unsigned char tmpW = wifiDmaRcvFifo.write_cur; +#ifdef __STM32F1__ - if (len > UDISKBUFLEN) return 0; + #include + #include + #include - if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { - memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); - wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; - wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; - return 1; + #include + #include + + #include + #include + + #include + #include + #include + #include + + void changeFlashMode(const bool dmaMode) { + if (flash_dma_mode != dmaMode) { + flash_dma_mode = dmaMode; + if (!flash_dma_mode) { + dma_disable(DMA1, DMA_CH5); + dma_clear_isr_bits(DMA1, DMA_CH4); + } + } } - return 0; -} -static void esp_dma_pre() { - dma_channel_reg_map *channel_regs = dma_tube_regs(DMA1, DMA_CH5); + static int storeRcvData(volatile uint8_t *bufToCpy, int32_t len) { + unsigned char tmpW = wifiDmaRcvFifo.write_cur; + if (len > UDISKBUFLEN) return 0; + if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { + memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); + wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; + wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return 1; + } + return 0; + } - CBI32(channel_regs->CCR, 0); - channel_regs->CMAR = (uint32_t)WIFISERIAL.usart_device->rb->buf; - channel_regs->CNDTR = 0x0000; - channel_regs->CNDTR = UART_RX_BUFFER_SIZE; - DMA1->regs->IFCR = 0xF0000; - SBI32(channel_regs->CCR, 0); -} + static void esp_dma_pre() { + dma_channel_reg_map *channel_regs = dma_tube_regs(DMA1, DMA_CH5); -static void dma_ch5_irq_handle() { + CBI32(channel_regs->CCR, 0); + channel_regs->CMAR = (uint32_t)WIFISERIAL.usart_device->rb->buf; + channel_regs->CNDTR = 0x0000; + channel_regs->CNDTR = UART_RX_BUFFER_SIZE; + DMA1->regs->IFCR = 0xF0000; + SBI32(channel_regs->CCR, 0); + } + + static void dma_ch5_irq_handle() { uint8 status_bits = dma_get_isr_bits(DMA1, DMA_CH5); dma_clear_isr_bits(DMA1, DMA_CH5); if (status_bits & 0x8) { @@ -254,74 +241,329 @@ static void dma_ch5_irq_handle() { // DMA transmit half WIFI_IO1_SET(); } -} - -static void wifi_usart_dma_init() { - dma_init(DMA1); - uint32_t flags = ( DMA_MINC_MODE | DMA_TRNS_CMPLT | DMA_HALF_TRNS | DMA_TRNS_ERR); - dma_xfer_size dma_bit_size = DMA_SIZE_8BITS; - dma_setup_transfer(DMA1, DMA_CH5, &USART1_BASE->DR, dma_bit_size, - (volatile void*)WIFISERIAL.usart_device->rb->buf, dma_bit_size, flags);// Transmit buffer DMA - dma_set_priority(DMA1, DMA_CH5, DMA_PRIORITY_LOW); - dma_attach_interrupt(DMA1, DMA_CH5, &dma_ch5_irq_handle); - - dma_clear_isr_bits(DMA1, DMA_CH5); - dma_set_num_transfers(DMA1, DMA_CH5, UART_RX_BUFFER_SIZE); - - bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 1); - dma_enable(DMA1, DMA_CH5); // enable transmit - - for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { - wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; - wifiDmaRcvFifo.state[i] = udisk_buf_empty; } - memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); - wifiDmaRcvFifo.read_cur = 0; - wifiDmaRcvFifo.write_cur = 0; -} + static void wifi_usart_dma_init() { + dma_init(DMA1); + uint32_t flags = ( DMA_MINC_MODE | DMA_TRNS_CMPLT | DMA_HALF_TRNS | DMA_TRNS_ERR); + dma_xfer_size dma_bit_size = DMA_SIZE_8BITS; + dma_setup_transfer(DMA1, DMA_CH5, &USART1_BASE->DR, dma_bit_size, + (volatile void*)WIFISERIAL.usart_device->rb->buf, dma_bit_size, flags);// Transmit buffer DMA + dma_set_priority(DMA1, DMA_CH5, DMA_PRIORITY_LOW); + dma_attach_interrupt(DMA1, DMA_CH5, &dma_ch5_irq_handle); -void esp_port_begin(uint8_t interrupt) { - WifiRxFifo.uart_read_point = 0; - WifiRxFifo.uart_write_point = 0; + dma_clear_isr_bits(DMA1, DMA_CH5); + dma_set_num_transfers(DMA1, DMA_CH5, UART_RX_BUFFER_SIZE); - #if 1 + bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 1); + dma_enable(DMA1, DMA_CH5); // enable transmit + for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { + wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; + wifiDmaRcvFifo.state[i] = udisk_buf_empty; + } + + memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); + wifiDmaRcvFifo.read_cur = 0; + wifiDmaRcvFifo.write_cur = 0; + } + + void esp_port_begin(uint8_t interrupt) { + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; #if ENABLED(MKS_WIFI_MODULE) - WIFISERIAL.end(); if (interrupt) { + WIFISERIAL.end(); for (uint16_t i = 0; i < 65535; i++) { /*nada*/ } WIFISERIAL.begin(WIFI_BAUDRATE); millis_t serial_connect_timeout = millis() + 1000UL; while (PENDING(millis(), serial_connect_timeout)) { /*nada*/ } } else { + WIFISERIAL.end(); WIFISERIAL.usart_device->regs->CR1 &= ~USART_CR1_RXNEIE; WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); wifi_usart_dma_init(); } #endif + } - #else +#else // !__STM32F1__ - #if MKS_WIFI_MODULE - WIFISERIAL.end(); - for (uint16_t i = 0; i < 65535; i++) { /*nada*/ } - WIFISERIAL.begin(interrupt ? WIFI_BAUDRATE : WIFI_UPLOAD_BAUDRATE); - millis_t serial_connect_timeout = millis() + 1000UL; - while (PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #endif - if (!interrupt) wifi_usart_dma_init(); + DMA_HandleTypeDef wifiUsartDMArx; + void changeFlashMode(const bool dmaMode) { + if (flash_dma_mode != dmaMode) { + flash_dma_mode = dmaMode; + if (flash_dma_mode == 1) { + } + else { + } + } + } + + #ifdef STM32F1xx + + HAL_StatusTypeDef HAL_DMA_PollForTransferCustomize(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout) { + uint32_t temp; + uint32_t tickstart = 0U; + + if (HAL_DMA_STATE_BUSY != hdma->State) { // No transfer ongoing + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + // Polling mode not supported in circular mode + if (RESET != (hdma->Instance->CCR & DMA_CCR_CIRC)) { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + // Get the level transfer complete flag + temp = (CompleteLevel == HAL_DMA_FULL_TRANSFER + ? __HAL_DMA_GET_TC_FLAG_INDEX(hdma) // Transfer Complete flag + : __HAL_DMA_GET_HT_FLAG_INDEX(hdma) // Half Transfer Complete flag + ); + + // Get tick + tickstart = HAL_GetTick(); + + while (__HAL_DMA_GET_FLAG(hdma, temp) == RESET) { + if ((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)) != RESET)) { + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); // Clear the half transfer complete flag + WIFI_IO1_SET(); + } + + if ((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)) != RESET)) { + /** + * When a DMA transfer error occurs + * A hardware clear of its EN bits is performed + * Clear all flags + */ + hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex); + + SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TE); // Update error code + hdma->State= HAL_DMA_STATE_READY; // Change the DMA state + __HAL_UNLOCK(hdma); // Process Unlocked + return HAL_ERROR; + } + + // Check for the Timeout + if (Timeout != HAL_MAX_DELAY && (!Timeout || (HAL_GetTick() - tickstart) > Timeout)) { + SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TIMEOUT); // Update error code + hdma->State = HAL_DMA_STATE_READY; // Change the DMA state + __HAL_UNLOCK(hdma); // Process Unlocked + return HAL_ERROR; + } + } + + if (CompleteLevel == HAL_DMA_FULL_TRANSFER) { + // Clear the transfer complete flag + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); + + /* The selected Channelx EN bit is cleared (DMA is disabled and + all transfers are complete) */ + hdma->State = HAL_DMA_STATE_READY; + } + else + __HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); // Clear the half transfer complete flag + + __HAL_UNLOCK(hdma); // Process unlocked + + return HAL_OK; + } + + #else // !STM32F1xx + + typedef struct { + __IO uint32_t ISR; //!< DMA interrupt status register + __IO uint32_t Reserved0; + __IO uint32_t IFCR; //!< DMA interrupt flag clear register + } MYDMA_Base_Registers; + + HAL_StatusTypeDef HAL_DMA_PollForTransferCustomize(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) { + HAL_StatusTypeDef status = HAL_OK; + uint32_t mask_cpltlevel; + uint32_t tickstart = HAL_GetTick(); + uint32_t tmpisr; + + MYDMA_Base_Registers *regs; // Calculate DMA base and stream number + + if (HAL_DMA_STATE_BUSY != hdma->State) { // No transfer ongoing + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + // Polling mode not supported in circular mode and double buffering mode + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + // Get the level transfer complete flag + mask_cpltlevel = (CompleteLevel == HAL_DMA_FULL_TRANSFER + ? DMA_FLAG_TCIF0_4 << hdma->StreamIndex // Transfer Complete flag + : DMA_FLAG_HTIF0_4 << hdma->StreamIndex // Half Transfer Complete flag + ); + + regs = (MYDMA_Base_Registers *)hdma->StreamBaseAddress; + tmpisr = regs->ISR; + + while (((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) { + // Check for the Timeout (Not applicable in circular mode) + if (Timeout != HAL_MAX_DELAY) { + if (!Timeout || (HAL_GetTick() - tickstart) > Timeout) { + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; // Update error code + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State = HAL_DMA_STATE_READY; // Change the DMA state + return HAL_TIMEOUT; + } + } + + tmpisr = regs->ISR; // Get the ISR register value + + if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) { + regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; // Clear the Direct Mode error flag + WIFI_IO1_SET(); + } + + if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_TE; // Update error code + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; // Clear the transfer error flag + } + + if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_FE; // Update error code + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; // Clear the FIFO error flag + } + + if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) { + hdma->ErrorCode |= HAL_DMA_ERROR_DME; // Update error code + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; // Clear the Direct Mode error flag + } + } + + if (hdma->ErrorCode != HAL_DMA_ERROR_NONE && (hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) { + HAL_DMA_Abort(hdma); + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State= HAL_DMA_STATE_READY; // Change the DMA state + return HAL_ERROR; + } + + // Get the level transfer complete flag + if (CompleteLevel == HAL_DMA_FULL_TRANSFER) { + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + __HAL_UNLOCK(hdma); // Process Unlocked + hdma->State = HAL_DMA_STATE_READY; + } + else + regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; // Clear the half transfer and transfer complete flags + + return status; + } #endif -} + + static void dmaTransmitBegin() { + wifiUsartDMArx.Init.MemInc = DMA_MINC_ENABLE; + if (HAL_DMA_Init((DMA_HandleTypeDef *)&wifiUsartDMArx) != HAL_OK) + Error_Handler(); + + if (HAL_DMA_Start(&wifiUsartDMArx, (uint32_t)&(USART1->DR), (uint32_t)WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) + Error_Handler(); + + USART1->CR1 |= USART_CR1_UE; + + SET_BIT(USART1->CR3, USART_CR3_DMAR); + WIFI_IO1_RESET(); + } + + static int storeRcvData(volatile uint8_t *bufToCpy, int32_t len) { + unsigned char tmpW = wifiDmaRcvFifo.write_cur; + + if (len > UDISKBUFLEN) return 0; + + if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { + const int timeOut = 2000; //millisecond + dmaTransmitBegin(); + if (HAL_DMA_PollForTransferCustomize(&wifiUsartDMArx, HAL_DMA_FULL_TRANSFER, timeOut) == HAL_OK) { + memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); + wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; + wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return 1; + } + } + return 0; + } + + static void wifi_usart_dma_init() { + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_ENABLE(); + wifiUsartDMArx.Instance = DMA1_Channel5; + #else + __HAL_RCC_DMA2_CLK_ENABLE(); + wifiUsartDMArx.Instance = DMA2_Stream2; + wifiUsartDMArx.Init.Channel = DMA_CHANNEL_4; + #endif + wifiUsartDMArx.Init.Direction = DMA_PERIPH_TO_MEMORY; + wifiUsartDMArx.Init.PeriphInc = DMA_PINC_DISABLE; + wifiUsartDMArx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + wifiUsartDMArx.Init.MemDataAlignment = DMA_PDATAALIGN_BYTE; + wifiUsartDMArx.Init.Mode = DMA_NORMAL; + #ifdef STM32F4xx + wifiUsartDMArx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif + wifiUsartDMArx.Init.MemInc = DMA_MINC_ENABLE; + if (HAL_DMA_Init((DMA_HandleTypeDef *)&wifiUsartDMArx) != HAL_OK) + Error_Handler(); + + if (HAL_DMA_Start(&wifiUsartDMArx, (uint32_t)&(USART1->DR), (uint32_t)WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) + Error_Handler(); + + USART1->CR1 |= USART_CR1_UE; + + SET_BIT(USART1->CR3, USART_CR3_DMAR); // Enable Rx DMA Request + + for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { + wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; + wifiDmaRcvFifo.state[i] = udisk_buf_empty; + } + + memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); + wifiDmaRcvFifo.read_cur = 0; + wifiDmaRcvFifo.write_cur = 0; + } + + void esp_port_begin(uint8_t interrupt) { + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; + + #if ENABLED(MKS_WIFI_MODULE) + if (interrupt) { + WIFISERIAL.end(); + for (uint16_t i = 0; i < 65535; i++) { /*nada*/ } + WIFISERIAL.begin(WIFI_BAUDRATE); + uint32_t serial_connect_timeout = millis() + 1000UL; + while (PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + } + else { + WIFISERIAL.end(); + USART1->CR1 &= ~USART_CR1_RXNEIE; + WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); + wifi_usart_dma_init(); + } + #endif + } + +#endif // !__STM32F1__ #if ENABLED(MKS_WIFI_MODULE) int raw_send_to_wifi(uint8_t *buf, int len) { if (buf == 0 || len <= 0) return 0; - for (int i = 0; i < len; i++) - WIFISERIAL.write(*(buf + i)); + for (int i = 0; i < len; i++) WIFISERIAL.write(*(buf + i)); return len; } @@ -336,9 +578,9 @@ int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { uint8_t wifi_ret_tail = 0xFC; if (type == WIFI_PARA_SET) { - int data_offset = 4; - int apLen = strlen((const char *)uiCfg.wifi_name); - int keyLen = strlen((const char *)uiCfg.wifi_key); + int data_offset = 4, + apLen = strlen((const char *)uiCfg.wifi_name), + keyLen = strlen((const char *)uiCfg.wifi_key); ZERO(buf_to_wifi); index_to_wifi = 0; @@ -378,9 +620,9 @@ int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { if (buf_to_wifi[index_to_wifi + 3] == '\n') { // mask "wait" "busy" "X:" - if (((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't') ) - || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y') ) - || ((buf_to_wifi[4] == 'X') && (buf_to_wifi[5] == ':') ) + if ( ((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't')) + || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y')) + || ((buf_to_wifi[4] == 'X') && (buf_to_wifi[5] == ':')) ) { ZERO(buf_to_wifi); index_to_wifi = 0; @@ -458,6 +700,7 @@ int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { return 1; } + #define SEND_OK_TO_WIFI send_to_wifi((uint8_t *)"ok\r\n", strlen("ok\r\n")) int send_to_wifi(uint8_t *buf, int len) { return package_to_wifi(WIFI_TRANS_INF, buf, len); } @@ -530,15 +773,15 @@ int write_to_file(char *buf, int len) { return 0; } -#define ESP_PROTOC_HEAD (uint8_t)0xA5 -#define ESP_PROTOC_TAIL (uint8_t)0xFC +#define ESP_PROTOC_HEAD (uint8_t)0xA5 +#define ESP_PROTOC_TAIL (uint8_t)0xFC -#define ESP_TYPE_NET (uint8_t)0x0 -#define ESP_TYPE_GCODE (uint8_t)0x1 +#define ESP_TYPE_NET (uint8_t)0x0 +#define ESP_TYPE_GCODE (uint8_t)0x1 #define ESP_TYPE_FILE_FIRST (uint8_t)0x2 -#define ESP_TYPE_FILE_FRAGMENT (uint8_t)0x3 +#define ESP_TYPE_FILE_FRAGMENT (uint8_t)0x3 -#define ESP_TYPE_WIFI_LIST (uint8_t)0x4 +#define ESP_TYPE_WIFI_LIST (uint8_t)0x4 uint8_t esp_msg_buf[UART_RX_BUFFER_SIZE] = { 0 }; uint16_t esp_msg_index = 0; @@ -651,13 +894,10 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { } break; - case 21: - /*init sd card*/ - SEND_OK_TO_WIFI; - break; + case 21: SEND_OK_TO_WIFI; break; // Init SD card case 23: - /*select the file*/ + // Select the file if (uiCfg.print_state == IDLE) { int index = 0; while (tmpStr[index] == ' ') index++; @@ -747,8 +987,10 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { if (card.isFileOpen()) { //saved_feedrate_percentage = feedrate_percentage; feedrate_percentage = 100; - planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + #if EXTRUDERS + planner.flow_percentage[0] = 100; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + #endif #if EXTRUDERS == 2 planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; @@ -786,7 +1028,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { break; case 25: - /*pause print file*/ + // Pause print file if (uiCfg.print_state == WORKING) { stop_print_time(); @@ -806,7 +1048,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { break; case 26: - /*stop print file*/ + // Stop print file if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED) || (uiCfg.print_state == REPRINTING)) { stop_print_time(); @@ -823,7 +1065,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { break; case 27: - /*report print rate*/ + // Report print rate if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)|| (uiCfg.print_state == REPRINTING)) { print_rate = uiCfg.totalSend; ZERO(tempBuf); @@ -833,7 +1075,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { break; case 28: - /*begin to transfer file to filesys*/ + // Begin to transfer file to filesys if (uiCfg.print_state == IDLE) { int index = 0; @@ -887,7 +1129,6 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { sprintf_P(tbuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); const int tlen = strlen(tbuf); - sprintf_P(outBuf, PSTR("T:%s"), tbuf); outBuf += 2 + tlen; @@ -909,7 +1150,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { #if HAS_MULTI_HOTEND sprintf_P(outBuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); #else - strcat_P(outBuf, PSTR("0 /0")); + strcpy_P(outBuf, PSTR("0 /0")); #endif outBuf += 4; @@ -918,17 +1159,11 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { else { sprintf_P((char *)tempBuf, PSTR("T:%d /%d B:%d /%d T0:%d /%d T1:%d /%d @:0 B@:0\r\n"), thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), - #if HAS_HEATED_BED - thermalManager.wholeDegBed(), thermalManager.degTargetBed(), - #else - 0, 0, - #endif + TERN0(HAS_HEATED_BED, thermalManager.wholeDegBed()), + TERN0(HAS_HEATED_BED, thermalManager.degTargetBed()), thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), - #if HAS_MULTI_HOTEND - thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1) - #else - 0, 0 - #endif + TERN0(HAS_MULTI_HOTEND, thermalManager.wholeDegHotend(1)), + TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1)) ); } @@ -977,11 +1212,8 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { case 998: if (uiCfg.print_state == IDLE) { - int v = atoi((char *)tmpStr); - if (v == 0) - set_cur_file_sys(0); - else if (v == 1) - set_cur_file_sys(1); + const int v = atoi((char *)tmpStr); + if (v == 0 || v == 1) set_cur_file_sys(v); wifi_ret_ack(); } break; @@ -996,18 +1228,14 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { strcat_P((char *)cmd_line, PSTR("\n")); if (espGcodeFifo.wait_tick > 5) { - uint32_t left; - if (espGcodeFifo.r > espGcodeFifo.w) - left = espGcodeFifo.r - espGcodeFifo.w - 1; - else - left = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; + const uint32_t left = espGcodeFifo.r > espGcodeFifo.w + ? espGcodeFifo.r - espGcodeFifo.w - 1 + : WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; if (left >= strlen((const char *)cmd_line)) { - uint32_t index = 0; - while (index < strlen((const char *)cmd_line)) { + for (uint32_t index = 0; index < strlen((const char *)cmd_line); index++) { espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - index++; } if (left - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) SEND_OK_TO_WIFI; @@ -1022,18 +1250,14 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { strcat_P((char *)cmd_line, PSTR("\n")); if (espGcodeFifo.wait_tick > 5) { - uint32_t left_g; - if (espGcodeFifo.r > espGcodeFifo.w) - left_g = espGcodeFifo.r - espGcodeFifo.w - 1; - else - left_g = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; + const uint32_t left_g = espGcodeFifo.r > espGcodeFifo.w + ? espGcodeFifo.r - espGcodeFifo.w - 1 + : WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; if (left_g >= strlen((const char *)cmd_line)) { - uint32_t index = 0; - while (index < strlen((const char *)cmd_line)) { + for (uint32_t index = 0; index < strlen((const char *)cmd_line); index++) { espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - index++; } if (left_g - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) SEND_OK_TO_WIFI; @@ -1061,11 +1285,10 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { if (msgLen <= 0) return; - // ip + // IP address sprintf_P(ipPara.ip_addr, PSTR("%d.%d.%d.%d"), msg[0], msg[1], msg[2], msg[3]); - // port - // connect state + // port connect state switch (msg[6]) { case 0x0A: wifi_link_state = WIFI_CONNECTED; break; case 0x0E: wifi_link_state = WIFI_EXCEPTION; break; @@ -1075,7 +1298,7 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { // mode wifiPara.mode = msg[7]; - // wifi name + // WiFi name wifiNameLen = msg[8]; wifiKeyLen = msg[9 + wifiNameLen]; if (wifiNameLen < 32) { @@ -1085,7 +1308,7 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { memset(&wifi_list.wifiConnectedName, 0, sizeof(wifi_list.wifiConnectedName)); memcpy(&wifi_list.wifiConnectedName, &msg[9], wifiNameLen); - // wifi key + // WiFi key if (wifiKeyLen < 64) { ZERO(wifiPara.keyCode); memcpy(wifiPara.keyCode, &msg[10 + wifiNameLen], wifiKeyLen); @@ -1102,7 +1325,7 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { cloud_para.port = msg[12 + wifiNameLen + wifiKeyLen + hostLen] + (msg[13 + wifiNameLen + wifiKeyLen + hostLen] << 8); } - // id + // ID id_len = msg[14 + wifiNameLen + wifiKeyLen + hostLen]; if (id_len == 20) { ZERO(cloud_para.id); @@ -1125,10 +1348,10 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { if (cfg_cloud_flag == 1) { if (((cloud_para.state >> 4) != (char)gCfgItems.cloud_enable) || (strncmp(cloud_para.hostUrl, (const char *)uiCfg.cloud_hostUrl, 96) != 0) - || (cloud_para.port != uiCfg.cloud_port)) { - package_to_wifi(WIFI_CLOUD_CFG, (uint8_t *)0, 0); - } - else cfg_cloud_flag = 0; + || (cloud_para.port != uiCfg.cloud_port) + ) package_to_wifi(WIFI_CLOUD_CFG, (uint8_t *)0, 0); + else + cfg_cloud_flag = 0; } } @@ -1366,6 +1589,7 @@ static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { lastFragment = frag; if ((frag & (~FRAG_MASK)) != 0) { + wifiDmaRcvFifo.receiveEspData = false; int res = upload_file.write(public_buf, file_writer.write_index); if (res == -1) { upload_file.close(); @@ -1392,7 +1616,7 @@ static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { ZERO(public_buf); file_writer.write_index = 0; file_writer.tick_end = getWifiTick(); - upload_time = getWifiTickDiff(file_writer.tick_begin, file_writer.tick_end) / 1000; + upload_time_sec = getWifiTickDiff(file_writer.tick_begin, file_writer.tick_end) / 1000; upload_size = gCfgItems.curFilesize; wifi_link_state = WIFI_CONNECTED; upload_result = 3; @@ -1540,9 +1764,16 @@ void stopEspTransfer() { WIFI_IO1_SET(); // disable dma - dma_clear_isr_bits(DMA1, DMA_CH5); - bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 0); - dma_disable(DMA1, DMA_CH5); + #ifdef __STM32F1__ + dma_clear_isr_bits(DMA1, DMA_CH5); + bb_peri_set_bit(&USART1_BASE->CR3, USART_CR3_DMAR_BIT, 0); + dma_disable(DMA1, DMA_CH5); + #else + // First, abort any running dma + HAL_DMA_Abort(&wifiUsartDMArx); + // DeInit objects + HAL_DMA_DeInit(&wifiUsartDMArx); + #endif wifi_delay(200); changeFlashMode(true); // Set SPI flash to use DMA mode @@ -1571,6 +1802,9 @@ void wifi_rcv_handle() { } } #else + #ifndef __STM32F1__ + if (wifiDmaRcvFifo.receiveEspData) storeRcvData(WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE); + #endif len = readWifiFifo(ucStr, UART_RX_BUFFER_SIZE); #endif if (len > 0) { @@ -1582,15 +1816,16 @@ void wifi_rcv_handle() { } getDataF = 1; } - if (esp_state == TRANSFER_STORE) { - if (storeRcvData(WIFISERIAL.usart_device->rb->buf, UART_RX_BUFFER_SIZE)) { - esp_state = TRANSFERING; - esp_dma_pre(); - if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + #ifdef __STM32F1__ + if (esp_state == TRANSFER_STORE) { + if (storeRcvData(WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) { + esp_state = TRANSFERING; + esp_dma_pre(); + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + } + else WIFI_IO1_SET(); } - else - WIFI_IO1_SET(); - } + #endif } else { len = readWifiBuf((int8_t *)ucStr, UART_RX_BUFFER_SIZE); @@ -1602,6 +1837,10 @@ void wifi_rcv_handle() { esp_port_begin(0); wifi_delay(10); tick_net_time1 = 0; + #ifndef __STM32F1__ + wifiDmaRcvFifo.receiveEspData = true; + return; + #endif } if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); getDataF = 1; @@ -1612,9 +1851,8 @@ void wifi_rcv_handle() { } } - if (getDataF == 1) { + if (getDataF == 1) tick_net_time1 = getWifiTick(); - } else { tick_net_time2 = getWifiTick(); @@ -1664,74 +1902,68 @@ void mks_esp_wifi_init() { esp_state = TRANSFER_IDLE; esp_port_begin(1); - + watchdog_refresh(); wifi_reset(); #if 0 if (update_flag == 0) { res = f_open(&esp_upload.uploadFile, ESP_WEB_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); - if (res == FR_OK) { - f_close(&esp_upload.uploadFile); + wifi_delay(2000); - wifi_delay(2000); + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { - return; - } + clear_cur_ui(); - clear_cur_ui(); - - draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE); - if (wifi_upload(1) >= 0) { - - f_unlink("1:/MKS_WIFI_CUR"); - f_rename(ESP_WEB_FIRMWARE_FILE,"/MKS_WIFI_CUR"); - } - draw_return_ui(); - update_flag = 1; + draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE); + if (wifi_upload(1) >= 0) { + f_unlink("1:/MKS_WIFI_CUR"); + f_rename(ESP_WEB_FIRMWARE_FILE,"/MKS_WIFI_CUR"); } - + draw_return_ui(); + update_flag = 1; } - if (update_flag == 0) { - res = f_open(&esp_upload.uploadFile, ESP_WEB_FILE, FA_OPEN_EXISTING | FA_READ); - if (res == FR_OK) { - f_close(&esp_upload.uploadFile); + } - wifi_delay(2000); + if (update_flag == 0) { + res = f_open(&esp_upload.uploadFile, ESP_WEB_FILE, FA_OPEN_EXISTING | FA_READ); + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { - return; - } + wifi_delay(2000); - clear_cur_ui(); + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; - draw_dialog(DIALOG_TYPE_UPDATE_ESP_DATA); + clear_cur_ui(); - if (wifi_upload(2) >= 0) { + draw_dialog(DIALOG_TYPE_UPDATE_ESP_DATA); - f_unlink("1:/MKS_WEB_CONTROL_CUR"); - f_rename(ESP_WEB_FILE,"/MKS_WEB_CONTROL_CUR"); - } - draw_return_ui(); + if (wifi_upload(2) >= 0) { + f_unlink("1:/MKS_WEB_CONTROL_CUR"); + f_rename(ESP_WEB_FILE,"/MKS_WEB_CONTROL_CUR"); } + draw_return_ui(); } + } #endif + wifiPara.decodeType = WIFI_DECODE_TYPE; wifiPara.baud = 115200; wifi_link_state = WIFI_NOT_CONFIG; } void mks_wifi_firmware_update() { + watchdog_refresh(); card.openFileRead((char *)ESP_FIRMWARE_FILE); if (card.isFileOpen()) { card.closefile(); wifi_delay(2000); - - if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) - return; + watchdog_refresh(); + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return; clear_cur_ui(); @@ -1753,12 +1985,6 @@ void mks_wifi_firmware_update() { } } -#define BUF_INC_POINTER(p) ((p + 1 == UART_FIFO_BUFFER_SIZE) ? 0:(p + 1)) - -int usartFifoAvailable(SZ_USART_FIFO *fifo) { - return WIFISERIAL.available(); -} - void get_wifi_commands() { static char wifi_line_buffer[MAX_CMD_SIZE]; static bool wifi_comment_mode = false; @@ -1836,4 +2062,6 @@ int readWifiBuf(int8_t *buf, int32_t len) { return i; } +int usartFifoAvailable(SZ_USART_FIFO *fifo) { return WIFISERIAL.available(); } + #endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index 8f64613417..709d3d1719 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -64,6 +64,7 @@ typedef enum{ #define TRANS_RCV_FIFO_BLOCK_NUM 14 typedef struct { + bool receiveEspData; unsigned char *bufferAddr[TRANS_RCV_FIFO_BLOCK_NUM]; unsigned char *p; UDISK_DATA_BUFFER_STATE state[TRANS_RCV_FIFO_BLOCK_NUM]; @@ -191,6 +192,9 @@ void get_wifi_list_command_send(); void get_wifi_commands(); int readWifiBuf(int8_t *buf, int32_t len); void mks_wifi_firmware_update(); +int usartFifoAvailable(SZ_USART_FIFO *fifo); +int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); +void esp_port_begin(uint8_t interrupt); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 4a8e473a5c..4a5f08edaa 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -40,7 +40,6 @@ extern SZ_USART_FIFO WifiRxFifo; extern int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); extern int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); void esp_port_begin(uint8_t interrupt); -extern int usartFifoAvailable(SZ_USART_FIFO *fifo); void wifi_delay(int n); #define ARRAY_SIZE(a) sizeof(a) / sizeof((a)[0]) @@ -280,7 +279,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t switch (state) { case begin: // expecting frame start c = uploadPort_read(); - if (c == (uint8_t)0xC0) break; + if (c != (uint8_t)0xC0) break; state = header; needBytes = 2; break; @@ -644,10 +643,7 @@ static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000 void ResetWiFiForUpload(int begin_or_end) { //#if 0 - uint32_t start, now; - - start = getWifiTick(); - now = start; + uint32_t start = getWifiTick(); if (begin_or_end == 0) { SET_OUTPUT(WIFI_IO0_PIN); @@ -657,7 +653,7 @@ void ResetWiFiForUpload(int begin_or_end) { SET_INPUT_PULLUP(WIFI_IO0_PIN); WIFI_RESET(); - while (getWifiTickDiff(start, now) < 500) now = getWifiTick(); + while (getWifiTickDiff(start, getWifiTick()) < 500) { /* nada */ } WIFI_SET(); //#endif } diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 14664bda39..c7850903e7 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -36,6 +36,7 @@ #define BOARD_INFO_NAME "MKS Robin E3P" #define BOARD_NO_NATIVE_USB +#define MKS_HARDWARE_TEST_ONLY_E0 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 091a336232..7de5552dbb 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -178,16 +178,16 @@ // // Misc. Functions // -#define MT_DET_1 PA4 -#define MT_DET_2 PE6 +#define MT_DET_1_PIN PA4 +#define MT_DET_2_PIN PE6 #define PW_DET PA13 #define PW_OFF PB2 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1 + #define FIL_RUNOUT_PIN MT_DET_1_PIN #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN MT_DET_2 + #define FIL_RUNOUT2_PIN MT_DET_2_PIN #endif #ifndef POWER_LOSS_PIN @@ -214,6 +214,13 @@ #define SDCARD_CONNECTION ONBOARD #endif +// MKS WIFI MODULE +#if ENABLED(MKS_WIFI_MODULE) + #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN + #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN + #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN +#endif + // // Onboard SD card // diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 index 0891744692..99ff2623bb 100755 --- a/buildroot/tests/mks_robin_nano35 +++ b/buildroot/tests/mks_robin_nano35 @@ -21,8 +21,8 @@ exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC -opt_enable TFT_INTERFACE_SPI -exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" +opt_enable TFT_INTERFACE_SPI MKS_WIFI_MODULE +exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" # # MKS Robin nano v1.2 LVGL FSMC diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 2580c4700c..db1cc99217 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -26,8 +26,7 @@ platform = ststm32@~12.1 board_build.core = maple build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} - -DARDUINO_ARCH_STM32 + ${common.build_flags} -DARDUINO_ARCH_STM32 -DMAPLE_STM32F1 build_unflags = -std=gnu11 -std=gnu++11 src_filter = ${common.default_src_filter} + lib_ignore = SPI, FreeRTOS701, FreeRTOS821 From 05ebde38127ca6c3bc056cb4068a414bade766b4 Mon Sep 17 00:00:00 2001 From: lujios <83166168+lujios@users.noreply.github.com> Date: Tue, 13 Jul 2021 02:19:29 +0200 Subject: [PATCH 0385/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Improve=20Sensor?= =?UTF-8?q?less=20homing/probing=20for=20G28,=20G33=20(#21899)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 6 +- Marlin/src/feature/tmc_util.h | 7 -- Marlin/src/gcode/calibrate/G28.cpp | 18 ++++- Marlin/src/gcode/calibrate/G33.cpp | 16 ++++- Marlin/src/module/delta.cpp | 1 + Marlin/src/module/endstops.cpp | 12 +++- Marlin/src/module/planner.cpp | 28 ++++++++ Marlin/src/module/planner.h | 13 ++++ Marlin/src/module/probe.cpp | 109 +++++++++++++++++++++++++++-- Marlin/src/module/probe.h | 12 ++++ 10 files changed, 197 insertions(+), 25 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index c595e8b136..3ec4a8193c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -828,10 +828,8 @@ void idle(bool no_stepper_sleep/*=false*/) { // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) - if (endstops.tmc_spi_homing.any - && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period)) - ) LOOP_L_N(i, 4) // Read SGT 4 times per idle loop - if (endstops.tmc_spi_homing_check()) break; + if (endstops.tmc_spi_homing.any && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period))) + LOOP_L_N(i, 4) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop #endif // Handle SD Card insert / remove diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 4753f78d91..c878d86fae 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -360,13 +360,6 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; constexpr uint16_t default_sg_guard_duration = 400; - - struct motion_state_t { - xy_ulong_t acceleration; - #if HAS_CLASSIC_JERK - xy_float_t jerk_state; - #endif - }; #endif bool tmc_enable_stallguard(TMC2130Stepper &st); diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 7cd1f65fbf..ca9cbb8cc9 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -167,12 +167,15 @@ motion_state_t begin_slow_homing() { motion_state_t motion_state{0}; motion_state.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], - planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + planner.settings.max_acceleration_mm_per_s2[Y_AXIS] + OPTARG(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) + ); planner.settings.max_acceleration_mm_per_s2[X_AXIS] = 100; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; + TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = 100); #if HAS_CLASSIC_JERK motion_state.jerk_state = planner.max_jerk; - planner.max_jerk.set(0, 0); + planner.max_jerk.set(0, 0 OPTARG(DELTA, 0)); #endif planner.reset_acceleration_rates(); return motion_state; @@ -181,6 +184,7 @@ void end_slow_homing(const motion_state_t &motion_state) { planner.settings.max_acceleration_mm_per_s2[X_AXIS] = motion_state.acceleration.x; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y; + TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = motion_state.acceleration.z); TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); planner.reset_acceleration_rates(); } @@ -259,7 +263,7 @@ void GcodeSuite::G28() { reset_stepper_timeout(); #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) - #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) #define HAS_HOMING_CURRENT 1 #endif @@ -287,6 +291,11 @@ void GcodeSuite::G28() { stepperY2.rms_current(Y2_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif + #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) + const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); + stepperZ.rms_current(Z_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Z"), tmc_save_current_Z, Z_CURRENT_HOME); + #endif #endif #if ENABLED(IMPROVE_HOMING_RELIABILITY) @@ -497,6 +506,9 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(Y2) stepperY2.rms_current(tmc_save_current_Y2); #endif + #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) + stepperZ.rms_current(tmc_save_current_Z); + #endif #if HAS_CURRENT_HOME(I) stepperI.rms_current(tmc_save_current_I); #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 0737c91668..a897a10115 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -71,7 +71,9 @@ float lcd_probe_pt(const xy_pos_t &xy); void ac_home() { endstops.enable(true); + TERN_(SENSORLESS_HOMING, probe.set_homing_current(true)); home_delta(); + TERN_(SENSORLESS_HOMING, probe.set_homing_current(false)); endstops.not_homing(); } @@ -384,6 +386,12 @@ static float auto_tune_a() { * V3 Report settings and probe results * * E Engage the probe for each point + * + * With SENSORLESS_PROBING: + * Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.) + * X Don't activate stallguard on X. + * Y Don't activate stallguard on Y. + * Z Don't activate stallguard on Z. */ void GcodeSuite::G33() { @@ -417,6 +425,12 @@ void GcodeSuite::G33() { const bool stow_after_each = parser.seen_test('E'); + #if ENABLED(SENSORLESS_PROBING) + probe.test_sensitivity.x = !parser.seen_test('X'); + TERN_(HAS_Y_AXIS, probe.test_sensitivity.y = !parser.seen_test('Y')); + TERN_(HAS_Z_AXIS, probe.test_sensitivity.z = !parser.seen_test('Z')); + #endif + const bool _0p_calibration = probe_points == 0, _1p_calibration = probe_points == 1 || probe_points == -1, _4p_calibration = probe_points == 2, @@ -587,7 +601,7 @@ void GcodeSuite::G33() { // print report - if (verbose_level == 3) + if (verbose_level == 3 || verbose_level == 0) print_calibration_results(z_at_pt, _tower_results, _opposite_results); if (verbose_level != 0) { // !dry run diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 96d8841f13..992c3a09b4 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -254,6 +254,7 @@ void home_delta() { current_position.z = DIFF_TERN(HAS_BED_PROBE, delta_height + 10, probe.offset.z); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); + TERN_(SENSORLESS_PROBING,endstops.report_states()); // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 8f6827de27..420acccb58 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -595,9 +595,15 @@ void _O2 Endstops::report_states() { // The following routines are called from an ISR context. It could be the temperature ISR, the // endstop ISR or the Stepper ISR. -#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX -#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN -#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING +#if BOTH(DELTA, SENSORLESS_PROBING) + #define _ENDSTOP(AXIS, MINMAX) AXIS ##_MAX + #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_MAX_PIN + #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_MAX_ENDSTOP_INVERTING +#else + #define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX + #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN + #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING +#endif // Check endstops - Could be called from Temperature ISR! void Endstops::update() { diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 49b2d60b20..e48d05b09f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1527,6 +1527,34 @@ void Planner::check_axes_activity() { } #endif +#if ENABLED(IMPROVE_HOMING_RELIABILITY) + + void Planner::enable_stall_prevention(const bool onoff) { + static motion_state_t saved_motion_state; + if (onoff) { + saved_motion_state.acceleration.x = settings.max_acceleration_mm_per_s2[X_AXIS]; + saved_motion_state.acceleration.y = settings.max_acceleration_mm_per_s2[Y_AXIS]; + settings.max_acceleration_mm_per_s2[X_AXIS] = settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; + #if ENABLED(DELTA) + saved_motion_state.acceleration.z = settings.max_acceleration_mm_per_s2[Z_AXIS]; + settings.max_acceleration_mm_per_s2[Z_AXIS] = 100; + #endif + #if HAS_CLASSIC_JERK + saved_motion_state.jerk_state = max_jerk; + max_jerk.set(0, 0 OPTARG(DELTA, 0)); + #endif + } + else { + settings.max_acceleration_mm_per_s2[X_AXIS] = saved_motion_state.acceleration.x; + settings.max_acceleration_mm_per_s2[Y_AXIS] = saved_motion_state.acceleration.y; + TERN_(DELTA, settings.max_acceleration_mm_per_s2[Z_AXIS] = saved_motion_state.acceleration.z); + TERN_(HAS_CLASSIC_JERK, max_jerk = saved_motion_state.jerk_state); + } + reset_acceleration_rates(); + } + +#endif + #if HAS_LEVELING constexpr xy_pos_t level_fulcrum = { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 10114ebfc6..9b104615f6 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -281,6 +281,15 @@ typedef struct { min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate } planner_settings_t; +#if ENABLED(IMPROVE_HOMING_RELIABILITY) + struct motion_state_t { + TERN(DELTA, xyz_ulong_t, xy_ulong_t) acceleration; + #if HAS_CLASSIC_JERK + TERN(DELTA, xyz_float_t, xy_float_t) jerk_state; + #endif + }; +#endif + #if DISABLED(SKEW_CORRECTION) #define XY_SKEW_FACTOR 0 #define XZ_SKEW_FACTOR 0 @@ -532,6 +541,10 @@ class Planner { } #endif + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + void enable_stall_prevention(const bool onoff); + #endif + #if DISABLED(NO_VOLUMETRICS) // Update multipliers based on new diameter measurements diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index dae25feea3..6831d151f9 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -68,7 +68,7 @@ #include "servo.h" #endif -#if ENABLED(SENSORLESS_PROBING) +#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) #include "stepper.h" #include "../feature/tmc_util.h" #endif @@ -92,6 +92,10 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() const xy_pos_t &Probe::offset_xy = Probe::offset; #endif +#if ENABLED(SENSORLESS_PROBING) + Probe::sense_bool_t Probe::test_sensitivity; +#endif + #if ENABLED(Z_PROBE_SLED) #ifndef SLED_DOCKING_OFFSET @@ -493,11 +497,12 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ENABLED(SENSORLESS_PROBING) sensorless_t stealth_states { false }; #if ENABLED(DELTA) - stealth_states.x = tmc_enable_stallguard(stepperX); - stealth_states.y = tmc_enable_stallguard(stepperY); + if (probe.test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall + if (probe.test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); #endif - stealth_states.z = tmc_enable_stallguard(stepperZ); + if (probe.test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall endstops.enable(true); + set_homing_current(true); // The "homing" current also applies to probing #endif TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); @@ -520,10 +525,11 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ENABLED(SENSORLESS_PROBING) endstops.not_homing(); #if ENABLED(DELTA) - tmc_disable_stallguard(stepperX, stealth_states.x); - tmc_disable_stallguard(stepperY, stealth_states.y); + if (probe.test_sensitivity.x) tmc_disable_stallguard(stepperX, stealth_states.x); + if (probe.test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); #endif - tmc_disable_stallguard(stepperZ, stealth_states.z); + if (probe.test_sensitivity.z) tmc_disable_stallguard(stepperZ, stealth_states.z); + set_homing_current(false); #endif if (probe_triggered && TERN0(BLTOUCH_SLOW_MODE, bltouch.stow())) // Stow in LOW SPEED MODE on every trigger @@ -815,4 +821,93 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif // HAS_Z_SERVO_PROBE +#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) + + sensorless_t stealth_states { false }; + + /** + * Disable stealthChop if used. Enable diag1 pin on driver. + */ + void Probe::enable_stallguard_diag1() { + #if ENABLED(SENSORLESS_PROBING) + #if ENABLED(DELTA) + stealth_states.x = tmc_enable_stallguard(stepperX); + stealth_states.y = tmc_enable_stallguard(stepperY); + #endif + stealth_states.z = tmc_enable_stallguard(stepperZ); + endstops.enable(true); + #endif + } + + /** + * Re-enable stealthChop if used. Disable diag1 pin on driver. + */ + void Probe::disable_stallguard_diag1() { + #if ENABLED(SENSORLESS_PROBING) + endstops.not_homing(); + #if ENABLED(DELTA) + tmc_disable_stallguard(stepperX, stealth_states.x); + tmc_disable_stallguard(stepperY, stealth_states.y); + #endif + tmc_disable_stallguard(stepperZ, stealth_states.z); + #endif + } + + /** + * Change the current in the TMC drivers to N##_CURRENT_HOME. And we save the current configuration of each TMC driver. + */ + void Probe::set_homing_current(const bool onoff) { + #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Z) + #if ENABLED(DELTA) + static int16_t saved_current_X, saved_current_Y; + #endif + #if HAS_CURRENT_HOME(Z) + static int16_t saved_current_Z; + #endif + auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); } + }; + if (onoff) { + #if ENABLED(DELTA) + #if HAS_CURRENT_HOME(X) + saved_current_X = stepperX.getMilliamps(); + stepperX.rms_current(X_CURRENT_HOME); + debug_current_on(PSTR("X"), saved_current_X, X_CURRENT_HOME); + #endif + #if HAS_CURRENT_HOME(Y) + saved_current_Y = stepperY.getMilliamps(); + stepperY.rms_current(Y_CURRENT_HOME); + debug_current_on(PSTR("Y"), saved_current_Y, Y_CURRENT_HOME); + #endif + #endif + #if HAS_CURRENT_HOME(Z) + saved_current_Z = stepperZ.getMilliamps(); + stepperZ.rms_current(Z_CURRENT_HOME); + debug_current_on(PSTR("Z"), saved_current_Z, Z_CURRENT_HOME); + #endif + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(true)); + } + else { + #if ENABLED(DELTA) + #if HAS_CURRENT_HOME(X) + stepperX.rms_current(saved_current_X); + debug_current_on(PSTR("X"), X_CURRENT_HOME, saved_current_X); + #endif + #if HAS_CURRENT_HOME(Y) + stepperY.rms_current(saved_current_Y); + debug_current_on(PSTR("Y"), Y_CURRENT_HOME, saved_current_Y); + #endif + #endif + #if HAS_CURRENT_HOME(Z) + stepperZ.rms_current(saved_current_Z); + debug_current_on(PSTR("Z"), Z_CURRENT_HOME, saved_current_Z); + #endif + TERN_(IMPROVE_HOMING_RELIABILITY, planner.enable_stall_prevention(false)); + } + #endif + } + +#endif // SENSORLESS_PROBING + #endif // HAS_BED_PROBE diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index da46c830f6..62880c865f 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -56,6 +56,11 @@ class Probe { public: + #if ENABLED(SENSORLESS_PROBING) + typedef struct { bool x:1, y:1, z:1; } sense_bool_t; + static sense_bool_t test_sensitivity; + #endif + #if HAS_BED_PROBE static xyz_pos_t offset; @@ -256,6 +261,13 @@ public: static bool tare(); #endif + // Basic functions for Sensorless Homing and Probing + #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + static void enable_stallguard_diag1(); + static void disable_stallguard_diag1(); + static void set_homing_current(const bool onoff); + #endif + private: static bool probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s); static void do_z_raise(const float z_raise); From fa6b01c677fbcdabe6972be4a20571ffe3f38415 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 12 Jul 2021 18:35:00 -0600 Subject: [PATCH 0386/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Fixes=20to=20FTD?= =?UTF-8?q?I=20Eve=20Touch=20UI=20(#22347)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/command_processor.h | 16 +++- .../ftdi_eve_lib/extended/text_box.cpp | 74 +++++++++++-------- .../generic/about_screen.cpp | 7 +- .../generic/interface_settings_screen.cpp | 46 ++++-------- .../generic/save_settings_dialog_box.cpp | 4 + .../generic/save_settings_dialog_box.h | 1 + .../lcd/extui/ftdi_eve_touch_ui/theme/fonts.h | 2 +- 7 files changed, 81 insertions(+), 69 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 8561eb05a2..9a83e9ee09 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -209,11 +209,25 @@ class CommandProcessor : public CLCD::CommandFifo { inline CommandProcessor& rectangle(int16_t x, int16_t y, int16_t w, int16_t h) { using namespace FTDI; CLCD::CommandFifo::cmd(BEGIN(RECTS)); - CLCD::CommandFifo::cmd(VERTEX2F(x * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); return *this; } + inline CommandProcessor& border(int16_t x, int16_t y, int16_t w, int16_t h) { + using namespace FTDI; + CLCD::CommandFifo::cmd(BEGIN(LINES)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, y * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F((x + w) * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, (y + h) * 16)); + CLCD::CommandFifo::cmd(VERTEX2F( x * 16, y * 16)); + return *this; + } + template FORCEDINLINE CommandProcessor& toggle(int16_t x, int16_t y, int16_t w, int16_t h, T text, bool state, uint16_t options = FTDI::OPT_3D) { CLCD::FontMetrics fm(_font); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 9f73c7dfb8..f3f518359c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -29,25 +29,30 @@ namespace FTDI { * be broken so that the display width is less than w. The line will also * be broken after a '\n'. Returns the display width of the line. */ - static uint16_t find_line_break(const FontMetrics &fm, uint16_t w, const char *str, const char *&end) { - w -= fm.get_char_width(' '); + static uint16_t find_line_break(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const uint16_t w, const char *str, const char *&end, bool use_utf8) { const char *p = str; end = str; uint16_t lw = 0, result = 0; for (;;) { - utf8_char_t c = get_utf8_char_and_inc(p); - if (c == ' ' || c == '\n' || c == '\0') { - if (lw < w || end == str) { - end = (c == '\0') ? p-1 : p; + const char *next = p; + utf8_char_t c = get_utf8_char_and_inc(next); + // Decide whether to break the string at this location + if (c == '\n' || c == '\0' || c == ' ') { + end = p; + result = lw; + } + if (c == '\n' || c == '\0') break; + // Now add the length of the current character to the tally. + lw += use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c]; + // Stop processing once string exceeds the display width + if (lw >= w) { + if (end == str) { + end = p; result = lw; } - if (c == '\0' || c == '\n') break; + break; } - lw += fm.get_char_width(c); - } - if (end == str) { - end = p-1; - result = lw; + p = next; } return result; } @@ -55,17 +60,18 @@ namespace FTDI { /** * This function returns a measurements of the word-wrapped text box. */ - static void measure_text_box(const FontMetrics &fm, const char *str, uint16_t &width, uint16_t &height) { + static void measure_text_box(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const char *str, uint16_t &width, uint16_t &height, bool use_utf8) { const char *line_start = (const char*)str; const char *line_end; const uint16_t wrap_width = width; width = height = 0; for (;;) { - uint16_t line_width = find_line_break(fm, wrap_width, line_start, line_end); - if (line_end == line_start) break; + uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); width = max(width, line_width); - height += fm.get_height(); + height += utf8_fm.get_height(); line_start = line_end; + if (line_start[0] == '\n' || line_start[0] == ' ') line_start++; + if (line_start[0] == '\0') break; } } @@ -73,41 +79,45 @@ namespace FTDI { * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. */ void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options, uint8_t font) { + #if ENABLED(TOUCH_UI_USE_UTF8) + const bool use_utf8 = has_utf8_chars(str); + #else + constexpr bool use_utf8 = false; + #endif uint16_t box_width, box_height; - FontMetrics fm(font); + FontMetrics utf8_fm(font); + CLCD::FontMetrics clcd_fm; + clcd_fm.load(font); // Shrink the font until we find a font that fits for (;;) { box_width = w; - measure_text_box(fm, str, box_width, box_height); + measure_text_box(utf8_fm, clcd_fm, str, box_width, box_height, use_utf8); if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; if (font == 26) break; - fm.load(--font); + utf8_fm.load(--font); + clcd_fm.load(font); } const uint16_t dx = (options & OPT_RIGHTX) ? w : - (options & OPT_CENTERX) ? w/2 : 0; - const uint16_t dy = (options & OPT_BOTTOMY) ? (h - box_height) : - (options & OPT_CENTERY) ? (h - box_height)/2 : 0; + (options & OPT_CENTERX) ? w / 2 : 0, + dy = (options & OPT_BOTTOMY) ? (h - box_height) : + (options & OPT_CENTERY) ? (h - box_height) / 2 : 0; - const char *line_start = str; - const char *line_end; + const char *line_start = str, *line_end; for (;;) { - find_line_break(fm, w, line_start, line_end); - if (line_end == line_start) break; + find_line_break(utf8_fm, clcd_fm, w, line_start, line_end, use_utf8); const size_t line_len = line_end - line_start; if (line_len) { char line[line_len + 1]; strncpy(line, line_start, line_len); line[line_len] = 0; - if (line[line_len - 1] == '\n' || line[line_len - 1] == ' ') - line[line_len - 1] = 0; #if ENABLED(TOUCH_UI_USE_UTF8) - if (has_utf8_chars(line)) { - draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY)); + if (use_utf8) { + draw_utf8_text(cmd, x + dx, y + dy, line, utf8_fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY)); } else #endif { @@ -115,9 +125,11 @@ namespace FTDI { cmd.CLCD::CommandFifo::str(line); } } - y += fm.get_height(); + y += utf8_fm.get_height(); line_start = line_end; + if (line_start[0] == '\n' || line_start[0] == ' ') line_start++; + if (line_start[0] == '\0') break; } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 4e90e71e8a..68e50c90ac 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -44,16 +44,13 @@ void AboutScreen::onRedraw(draw_mode_t) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define HEADING_POS BTN_POS(1,1), BTN_SIZE(4,2) #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,3) #define STATS_POS BTN_POS(1,8), BTN_SIZE(2,1) #define BACK_POS BTN_POS(3,8), BTN_SIZE(2,1) - #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h - #define INSET_POS(pos) _INSET_POS(pos) - char about_str[1 + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) #ifdef TOOLHEAD_NAME @@ -89,7 +86,7 @@ void AboutScreen::onRedraw(draw_mode_t) { , OPT_CENTER, font_medium); cmd.tag(0); draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); - draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium); #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp index 568da53524..a3febb39a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp @@ -58,11 +58,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { #define GRID_COLS 4 - #if ENABLED(TOUCH_UI_PORTRAIT) - #define GRID_ROWS 7 - #else - #define GRID_ROWS 6 - #endif + #define GRID_ROWS TERN(TOUCH_UI_PORTRAIT, 7, 6) cmd.cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) @@ -77,21 +73,19 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { #if DISABLED(LCD_FYSETC_TFT81050) .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) #endif - .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) - .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY); + #if ENABLED(FTDI_LOCK_SCREEN) + cmd.text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + #endif #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) - cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); + cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); #endif #undef EDGE_R } if (what & FOREGROUND) { - #if defined(FTDI_LOCK_SCREEN) || DISABLED(TOUCH_UI_NO_BOOTSCREEN) - #if ENABLED(TOUCH_UI_PORTRAIT) - constexpr uint8_t w = 2; - #else - constexpr uint8_t w = 1; - #endif + #if ENABLED(FTDI_LOCK_SCREEN) || DISABLED(TOUCH_UI_NO_BOOTSCREEN) + constexpr uint8_t w = TERN(TOUCH_UI_PORTRAIT, 2, 1); #endif cmd.font(font_medium) @@ -101,7 +95,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .tag(2).slider(BTN_POS(3,2), BTN_SIZE(2,1), mydata.brightness, 128) #endif .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), mydata.volume, 0xFF) - #ifdef FTDI_LOCK_SCREEN + #if ENABLED(FTDI_LOCK_SCREEN) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) #endif @@ -126,7 +120,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { bool InterfaceSettingsScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); return true; - #ifdef FTDI_LOCK_SCREEN + #if ENABLED(FTDI_LOCK_SCREEN) case 4: if (!LockScreen::is_enabled()) LockScreen::enable(); @@ -185,8 +179,7 @@ void InterfaceSettingsScreen::onIdle() { } void InterfaceSettingsScreen::failSafeSettings() { - // Reset settings that may make the printer interface - // unusable. + // Reset settings that may make the printer interface unusable. CLCD::mem_write_32(CLCD::REG::ROTATE, 0); CLCD::default_touch_transform(); CLCD::default_display_orientation(); @@ -197,9 +190,7 @@ void InterfaceSettingsScreen::failSafeSettings() { } void InterfaceSettingsScreen::defaultSettings() { - #ifdef FTDI_LOCK_SCREEN - LockScreen::passcode = 0; - #endif + TERN_(FTDI_LOCK_SCREEN, LockScreen::passcode = 0); SoundPlayer::set_volume(255); CLCD::set_brightness(255); UIData::reset_persistent_data(); @@ -218,11 +209,7 @@ void InterfaceSettingsScreen::saveSettings(char *buff) { persistent_data_t eeprom; - #ifdef FTDI_LOCK_SCREEN - eeprom.passcode = LockScreen::passcode; - #else - eeprom.passcode = 0; - #endif + eeprom.passcode = TERN0(FTDI_LOCK_SCREEN, LockScreen::passcode); eeprom.sound_volume = SoundPlayer::get_volume(); eeprom.display_brightness = CLCD::get_brightness(); eeprom.bit_flags = UIData::get_persistent_data(); @@ -251,7 +238,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { SERIAL_ECHOLNPGM("Loading setting from EEPROM"); - #ifdef FTDI_LOCK_SCREEN + #if ENABLED(FTDI_LOCK_SCREEN) LockScreen::passcode = eeprom.passcode; #endif SoundPlayer::set_volume(eeprom.sound_volume); @@ -282,10 +269,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { if (success) success = persistentStore.write_data(0, data, ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE) == PERSISTENT_STORE_SUCCESS; - if (success) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_EEPROM_RESTORED)); - else - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_EEPROM_RESET)); + StatusScreen::setStatusMessage(success ? GET_TEXT_F(MSG_EEPROM_RESTORED) : GET_TEXT_F(MSG_EEPROM_RESET)); return success; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp index 176630d11e..5d92052ace 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp @@ -60,4 +60,8 @@ void SaveSettingsDialogBox::promptToSaveSettings() { GOTO_PREVIOUS(); // No save needed. } +void SaveSettingsDialogBox::promptToSaveAndStay() { + if (needs_save) GOTO_SCREEN(SaveSettingsDialogBox); +} + #endif // FTDI_SAVE_SETTINGS_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h index 8985a974fe..0cbadfbbe6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.h @@ -34,5 +34,6 @@ class SaveSettingsDialogBox : public DialogBoxBaseClass, public UncachedScreen { static bool onTouchEnd(uint8_t tag); static void promptToSaveSettings(); + static void promptToSaveAndStay(); static void settingsChanged() {needs_save = true;} }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h index 7cc4e078ad..63ecdfcb3c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/fonts.h @@ -55,7 +55,7 @@ namespace Theme { constexpr int16_t font_small = 27; constexpr int16_t font_medium = 28; constexpr int16_t font_large = 30; - constexpr int16_t font_xlarge = 31; + constexpr int16_t font_xlarge = 30; constexpr float icon_scale = 0.6; #endif #elif defined(TOUCH_UI_320x240) From d95e32f95015d1dac8a5dd51a78638706ff21c09 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 13 Jul 2021 00:59:56 +0000 Subject: [PATCH 0387/2168] [cron] Bump distribution date (2021-07-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c2df42881a..5cfb8c0a07 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-12" +//#define STRING_DISTRIBUTION_DATE "2021-07-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b8a83e02ca..2834d3888b 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 "2021-07-12" + #define STRING_DISTRIBUTION_DATE "2021-07-13" #endif /** From 315a722b420226be0c07c05abf95a5b666caf1e6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Jul 2021 22:52:17 -0500 Subject: [PATCH 0388/2168] =?UTF-8?q?=F0=9F=90=9B=20TM3D=20fixes=20and=20i?= =?UTF-8?q?mprovements?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> --- Marlin/src/core/serial.h | 2 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 16 +++++++++------- .../cocoa_press/leveling_menu.cpp | 4 ++-- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 4 +++- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 7 ++++++- 6 files changed, 22 insertions(+), 13 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index a5afb9d895..ee6c0e6eae 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -67,7 +67,7 @@ extern uint8_t marlin_debug_flags; // Serial redirection // // Step 1: Find out what the first serial leaf is -#if BOTH(HAS_MULTI_SERIAL, SERIAL_CATCHALL) +#if HAS_MULTI_SERIAL && defined(SERIAL_CATCHALL) #define _SERIAL_LEAF_1 MYSERIAL #else #define _SERIAL_LEAF_1 MYSERIAL1 diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 9aea68dfcb..114590a043 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -2417,13 +2417,15 @@ void Draw_HomeOff_Menu() { #include "../../../libs/buzzer.h" void HMI_AudioFeedback(const bool success=true) { - if (success) { - buzzer.tone(100, 659); - buzzer.tone(10, 0); - buzzer.tone(100, 698); - } - else - buzzer.tone(40, 440); + #if HAS_BUZZER + if (success) { + buzzer.tone(100, 659); + buzzer.tone(10, 0); + buzzer.tone(100, 698); + } + else + buzzer.tone(40, 440); + #endif } /* Prepare */ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index 57c8a7505c..6718fe0a41 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -23,9 +23,9 @@ #include "../config.h" #include "../screens.h" -#ifdef COCOA_LEVELING_MENU +#if ENABLED(COCOA_LEVELING_MENU) -#if BOTH(HAS_BED_PROBE,BLTOUCH) +#if BOTH(HAS_BED_PROBE, BLTOUCH) #include "../../../../feature/bltouch.h" #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 7173790262..4ef96251bc 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1057,7 +1057,7 @@ namespace ExtUI { return isPrinting() && (isPrintingFromMediaPaused() || print_job_timer.isPaused()); } - bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED() && card.isMounted()); } + bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED()); } void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index fb143fa8bc..2c271408b0 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -655,7 +655,9 @@ #define BEEPER_PIN EXP1_10_PIN #define BTN_ENC EXP1_09_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_04_PIN + #endif #ifndef KILL_PIN #define KILL_PIN EXP2_03_PIN diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index a8be2cfc07..63ad06dc57 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -172,8 +172,13 @@ // // Misc. Functions // -#define LED_CONTROL_PIN PA13 +#define CASE_LIGHT_PIN PA13 #ifndef NEOPIXEL_PIN #define NEOPIXEL_PIN PA8 #endif + +#define SUICIDE_PIN PC13 +#ifndef SUICIDE_PIN_INVERTING + #define SUICIDE_PIN_INVERTING false +#endif From 4479b0222bb66dd54f2c60f50a35a9d35f3230dc Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Mon, 12 Jul 2021 20:57:01 -0700 Subject: [PATCH 0389/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20TEMP?= =?UTF-8?q?=5FSENSOR=5FBOARD=20(#22343,=20#22344)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22279 --- Marlin/src/inc/Conditionals_adv.h | 4 +++- Marlin/src/inc/Conditionals_post.h | 17 +++++++++++++++++ Marlin/src/module/temperature.cpp | 16 ++++++++-------- Marlin/src/module/temperature.h | 2 +- buildroot/tests/mega2560 | 11 +++++++++++ 5 files changed, 40 insertions(+), 10 deletions(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 33ed0dad38..c781ebb595 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -127,7 +127,9 @@ // Usurp a sensor to do redundant readings #if TEMP_SENSOR_REDUNDANT - #define REDUNDANT_TEMP_MATCH(M,N) (TEMP_SENSOR_REDUNDANT_##M == HID_##N) + #define _HEATER_ID(M) HID_##M + #define HEATER_ID(M) _HEATER_ID(M) + #define REDUNDANT_TEMP_MATCH(M,N) (HEATER_ID(TEMP_SENSOR_REDUNDANT_##M) == _HEATER_ID(N)) #else #define REDUNDANT_TEMP_MATCH(...) 0 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d62debf755..1bac56339f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1135,6 +1135,23 @@ #endif #endif +#if TEMP_SENSOR_BOARD == -4 + #define TEMP_SENSOR_BOARD_IS_AD8495 1 +#elif TEMP_SENSOR_BOARD == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BOARD." +#elif TEMP_SENSOR_BOARD == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BOARD." +#elif TEMP_SENSOR_BOARD == -1 + #define TEMP_SENSOR_BOARD_IS_AD595 1 +#elif TEMP_SENSOR_BOARD > 0 + #define TEMP_SENSOR_BOARD_IS_THERMISTOR 1 + #if TEMP_SENSOR_BOARD == 1000 + #define TEMP_SENSOR_BOARD_IS_CUSTOM 1 + #elif TEMP_SENSOR_BOARD == 998 || TEMP_SENSOR_BOARD == 999 + #define TEMP_SENSOR_BOARD_IS_DUMMY 1 + #endif +#endif + /** * X_DUAL_ENDSTOPS endstop reassignment */ diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4a56ba66e9..fd2c260fd3 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -440,7 +440,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, board_info_t Temperature::temp_board; // = { 0 } #if ENABLED(THERMAL_PROTECTION_BOARD) int16_t Temperature::mintemp_raw_BOARD = TEMP_SENSOR_BOARD_RAW_LO_TEMP, - Temperature::maxtemp_raw_BOARD = TEMP_SENSOR_COOLER_RAW_HI_TEMP; + Temperature::maxtemp_raw_BOARD = TEMP_SENSOR_BOARD_RAW_HI_TEMP; #endif #endif @@ -951,7 +951,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms #if HAS_TEMP_REDUNDANT if (heater_id == H_REDUNDANT) { SERIAL_ECHOPGM(STR_REDUNDANT); // print redundant and cascade to print target, too. - real_heater_id = (heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET; + real_heater_id = (heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET); } #endif @@ -1323,7 +1323,7 @@ void Temperature::manage_heater() { #if HAS_TEMP_REDUNDANT // Make sure measured temperatures are close together if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) - _temp_error((heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); + _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); #endif #if HAS_AUTO_FAN @@ -2015,7 +2015,7 @@ void Temperature::updateTemperaturesFromRawValues() { TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].raw = READ_MAX_TC(1)); - TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(TEMP_SENSOR_REDUNDANT_SOURCE)); + TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(HEATER_ID(TEMP_SENSOR_REDUNDANT_SOURCE))); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); @@ -2455,9 +2455,9 @@ void Temperature::init() { while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif - #if HAS_TEMP_BOARD - while (analog_to_celsius_board(mintemp_raw_BOARD) > BOARD_MINTEMP) mintemp_raw_BOARD += TEMPDIR(BOARD) * (OVERSAMPLENR); - while (analog_to_celsius_board(maxtemp_raw_BOARD) < BOARD_MAXTEMP) maxtemp_raw_BOARD -= TEMPDIR(BOARD) * (OVERSAMPLENR); + #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + while (analog_to_celsius_board(mintemp_raw_BOARD) < BOARD_MINTEMP) mintemp_raw_BOARD += TEMPDIR(BOARD) * (OVERSAMPLENR); + while (analog_to_celsius_board(maxtemp_raw_BOARD) > BOARD_MAXTEMP) maxtemp_raw_BOARD -= TEMPDIR(BOARD) * (OVERSAMPLENR); #endif #if HAS_TEMP_REDUNDANT @@ -2473,7 +2473,7 @@ void Temperature::init() { #elif REDUNDANT_TEMP_MATCH(TARGET, BED) && HAS_TEMP_BED temp_bed #else - temp_hotend[TEMP_SENSOR_REDUNDANT_TARGET] + temp_hotend[HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET)] #endif ); #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 61993c43a8..c78dfa9372 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -815,7 +815,7 @@ class Temperature { static inline int16_t rawBoardTemp() { return temp_board.raw; } #endif static inline celsius_float_t degBoard() { return temp_board.celsius; } - static inline celsius_t wholeDegBoard() { return static_cast(degBoard() + 0.5f); } + static inline celsius_t wholeDegBoard() { return static_cast(temp_board.celsius + 0.5f); } #endif #if HAS_TEMP_REDUNDANT diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 0932388969..edae6d24ae 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -198,6 +198,17 @@ opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOO exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" +# +# Test redundant temperature sensors + MAX TC +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 1 \ + TEMP_SENSOR_0 -2 TEMP_SENSOR_REDUNDANT -2 \ + TEMP_SENSOR_REDUNDANT_SOURCE E1 TEMP_SENSOR_REDUNDANT_TARGET E0 \ + TEMP_0_CS_PIN 11 TEMP_1_CS_PIN 12 + +exec_test $1 $2 "MEGA2560 RAMPS | Redundant temperature sensor | 2x MAX6675" "$3" + # # Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER # From 3797549e7e873864f3cd11ab9185f01676c046e0 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 13 Jul 2021 17:08:04 -0700 Subject: [PATCH 0390/2168] =?UTF-8?q?=F0=9F=90=9B=20Board=20Temp=20Sensor?= =?UTF-8?q?=20followup=20(#22350)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/lcd/thermistornames.h | 2 + .../src/module/thermistor/thermistor_2000.h | 60 +++++++++++++++++++ Marlin/src/module/thermistor/thermistors.h | 3 + Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 2 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 2 +- 6 files changed, 68 insertions(+), 2 deletions(-) create mode 100644 Marlin/src/module/thermistor/thermistor_2000.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bdeb8d8501..4adc40a19f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -451,6 +451,7 @@ * 67 : 500kΩ SliceEngineering 450°C Thermistor * 70 : 100kΩ bq Hephestos 2 * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor * * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. * ------- (but gives greater accuracy and more stable PID) diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index f9f91ac49a..4f6dd23ece 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -128,6 +128,8 @@ #define THERMISTOR_NAME "Pt100 1K" #elif THERMISTOR_ID == 666 #define THERMISTOR_NAME "Einstart S" +#elif THERMISTOR_ID == 2000 + #define THERMISTOR_NAME "TDK NTCG104LH104JT1" // High Temperature thermistors #elif THERMISTOR_ID == 61 diff --git a/Marlin/src/module/thermistor/thermistor_2000.h b/Marlin/src/module/thermistor/thermistor_2000.h new file mode 100644 index 0000000000..3815a6f256 --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_2000.h @@ -0,0 +1,60 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +// R25 = 100 KOhm, beta25 = 4550 K, 4.7 kOhm pull-up, TDK NTCG104LH104KT1 https://product.tdk.com/en/search/sensor/ntc/chip-ntc-thermistor/info?part_no=NTCG104LH104KT1 +constexpr temp_entry_t temptable_2000[] PROGMEM = { +{ OV(313), 125 }, +{ OV(347), 120 }, +{ OV(383), 115 }, +{ OV(422), 110 }, +{ OV(463), 105 }, +{ OV(506), 100 }, +{ OV(549), 95 }, +{ OV(594), 90 }, +{ OV(638), 85 }, +{ OV(681), 80 }, +{ OV(722), 75 }, +{ OV(762), 70 }, +{ OV(799), 65 }, +{ OV(833), 60 }, +{ OV(863), 55 }, +{ OV(890), 50 }, +{ OV(914), 45 }, +{ OV(934), 40 }, +{ OV(951), 35 }, +{ OV(966), 30 }, +{ OV(978), 25 }, +{ OV(988), 20 }, +{ OV(996), 15 }, +{ OV(1002), 10 }, +{ OV(1007), 5 }, +{ OV(1012), 0 }, +{ OV(1015), -5 }, +{ OV(1017), -10 }, +{ OV(1019), -15 }, +{ OV(1020), -20 }, +{ OV(1021), -25 }, +{ OV(1022), -30 }, +{ OV(1023), -35 }, +{ OV(1023), -40 } +}; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 9351fa6eb1..28a1e2f90f 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -201,6 +201,9 @@ typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; #if ANY_THERMISTOR_IS(1047) // Pt1000 with 4k7 pullup #include "thermistor_1047.h" #endif +#if ANY_THERMISTOR_IS(2000) // "Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor" https://product.tdk.com/en/search/sensor/ntc/chip-ntc-thermistor/info?part_no=NTCG104LH104KT1 + #include "thermistor_2000.h" +#endif #if ANY_THERMISTOR_IS(998) // User-defined table 1 #include "thermistor_998.h" #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 5be2bba25c..78465dd7a8 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -116,7 +116,7 @@ // #define TEMP_0_PIN 0 // Analog Input, Header J2 #define TEMP_1_PIN 1 // Analog Input, Header J3 -#define TEMP_BOARD_PIN TEMP_1_PIN // Analog Input, Header J3 +#define TEMP_BOARD_PIN 91 // Onboard thermistor, 100k TDK NTCG104LH104JT1 #define TEMP_BED_PIN 2 // Analog Input, Header J6 #define TEMP_PROBE_PIN 3 // Analog Input, Header J15 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 866d94924a..2bfbb19427 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -161,7 +161,7 @@ // #define TEMP_0_PIN PA2 // T0 <-> E0 #define TEMP_1_PIN PA0 // T1 <-> E1 -#define TEMP_BOARD_PIN TEMP_1_PIN // Onboard sensor shared with T1 +#define TEMP_BOARD_PIN PC2 // Onboard thermistor, NTC100K #define TEMP_BED_PIN PA1 // T2 <-> Bed #define TEMP_PROBE_PIN PC3 // Shares J4 connector with PD1 From 9a7727e61c76a9e30fda85d8ac33392be0e453c0 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Tue, 13 Jul 2021 17:13:06 -0700 Subject: [PATCH 0391/2168] =?UTF-8?q?=F0=9F=8E=A8=20Define=20temp=20sensor?= =?UTF-8?q?=20conditionals=20earlier=20(#22342)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_adv.h | 419 +++++++++++++++++++++++++++-- Marlin/src/inc/Conditionals_post.h | 392 +-------------------------- 2 files changed, 402 insertions(+), 409 deletions(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index c781ebb595..55ae6ec535 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -112,27 +112,9 @@ #undef STEALTHCHOP_E #endif -#if TEMP_SENSOR_BED == 0 - #undef THERMAL_PROTECTION_BED - #undef THERMAL_PROTECTION_BED_PERIOD -#endif - -#if TEMP_SENSOR_CHAMBER == 0 - #undef THERMAL_PROTECTION_CHAMBER -#endif - -#if TEMP_SENSOR_COOLER == 0 - #undef THERMAL_PROTECTION_COOLER -#endif - -// Usurp a sensor to do redundant readings -#if TEMP_SENSOR_REDUNDANT - #define _HEATER_ID(M) HID_##M - #define HEATER_ID(M) _HEATER_ID(M) - #define REDUNDANT_TEMP_MATCH(M,N) (HEATER_ID(TEMP_SENSOR_REDUNDANT_##M) == _HEATER_ID(N)) -#else - #define REDUNDANT_TEMP_MATCH(...) 0 -#endif +/** + * Temperature Sensors; define what sensor(s) we have. + */ // Temperature sensor IDs #define HID_REDUNDANT -6 @@ -150,6 +132,401 @@ #define HID_E6 6 #define HID_E7 7 +#define ANY_TEMP_SENSOR_IS(n) (n == TEMP_SENSOR_0 || n == TEMP_SENSOR_1 || n == TEMP_SENSOR_2 || n == TEMP_SENSOR_3 \ + || n == TEMP_SENSOR_4 || n == TEMP_SENSOR_5 || n == TEMP_SENSOR_6 || n == TEMP_SENSOR_7 \ + || n == TEMP_SENSOR_BED \ + || n == TEMP_SENSOR_PROBE \ + || n == TEMP_SENSOR_CHAMBER \ + || n == TEMP_SENSOR_COOLER \ + || n == TEMP_SENSOR_REDUNDANT ) +#if ANY_TEMP_SENSOR_IS(1000) + #define HAS_USER_THERMISTORS 1 +#endif +#undef ANY_TEMP_SENSOR_IS + +#if TEMP_SENSOR_REDUNDANT + #define _HEATER_ID(M) HID_##M + #define HEATER_ID(M) _HEATER_ID(M) + #define REDUNDANT_TEMP_MATCH(M,N) (HEATER_ID(TEMP_SENSOR_REDUNDANT_##M) == _HEATER_ID(N)) +#else + #define REDUNDANT_TEMP_MATCH(...) 0 +#endif + +#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 + #define TEMP_SENSOR_0_IS_MAX_TC 1 + #if TEMP_SENSOR_0 == -5 + #define TEMP_SENSOR_0_IS_MAX31865 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif + #elif TEMP_SENSOR_0 == -3 + #define TEMP_SENSOR_0_IS_MAX31855 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN -270 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_0 == -2 + #define TEMP_SENSOR_0_IS_MAX6675 1 + #define TEMP_SENSOR_0_MAX_TC_TMIN 0 + #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 + #endif +#elif TEMP_SENSOR_0 == -4 + #define TEMP_SENSOR_0_IS_AD8495 1 +#elif TEMP_SENSOR_0 == -1 + #define TEMP_SENSOR_0_IS_AD595 1 +#elif TEMP_SENSOR_0 > 0 + #define TEMP_SENSOR_0_IS_THERMISTOR 1 + #if TEMP_SENSOR_0 == 1000 + #define TEMP_SENSOR_0_IS_CUSTOM 1 + #elif TEMP_SENSOR_0 == 998 || TEMP_SENSOR_0 == 999 + #define TEMP_SENSOR_0_IS_DUMMY 1 + #endif +#else + #undef HEATER_0_MINTEMP + #undef HEATER_0_MAXTEMP +#endif + +#if TEMP_SENSOR_1 == -5 || TEMP_SENSOR_1 == -3 || TEMP_SENSOR_1 == -2 + #define TEMP_SENSOR_1_IS_MAX_TC 1 + #if TEMP_SENSOR_1 == -5 + #define TEMP_SENSOR_1_IS_MAX31865 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN 0 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #elif TEMP_SENSOR_1 == -3 + #define TEMP_SENSOR_1_IS_MAX31855 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN -270 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_1 == -2 + #define TEMP_SENSOR_1_IS_MAX6675 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN 0 + #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 + #endif + + #if TEMP_SENSOR_1 != TEMP_SENSOR_0 + #if TEMP_SENSOR_1 == -5 + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." + #elif TEMP_SENSOR_1 == -3 + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." + #elif TEMP_SENSOR_1 == -2 + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." + #endif + #endif +#elif TEMP_SENSOR_1 == -4 + #define TEMP_SENSOR_1_IS_AD8495 1 +#elif TEMP_SENSOR_1 == -1 + #define TEMP_SENSOR_1_IS_AD595 1 +#elif TEMP_SENSOR_1 > 0 + #define TEMP_SENSOR_1_IS_THERMISTOR 1 + #if TEMP_SENSOR_1 == 1000 + #define TEMP_SENSOR_1_IS_CUSTOM 1 + #elif TEMP_SENSOR_1 == 998 || TEMP_SENSOR_1 == 999 + #define TEMP_SENSOR_1_IS_DUMMY 1 + #endif +#else + #undef HEATER_1_MINTEMP + #undef HEATER_1_MAXTEMP +#endif + +#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 + #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 + + #if TEMP_SENSOR_REDUNDANT == -5 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + + #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 + #elif TEMP_SENSOR_REDUNDANT == -3 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + + #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_REDUNDANT == -2 + #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + + #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 + #endif + + // mimic setting up the source TEMP_SENSOR + #if REDUNDANT_TEMP_MATCH(SOURCE, E0) + #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #ifndef MAX31865_SENSOR_WIRES_0 + #define MAX31865_SENSOR_WIRES_0 2 + #endif + #elif REDUNDANT_TEMP_MATCH(SOURCE, E1) + #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #ifndef MAX31865_SENSOR_WIRES_1 + #define MAX31865_SENSOR_WIRES_1 2 + #endif + #endif + + #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) + #if TEMP_SENSOR_REDUNDANT == -5 + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -3 + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -2 + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #endif + #endif +#elif TEMP_SENSOR_REDUNDANT == -4 + #define TEMP_SENSOR_REDUNDANT_IS_AD8495 1 +#elif TEMP_SENSOR_REDUNDANT == -1 + #define TEMP_SENSOR_REDUNDANT_IS_AD595 1 +#elif TEMP_SENSOR_REDUNDANT > 0 + #define TEMP_SENSOR_REDUNDANT_IS_THERMISTOR 1 + #if TEMP_SENSOR_REDUNDANT == 1000 + #define TEMP_SENSOR_REDUNDANT_IS_CUSTOM 1 + #elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 + #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." + #endif +#endif + +#if TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC + #define HAS_MAX_TC 1 +#endif +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 + #define HAS_MAX6675 1 +#endif +#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 + #define HAS_MAX31855 1 +#endif +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 + #define HAS_MAX31865 1 +#endif + +#if TEMP_SENSOR_2 == -4 + #define TEMP_SENSOR_2_IS_AD8495 1 +#elif TEMP_SENSOR_2 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_2." +#elif TEMP_SENSOR_2 == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_2." +#elif TEMP_SENSOR_2 == -1 + #define TEMP_SENSOR_2_IS_AD595 1 +#elif TEMP_SENSOR_2 > 0 + #define TEMP_SENSOR_2_IS_THERMISTOR 1 + #if TEMP_SENSOR_2 == 1000 + #define TEMP_SENSOR_2_IS_CUSTOM 1 + #elif TEMP_SENSOR_2 == 998 || TEMP_SENSOR_2 == 999 + #define TEMP_SENSOR_2_IS_DUMMY 1 + #endif +#else + #undef HEATER_2_MINTEMP + #undef HEATER_2_MAXTEMP +#endif + +#if TEMP_SENSOR_3 == -4 + #define TEMP_SENSOR_3_IS_AD8495 1 +#elif TEMP_SENSOR_3 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_3." +#elif TEMP_SENSOR_3 == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_3." +#elif TEMP_SENSOR_3 == -1 + #define TEMP_SENSOR_3_IS_AD595 1 +#elif TEMP_SENSOR_3 > 0 + #define TEMP_SENSOR_3_IS_THERMISTOR 1 + #if TEMP_SENSOR_3 == 1000 + #define TEMP_SENSOR_3_IS_CUSTOM 1 + #elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 + #define TEMP_SENSOR_3_IS_DUMMY 1 + #endif +#else + #undef HEATER_3_MINTEMP + #undef HEATER_3_MAXTEMP +#endif + +#if TEMP_SENSOR_4 == -4 + #define TEMP_SENSOR_4_IS_AD8495 1 +#elif TEMP_SENSOR_4 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_4." +#elif TEMP_SENSOR_4 == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_4." +#elif TEMP_SENSOR_4 == -1 + #define TEMP_SENSOR_4_IS_AD595 1 +#elif TEMP_SENSOR_4 > 0 + #define TEMP_SENSOR_4_IS_THERMISTOR 1 + #if TEMP_SENSOR_4 == 1000 + #define TEMP_SENSOR_4_IS_CUSTOM 1 + #elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 + #define TEMP_SENSOR_4_IS_DUMMY 1 + #endif +#else + #undef HEATER_4_MINTEMP + #undef HEATER_4_MAXTEMP +#endif + +#if TEMP_SENSOR_5 == -4 + #define TEMP_SENSOR_5_IS_AD8495 1 +#elif TEMP_SENSOR_5 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_5." +#elif TEMP_SENSOR_5 == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_5." +#elif TEMP_SENSOR_5 == -1 + #define TEMP_SENSOR_5_IS_AD595 1 +#elif TEMP_SENSOR_5 > 0 + #define TEMP_SENSOR_5_IS_THERMISTOR 1 + #if TEMP_SENSOR_5 == 1000 + #define TEMP_SENSOR_5_IS_CUSTOM 1 + #elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 + #define TEMP_SENSOR_5_IS_DUMMY 1 + #endif +#else + #undef HEATER_5_MINTEMP + #undef HEATER_5_MAXTEMP +#endif + +#if TEMP_SENSOR_6 == -4 + #define TEMP_SENSOR_6_IS_AD8495 1 +#elif TEMP_SENSOR_6 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_6." +#elif TEMP_SENSOR_6 == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_6." +#elif TEMP_SENSOR_6 == -1 + #define TEMP_SENSOR_6_IS_AD595 1 +#elif TEMP_SENSOR_6 > 0 + #define TEMP_SENSOR_6_IS_THERMISTOR 1 + #if TEMP_SENSOR_6 == 1000 + #define TEMP_SENSOR_6_IS_CUSTOM 1 + #elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 + #define TEMP_SENSOR_6_IS_DUMMY 1 + #endif +#else + #undef HEATER_6_MINTEMP + #undef HEATER_6_MAXTEMP +#endif + +#if TEMP_SENSOR_7 == -4 + #define TEMP_SENSOR_7_IS_AD8495 1 +#elif TEMP_SENSOR_7 == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_7." +#elif TEMP_SENSOR_7 == -2 + #error "MAX7775 Thermocouples (-2) not supported for TEMP_SENSOR_7." +#elif TEMP_SENSOR_7 == -1 + #define TEMP_SENSOR_7_IS_AD595 1 +#elif TEMP_SENSOR_7 > 0 + #define TEMP_SENSOR_7_IS_THERMISTOR 1 + #if TEMP_SENSOR_7 == 1000 + #define TEMP_SENSOR_7_IS_CUSTOM 1 + #elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 + #define TEMP_SENSOR_7_IS_DUMMY 1 + #endif +#else + #undef HEATER_7_MINTEMP + #undef HEATER_7_MAXTEMP +#endif + +#if TEMP_SENSOR_BED == -4 + #define TEMP_SENSOR_BED_IS_AD8495 1 +#elif TEMP_SENSOR_BED == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BED." +#elif TEMP_SENSOR_BED == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BED." +#elif TEMP_SENSOR_BED == -1 + #define TEMP_SENSOR_BED_IS_AD595 1 +#elif TEMP_SENSOR_BED > 0 + #define TEMP_SENSOR_BED_IS_THERMISTOR 1 + #if TEMP_SENSOR_BED == 1000 + #define TEMP_SENSOR_BED_IS_CUSTOM 1 + #elif TEMP_SENSOR_BED == 998 || TEMP_SENSOR_BED == 999 + #define TEMP_SENSOR_BED_IS_DUMMY 1 + #endif +#else + #undef THERMAL_PROTECTION_BED + #undef THERMAL_PROTECTION_BED_PERIOD + #undef BED_MINTEMP + #undef BED_MAXTEMP +#endif + +#if TEMP_SENSOR_CHAMBER == -4 + #define TEMP_SENSOR_CHAMBER_IS_AD8495 1 +#elif TEMP_SENSOR_CHAMBER == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_CHAMBER." +#elif TEMP_SENSOR_CHAMBER == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_CHAMBER." +#elif TEMP_SENSOR_CHAMBER == -1 + #define TEMP_SENSOR_CHAMBER_IS_AD595 1 +#elif TEMP_SENSOR_CHAMBER > 0 + #define TEMP_SENSOR_CHAMBER_IS_THERMISTOR 1 + #if TEMP_SENSOR_CHAMBER == 1000 + #define TEMP_SENSOR_CHAMBER_IS_CUSTOM 1 + #elif TEMP_SENSOR_CHAMBER == 998 || TEMP_SENSOR_CHAMBER == 999 + #define TEMP_SENSOR_CHAMBER_IS_DUMMY 1 + #endif +#else + #undef THERMAL_PROTECTION_CHAMBER + #undef CHAMBER_MINTEMP + #undef CHAMBER_MAXTEMP +#endif + +#if TEMP_SENSOR_COOLER == -4 + #define TEMP_SENSOR_COOLER_IS_AD8495 1 +#elif TEMP_SENSOR_COOLER == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_COOLER." +#elif TEMP_SENSOR_COOLER == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_COOLER." +#elif TEMP_SENSOR_COOLER == -1 + #define TEMP_SENSOR_COOLER_IS_AD595 1 +#elif TEMP_SENSOR_COOLER > 0 + #define TEMP_SENSOR_COOLER_IS_THERMISTOR 1 + #if TEMP_SENSOR_COOLER == 1000 + #define TEMP_SENSOR_COOLER_IS_CUSTOM 1 + #elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 + #define TEMP_SENSOR_COOLER_IS_DUMMY 1 + #endif +#else + #undef THERMAL_PROTECTION_COOLER + #undef COOLER_MINTEMP + #undef COOLER_MAXTEMP +#endif + +#if TEMP_SENSOR_PROBE == -4 + #define TEMP_SENSOR_PROBE_IS_AD8495 1 +#elif TEMP_SENSOR_PROBE == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_PROBE." +#elif TEMP_SENSOR_PROBE == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_PROBE." +#elif TEMP_SENSOR_PROBE == -1 + #define TEMP_SENSOR_PROBE_IS_AD595 1 +#elif TEMP_SENSOR_PROBE > 0 + #define TEMP_SENSOR_PROBE_IS_THERMISTOR 1 + #if TEMP_SENSOR_PROBE == 1000 + #define TEMP_SENSOR_PROBE_IS_CUSTOM 1 + #elif TEMP_SENSOR_PROBE == 998 || TEMP_SENSOR_PROBE == 999 + #define TEMP_SENSOR_PROBE_IS_DUMMY 1 + #endif +#endif + +#if TEMP_SENSOR_BOARD == -4 + #define TEMP_SENSOR_BOARD_IS_AD8495 1 +#elif TEMP_SENSOR_BOARD == -3 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BOARD." +#elif TEMP_SENSOR_BOARD == -2 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BOARD." +#elif TEMP_SENSOR_BOARD == -1 + #define TEMP_SENSOR_BOARD_IS_AD595 1 +#elif TEMP_SENSOR_BOARD > 0 + #define TEMP_SENSOR_BOARD_IS_THERMISTOR 1 + #if TEMP_SENSOR_BOARD == 1000 + #define TEMP_SENSOR_BOARD_IS_CUSTOM 1 + #elif TEMP_SENSOR_BOARD == 998 || TEMP_SENSOR_BOARD == 999 + #define TEMP_SENSOR_BOARD_IS_DUMMY 1 + #endif +#endif + #if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 1bac56339f..b6cf8eccb6 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -513,22 +513,9 @@ #endif /** - * Temp Sensor defines + * Temp Sensor defines; set up pins as needed. */ -#define ANY_TEMP_SENSOR_IS(n) ( \ - n == TEMP_SENSOR_0 || n == TEMP_SENSOR_1 || n == TEMP_SENSOR_2 || n == TEMP_SENSOR_3 \ - || n == TEMP_SENSOR_4 || n == TEMP_SENSOR_5 || n == TEMP_SENSOR_6 || n == TEMP_SENSOR_7 \ - || n == TEMP_SENSOR_BED \ - || n == TEMP_SENSOR_PROBE \ - || n == TEMP_SENSOR_CHAMBER \ - || n == TEMP_SENSOR_COOLER \ - || n == TEMP_SENSOR_REDUNDANT ) -#if ANY_TEMP_SENSOR_IS(1000) - #define HAS_USER_THERMISTORS 1 -#endif -#undef ANY_TEMP_SENSOR_IS - // Usurp a sensor to do redundant readings #if TEMP_SENSOR_REDUNDANT #ifndef TEMP_SENSOR_REDUNDANT_SOURCE @@ -617,166 +604,9 @@ #endif #endif -#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 - #define TEMP_SENSOR_0_IS_MAX_TC 1 - #if TEMP_SENSOR_0 == -5 - #define TEMP_SENSOR_0_IS_MAX31865 1 - #define TEMP_SENSOR_0_MAX_TC_TMIN 0 - #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 - #ifndef MAX31865_SENSOR_WIRES_0 - #define MAX31865_SENSOR_WIRES_0 2 - #endif - #elif TEMP_SENSOR_0 == -3 - #define TEMP_SENSOR_0_IS_MAX31855 1 - #define TEMP_SENSOR_0_MAX_TC_TMIN -270 - #define TEMP_SENSOR_0_MAX_TC_TMAX 1800 - #elif TEMP_SENSOR_0 == -2 - #define TEMP_SENSOR_0_IS_MAX6675 1 - #define TEMP_SENSOR_0_MAX_TC_TMIN 0 - #define TEMP_SENSOR_0_MAX_TC_TMAX 1024 - #endif -#elif TEMP_SENSOR_0 == -4 - #define TEMP_SENSOR_0_IS_AD8495 1 -#elif TEMP_SENSOR_0 == -1 - #define TEMP_SENSOR_0_IS_AD595 1 -#elif TEMP_SENSOR_0 > 0 - #define TEMP_SENSOR_0_IS_THERMISTOR 1 - #if TEMP_SENSOR_0 == 1000 - #define TEMP_SENSOR_0_IS_CUSTOM 1 - #elif TEMP_SENSOR_0 == 998 || TEMP_SENSOR_0 == 999 - #define TEMP_SENSOR_0_IS_DUMMY 1 - #endif -#else - #undef HEATER_0_MINTEMP - #undef HEATER_0_MAXTEMP -#endif - -#if TEMP_SENSOR_1 == -5 || TEMP_SENSOR_1 == -3 || TEMP_SENSOR_1 == -2 - #define TEMP_SENSOR_1_IS_MAX_TC 1 - #if TEMP_SENSOR_1 == -5 - #define TEMP_SENSOR_1_IS_MAX31865 1 - #define TEMP_SENSOR_1_MAX_TC_TMIN 0 - #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 - #ifndef MAX31865_SENSOR_WIRES_1 - #define MAX31865_SENSOR_WIRES_1 2 - #endif - #elif TEMP_SENSOR_1 == -3 - #define TEMP_SENSOR_1_IS_MAX31855 1 - #define TEMP_SENSOR_1_MAX_TC_TMIN -270 - #define TEMP_SENSOR_1_MAX_TC_TMAX 1800 - #elif TEMP_SENSOR_1 == -2 - #define TEMP_SENSOR_1_IS_MAX6675 1 - #define TEMP_SENSOR_1_MAX_TC_TMIN 0 - #define TEMP_SENSOR_1_MAX_TC_TMAX 1024 - #endif - - #if TEMP_SENSOR_1 != TEMP_SENSOR_0 - #if TEMP_SENSOR_1 == -5 - #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." - #elif TEMP_SENSOR_1 == -3 - #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." - #elif TEMP_SENSOR_1 == -2 - #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_1 then TEMP_SENSOR_0 must match." - #endif - #endif -#elif TEMP_SENSOR_1 == -4 - #define TEMP_SENSOR_1_IS_AD8495 1 -#elif TEMP_SENSOR_1 == -1 - #define TEMP_SENSOR_1_IS_AD595 1 -#elif TEMP_SENSOR_1 > 0 - #define TEMP_SENSOR_1_IS_THERMISTOR 1 - #if TEMP_SENSOR_1 == 1000 - #define TEMP_SENSOR_1_IS_CUSTOM 1 - #elif TEMP_SENSOR_1 == 998 || TEMP_SENSOR_1 == 999 - #define TEMP_SENSOR_1_IS_DUMMY 1 - #endif -#else - #undef HEATER_1_MINTEMP - #undef HEATER_1_MAXTEMP -#endif - -#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 - #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 - - #if TEMP_SENSOR_REDUNDANT == -5 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) - #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." - #endif - - #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 - #elif TEMP_SENSOR_REDUNDANT == -3 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." - #endif - - #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 - #elif TEMP_SENSOR_REDUNDANT == -2 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." - #endif - - #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 - #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 - #endif - - // mimic setting up the source TEMP_SENSOR - #if REDUNDANT_TEMP_MATCH(SOURCE, E0) - #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN - #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - #ifndef MAX31865_SENSOR_WIRES_0 - #define MAX31865_SENSOR_WIRES_0 2 - #endif - #elif REDUNDANT_TEMP_MATCH(SOURCE, E1) - #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN - #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - #ifndef MAX31865_SENSOR_WIRES_1 - #define MAX31865_SENSOR_WIRES_1 2 - #endif - #endif - - #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) - #if TEMP_SENSOR_REDUNDANT == -5 - #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." - #elif TEMP_SENSOR_REDUNDANT == -3 - #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." - #elif TEMP_SENSOR_REDUNDANT == -2 - #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." - #endif - #endif -#elif TEMP_SENSOR_REDUNDANT == -4 - #define TEMP_SENSOR_REDUNDANT_IS_AD8495 1 -#elif TEMP_SENSOR_REDUNDANT == -1 - #define TEMP_SENSOR_REDUNDANT_IS_AD595 1 -#elif TEMP_SENSOR_REDUNDANT > 0 - #define TEMP_SENSOR_REDUNDANT_IS_THERMISTOR 1 - #if TEMP_SENSOR_REDUNDANT == 1000 - #define TEMP_SENSOR_REDUNDANT_IS_CUSTOM 1 - #elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 - #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." - #endif -#endif - -#if TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC - #define HAS_MAX_TC 1 -#endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 - #define HAS_MAX6675 1 -#endif -#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 - #define HAS_MAX31855 1 -#endif -#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 - #define HAS_MAX31865 1 -#endif - -// -// Compatibility layer for MAX (SPI) temp boards -// +/** + * Compatibility layer for MAX (SPI) temp boards + */ #if HAS_MAX_TC // Translate old _SS, _CS, _SCK, _DO, _DI, _MISO, and _MOSI PIN defines. @@ -938,220 +768,6 @@ #endif //HAS_MAX_TC -#if TEMP_SENSOR_2 == -4 - #define TEMP_SENSOR_2_IS_AD8495 1 -#elif TEMP_SENSOR_2 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_2." -#elif TEMP_SENSOR_2 == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_2." -#elif TEMP_SENSOR_2 == -1 - #define TEMP_SENSOR_2_IS_AD595 1 -#elif TEMP_SENSOR_2 > 0 - #define TEMP_SENSOR_2_IS_THERMISTOR 1 - #if TEMP_SENSOR_2 == 1000 - #define TEMP_SENSOR_2_IS_CUSTOM 1 - #elif TEMP_SENSOR_2 == 998 || TEMP_SENSOR_2 == 999 - #define TEMP_SENSOR_2_IS_DUMMY 1 - #endif -#else - #undef HEATER_2_MINTEMP - #undef HEATER_2_MAXTEMP -#endif - -#if TEMP_SENSOR_3 == -4 - #define TEMP_SENSOR_3_IS_AD8495 1 -#elif TEMP_SENSOR_3 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_3." -#elif TEMP_SENSOR_3 == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_3." -#elif TEMP_SENSOR_3 == -1 - #define TEMP_SENSOR_3_IS_AD595 1 -#elif TEMP_SENSOR_3 > 0 - #define TEMP_SENSOR_3_IS_THERMISTOR 1 - #if TEMP_SENSOR_3 == 1000 - #define TEMP_SENSOR_3_IS_CUSTOM 1 - #elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 - #define TEMP_SENSOR_3_IS_DUMMY 1 - #endif -#else - #undef HEATER_3_MINTEMP - #undef HEATER_3_MAXTEMP -#endif - -#if TEMP_SENSOR_4 == -4 - #define TEMP_SENSOR_4_IS_AD8495 1 -#elif TEMP_SENSOR_4 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_4." -#elif TEMP_SENSOR_4 == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_4." -#elif TEMP_SENSOR_4 == -1 - #define TEMP_SENSOR_4_IS_AD595 1 -#elif TEMP_SENSOR_4 > 0 - #define TEMP_SENSOR_4_IS_THERMISTOR 1 - #if TEMP_SENSOR_4 == 1000 - #define TEMP_SENSOR_4_IS_CUSTOM 1 - #elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 - #define TEMP_SENSOR_4_IS_DUMMY 1 - #endif -#else - #undef HEATER_4_MINTEMP - #undef HEATER_4_MAXTEMP -#endif - -#if TEMP_SENSOR_5 == -4 - #define TEMP_SENSOR_5_IS_AD8495 1 -#elif TEMP_SENSOR_5 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_5." -#elif TEMP_SENSOR_5 == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_5." -#elif TEMP_SENSOR_5 == -1 - #define TEMP_SENSOR_5_IS_AD595 1 -#elif TEMP_SENSOR_5 > 0 - #define TEMP_SENSOR_5_IS_THERMISTOR 1 - #if TEMP_SENSOR_5 == 1000 - #define TEMP_SENSOR_5_IS_CUSTOM 1 - #elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 - #define TEMP_SENSOR_5_IS_DUMMY 1 - #endif -#else - #undef HEATER_5_MINTEMP - #undef HEATER_5_MAXTEMP -#endif - -#if TEMP_SENSOR_6 == -4 - #define TEMP_SENSOR_6_IS_AD8495 1 -#elif TEMP_SENSOR_6 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_6." -#elif TEMP_SENSOR_6 == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_6." -#elif TEMP_SENSOR_6 == -1 - #define TEMP_SENSOR_6_IS_AD595 1 -#elif TEMP_SENSOR_6 > 0 - #define TEMP_SENSOR_6_IS_THERMISTOR 1 - #if TEMP_SENSOR_6 == 1000 - #define TEMP_SENSOR_6_IS_CUSTOM 1 - #elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 - #define TEMP_SENSOR_6_IS_DUMMY 1 - #endif -#else - #undef HEATER_6_MINTEMP - #undef HEATER_6_MAXTEMP -#endif - -#if TEMP_SENSOR_7 == -4 - #define TEMP_SENSOR_7_IS_AD8495 1 -#elif TEMP_SENSOR_7 == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_7." -#elif TEMP_SENSOR_7 == -2 - #error "MAX7775 Thermocouples (-2) not supported for TEMP_SENSOR_7." -#elif TEMP_SENSOR_7 == -1 - #define TEMP_SENSOR_7_IS_AD595 1 -#elif TEMP_SENSOR_7 > 0 - #define TEMP_SENSOR_7_IS_THERMISTOR 1 - #if TEMP_SENSOR_7 == 1000 - #define TEMP_SENSOR_7_IS_CUSTOM 1 - #elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 - #define TEMP_SENSOR_7_IS_DUMMY 1 - #endif -#else - #undef HEATER_7_MINTEMP - #undef HEATER_7_MAXTEMP -#endif - -#if TEMP_SENSOR_BED == -4 - #define TEMP_SENSOR_BED_IS_AD8495 1 -#elif TEMP_SENSOR_BED == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BED." -#elif TEMP_SENSOR_BED == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BED." -#elif TEMP_SENSOR_BED == -1 - #define TEMP_SENSOR_BED_IS_AD595 1 -#elif TEMP_SENSOR_BED > 0 - #define TEMP_SENSOR_BED_IS_THERMISTOR 1 - #if TEMP_SENSOR_BED == 1000 - #define TEMP_SENSOR_BED_IS_CUSTOM 1 - #elif TEMP_SENSOR_BED == 998 || TEMP_SENSOR_BED == 999 - #define TEMP_SENSOR_BED_IS_DUMMY 1 - #endif -#else - #undef BED_MINTEMP - #undef BED_MAXTEMP -#endif - -#if TEMP_SENSOR_CHAMBER == -4 - #define TEMP_SENSOR_CHAMBER_IS_AD8495 1 -#elif TEMP_SENSOR_CHAMBER == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_CHAMBER." -#elif TEMP_SENSOR_CHAMBER == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_CHAMBER." -#elif TEMP_SENSOR_CHAMBER == -1 - #define TEMP_SENSOR_CHAMBER_IS_AD595 1 -#elif TEMP_SENSOR_CHAMBER > 0 - #define TEMP_SENSOR_CHAMBER_IS_THERMISTOR 1 - #if TEMP_SENSOR_CHAMBER == 1000 - #define TEMP_SENSOR_CHAMBER_IS_CUSTOM 1 - #elif TEMP_SENSOR_CHAMBER == 998 || TEMP_SENSOR_CHAMBER == 999 - #define TEMP_SENSOR_CHAMBER_IS_DUMMY 1 - #endif -#else - #undef CHAMBER_MINTEMP - #undef CHAMBER_MAXTEMP -#endif - -#if TEMP_SENSOR_COOLER == -4 - #define TEMP_SENSOR_COOLER_IS_AD8495 1 -#elif TEMP_SENSOR_COOLER == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_COOLER." -#elif TEMP_SENSOR_COOLER == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_COOLER." -#elif TEMP_SENSOR_COOLER == -1 - #define TEMP_SENSOR_COOLER_IS_AD595 1 -#elif TEMP_SENSOR_COOLER > 0 - #define TEMP_SENSOR_COOLER_IS_THERMISTOR 1 - #if TEMP_SENSOR_COOLER == 1000 - #define TEMP_SENSOR_COOLER_IS_CUSTOM 1 - #elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 - #define TEMP_SENSOR_COOLER_IS_DUMMY 1 - #endif -#else - #undef COOLER_MINTEMP - #undef COOLER_MAXTEMP -#endif - -#if TEMP_SENSOR_PROBE == -4 - #define TEMP_SENSOR_PROBE_IS_AD8495 1 -#elif TEMP_SENSOR_PROBE == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_PROBE." -#elif TEMP_SENSOR_PROBE == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_PROBE." -#elif TEMP_SENSOR_PROBE == -1 - #define TEMP_SENSOR_PROBE_IS_AD595 1 -#elif TEMP_SENSOR_PROBE > 0 - #define TEMP_SENSOR_PROBE_IS_THERMISTOR 1 - #if TEMP_SENSOR_PROBE == 1000 - #define TEMP_SENSOR_PROBE_IS_CUSTOM 1 - #elif TEMP_SENSOR_PROBE == 998 || TEMP_SENSOR_PROBE == 999 - #define TEMP_SENSOR_PROBE_IS_DUMMY 1 - #endif -#endif - -#if TEMP_SENSOR_BOARD == -4 - #define TEMP_SENSOR_BOARD_IS_AD8495 1 -#elif TEMP_SENSOR_BOARD == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BOARD." -#elif TEMP_SENSOR_BOARD == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BOARD." -#elif TEMP_SENSOR_BOARD == -1 - #define TEMP_SENSOR_BOARD_IS_AD595 1 -#elif TEMP_SENSOR_BOARD > 0 - #define TEMP_SENSOR_BOARD_IS_THERMISTOR 1 - #if TEMP_SENSOR_BOARD == 1000 - #define TEMP_SENSOR_BOARD_IS_CUSTOM 1 - #elif TEMP_SENSOR_BOARD == 998 || TEMP_SENSOR_BOARD == 999 - #define TEMP_SENSOR_BOARD_IS_DUMMY 1 - #endif -#endif - /** * X_DUAL_ENDSTOPS endstop reassignment */ From 4ac32b1993972f7b557378e6700e98c4f2d3d17a Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Tue, 13 Jul 2021 19:14:34 -0500 Subject: [PATCH 0392/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Robin=20Nano=20V?= =?UTF-8?q?3=20X=5FDIAG=5FPIN=20(#22340)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 7de5552dbb..ac93580589 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -59,7 +59,7 @@ // // Limit Switches // -#define X_DIAG_PIN PD15 +#define X_DIAG_PIN PA15 #define Y_DIAG_PIN PD2 #define Z_DIAG_PIN PC8 #define E0_DIAG_PIN PC4 From 88dad3a1645f6de0151659494e0ba6ccebbf1526 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 14 Jul 2021 12:32:21 +1200 Subject: [PATCH 0393/2168] =?UTF-8?q?=F0=9F=90=9B=20Define=20MT=5FDET=5FPI?= =?UTF-8?q?N=5FINVERTING=20for=20MKS=5FROBIN=5FNANO=5FV3=20(#22348)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index ac93580589..141c6d4a76 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -180,6 +180,7 @@ // #define MT_DET_1_PIN PA4 #define MT_DET_2_PIN PE6 +#define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE #define PW_DET PA13 #define PW_OFF PB2 From 9a0d4d666f85e484d850a48d989d379d58c59781 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 14 Jul 2021 00:54:43 +0000 Subject: [PATCH 0394/2168] [cron] Bump distribution date (2021-07-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5cfb8c0a07..a218af3d3d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-13" +//#define STRING_DISTRIBUTION_DATE "2021-07-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2834d3888b..3db502c470 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 "2021-07-13" + #define STRING_DISTRIBUTION_DATE "2021-07-14" #endif /** From 65cfbc074104c6b1ae4ef58251e516e3c4bad659 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Wed, 14 Jul 2021 02:34:18 -0300 Subject: [PATCH 0395/2168] =?UTF-8?q?=E2=9C=A8=20MSC=20Support=20for=20STM?= =?UTF-8?q?32=20+=20SDIO=20boards=20->=20SKR=202=20(#22354)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 517 +++++++++--------- Marlin/src/HAL/STM32/msc_sd.cpp | 2 +- Marlin/src/HAL/STM32F1/sdio.cpp | 4 + Marlin/src/pins/pins.h | 4 +- Marlin/src/sd/Sd2Card_sdio.h | 20 +- ini/stm32f4.ini | 10 + 6 files changed, 276 insertions(+), 281 deletions(-) diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 2ba0359cac..05f859a4af 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -28,319 +28,296 @@ #include #include -#if NONE(STM32F103xE, STM32F103xG, STM32F4xx, STM32F7xx) - #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" +// use local drivers +#if defined(STM32F103xE) || defined(STM32F103xG) + #include + #include +#elif defined(STM32F4xx) + #include + #include + #include + #include +#elif defined(STM32F7xx) + #include + #include + #include + #include +#else + #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, or STM32F7xx." #endif -#if HAS_SD_HOST_DRIVE +// Fixed +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 - // use USB drivers +SD_HandleTypeDef hsd; // create SDIO structure +// F4 supports one DMA for RX and another for TX, but Marlin will never +// do read and write at same time, so we use the same DMA for both. +DMA_HandleTypeDef hdma_sdio; - extern "C" { - int8_t SD_MSC_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - int8_t SD_MSC_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len); - extern SD_HandleTypeDef hsd; - } +/* + SDIO_INIT_CLK_DIV is 118 + SDIO clock frequency is 48MHz / (TRANSFER_CLOCK_DIV + 2) + SDIO init clock frequency should not exceed 400KHz = 48MHz / (118 + 2) - bool SDIO_Init() { - return hsd.State == HAL_SD_STATE_READY; // return pass/fail status - } + Default TRANSFER_CLOCK_DIV is 2 (118 / 40) + Default SDIO clock frequency is 48MHz / (2 + 2) = 12 MHz + This might be too fast for stable SDIO operations - bool SDIO_ReadBlock(uint32_t block, uint8_t *src) { - int8_t status = SD_MSC_Read(0, (uint8_t*)src, block, 1); // read one 512 byte block - return (bool) status; - } + MKS Robin board seems to have stable SDIO with BusWide 1bit and ClockDiv 8 i.e. 4.8MHz SDIO clock frequency + Additional testing is required as there are clearly some 4bit initialization problems +*/ - bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { - int8_t status = SD_MSC_Write(0, (uint8_t*)src, block, 1); // write one 512 byte block - return (bool) status; - } +#ifndef USBD_OK + #define USBD_OK 0 +#endif -#else // !USBD_USE_CDC_COMPOSITE +// Target Clock, configurable. Default is 18MHz, from STM32F1 +#ifndef SDIO_CLOCK + #define SDIO_CLOCK 18000000 // 18 MHz +#endif - // use local drivers - #if defined(STM32F103xE) || defined(STM32F103xG) - #include - #include - #elif defined(STM32F4xx) - #include - #include - #include - #include - #elif defined(STM32F7xx) - #include - #include - #include - #include - #else - #error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported" +// SDIO retries, configurable. Default is 3, from STM32F1 +#ifndef SDIO_READ_RETRIES + #define SDIO_READ_RETRIES 3 +#endif + +// SDIO Max Clock (naming from STM Manual, don't change) +#define SDIOCLK 48000000 + +static uint32_t clock_to_divider(uint32_t clk) { + // limit the SDIO master clock to 8/3 of PCLK2. See STM32 Manuals + // Also limited to no more than 48Mhz (SDIOCLK). + const uint32_t pclk2 = HAL_RCC_GetPCLK2Freq(); + clk = min(clk, (uint32_t)(pclk2 * 8 / 3)); + clk = min(clk, (uint32_t)SDIOCLK); + // Round up divider, so we don't run the card over the speed supported, + // and subtract by 2, because STM32 will add 2, as written in the manual: + // SDIO_CK frequency = SDIOCLK / [CLKDIV + 2] + return pclk2 / clk + (pclk2 % clk != 0) - 2; +} + +void go_to_transfer_speed() { + /* Default SDIO peripheral configuration for SD card initialization */ + hsd.Init.ClockEdge = hsd.Init.ClockEdge; + hsd.Init.ClockBypass = hsd.Init.ClockBypass; + hsd.Init.ClockPowerSave = hsd.Init.ClockPowerSave; + hsd.Init.BusWide = hsd.Init.BusWide; + hsd.Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; + hsd.Init.ClockDiv = clock_to_divider(SDIO_CLOCK); + + /* Initialize SDIO peripheral interface with default configuration */ + SDIO_Init(hsd.Instance, hsd.Init); +} + +void SD_LowLevel_Init(void) { + uint32_t tempreg; + + __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks + __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks + + GPIO_InitTypeDef GPIO_InitStruct; + + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + + #if DISABLED(STM32F1xx) + GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; #endif - // Fixed - #define SDIO_D0_PIN PC8 - #define SDIO_D1_PIN PC9 - #define SDIO_D2_PIN PC10 - #define SDIO_D3_PIN PC11 - #define SDIO_CK_PIN PC12 - #define SDIO_CMD_PIN PD2 + GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - SD_HandleTypeDef hsd; // create SDIO structure - // F4 supports one DMA for RX and another for TX, but Marlin will never - // do read and write at same time, so we use the same DMA for both. - DMA_HandleTypeDef hdma_sdio; - - /* - SDIO_INIT_CLK_DIV is 118 - SDIO clock frequency is 48MHz / (TRANSFER_CLOCK_DIV + 2) - SDIO init clock frequency should not exceed 400KHz = 48MHz / (118 + 2) - - Default TRANSFER_CLOCK_DIV is 2 (118 / 40) - Default SDIO clock frequency is 48MHz / (2 + 2) = 12 MHz - This might be too fast for stable SDIO operations - - MKS Robin board seems to have stable SDIO with BusWide 1bit and ClockDiv 8 i.e. 4.8MHz SDIO clock frequency - Additional testing is required as there are clearly some 4bit initialization problems - */ - - #ifndef USBD_OK - #define USBD_OK 0 - #endif - - // Target Clock, configurable. Default is 18MHz, from STM32F1 - #ifndef SDIO_CLOCK - #define SDIO_CLOCK 18000000 // 18 MHz - #endif - - // SDIO retries, configurable. Default is 3, from STM32F1 - #ifndef SDIO_READ_RETRIES - #define SDIO_READ_RETRIES 3 - #endif - - // SDIO Max Clock (naming from STM Manual, don't change) - #define SDIOCLK 48000000 - - static uint32_t clock_to_divider(uint32_t clk) { - // limit the SDIO master clock to 8/3 of PCLK2. See STM32 Manuals - // Also limited to no more than 48Mhz (SDIOCLK). - const uint32_t pclk2 = HAL_RCC_GetPCLK2Freq(); - clk = min(clk, (uint32_t)(pclk2 * 8 / 3)); - clk = min(clk, (uint32_t)SDIOCLK); - // Round up divider, so we don't run the card over the speed supported, - // and subtract by 2, because STM32 will add 2, as written in the manual: - // SDIO_CK frequency = SDIOCLK / [CLKDIV + 2] - return pclk2 / clk + (pclk2 % clk != 0) - 2; - } - - void go_to_transfer_speed() { - /* Default SDIO peripheral configuration for SD card initialization */ - hsd.Init.ClockEdge = hsd.Init.ClockEdge; - hsd.Init.ClockBypass = hsd.Init.ClockBypass; - hsd.Init.ClockPowerSave = hsd.Init.ClockPowerSave; - hsd.Init.BusWide = hsd.Init.BusWide; - hsd.Init.HardwareFlowControl = hsd.Init.HardwareFlowControl; - hsd.Init.ClockDiv = clock_to_divider(SDIO_CLOCK); - - /* Initialize SDIO peripheral interface with default configuration */ - SDIO_Init(hsd.Instance, hsd.Init); - } - - void SD_LowLevel_Init(void) { - uint32_t tempreg; - - __HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks - __HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks - - GPIO_InitTypeDef GPIO_InitStruct; - - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = 1; //GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - - #if DISABLED(STM32F1xx) - GPIO_InitStruct.Alternate = GPIO_AF12_SDIO; - #endif - - GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus + GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + #endif - #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // define D1-D3 only if have a four bit wide SDIO bus - GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3 - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - #endif + // Configure PD.02 CMD line + GPIO_InitStruct.Pin = GPIO_PIN_2; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - // Configure PD.02 CMD line - GPIO_InitStruct.Pin = GPIO_PIN_2; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + // Setup DMA + #if defined(STM32F1xx) + hdma_sdio.Init.Mode = DMA_NORMAL; + hdma_sdio.Instance = DMA2_Channel4; + HAL_NVIC_EnableIRQ(DMA2_Channel4_5_IRQn); + #elif defined(STM32F4xx) + hdma_sdio.Init.Mode = DMA_PFCTRL; + hdma_sdio.Instance = DMA2_Stream3; + hdma_sdio.Init.Channel = DMA_CHANNEL_4; + hdma_sdio.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + hdma_sdio.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + hdma_sdio.Init.MemBurst = DMA_MBURST_INC4; + hdma_sdio.Init.PeriphBurst = DMA_PBURST_INC4; + HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); + #endif + HAL_NVIC_EnableIRQ(SDIO_IRQn); + hdma_sdio.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_sdio.Init.MemInc = DMA_MINC_ENABLE; + hdma_sdio.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; + hdma_sdio.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; + hdma_sdio.Init.Priority = DMA_PRIORITY_LOW; + __HAL_LINKDMA(&hsd, hdmarx, hdma_sdio); + __HAL_LINKDMA(&hsd, hdmatx, hdma_sdio); - // Setup DMA - #if defined(STM32F1xx) - hdma_sdio.Init.Mode = DMA_NORMAL; - hdma_sdio.Instance = DMA2_Channel4; - HAL_NVIC_EnableIRQ(DMA2_Channel4_5_IRQn); - #elif defined(STM32F4xx) - hdma_sdio.Init.Mode = DMA_PFCTRL; - hdma_sdio.Instance = DMA2_Stream3; - hdma_sdio.Init.Channel = DMA_CHANNEL_4; - hdma_sdio.Init.FIFOMode = DMA_FIFOMODE_ENABLE; - hdma_sdio.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; - hdma_sdio.Init.MemBurst = DMA_MBURST_INC4; - hdma_sdio.Init.PeriphBurst = DMA_PBURST_INC4; - HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); - #endif - HAL_NVIC_EnableIRQ(SDIO_IRQn); - hdma_sdio.Init.PeriphInc = DMA_PINC_DISABLE; - hdma_sdio.Init.MemInc = DMA_MINC_ENABLE; - hdma_sdio.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD; - hdma_sdio.Init.MemDataAlignment = DMA_MDATAALIGN_WORD; - hdma_sdio.Init.Priority = DMA_PRIORITY_LOW; - __HAL_LINKDMA(&hsd, hdmarx, hdma_sdio); - __HAL_LINKDMA(&hsd, hdmatx, hdma_sdio); + #if defined(STM32F1xx) + __HAL_RCC_SDIO_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + #else + __HAL_RCC_SDIO_FORCE_RESET(); + delay(2); + __HAL_RCC_SDIO_RELEASE_RESET(); + delay(2); + __HAL_RCC_SDIO_CLK_ENABLE(); - #if defined(STM32F1xx) - __HAL_RCC_SDIO_CLK_ENABLE(); - __HAL_RCC_DMA2_CLK_ENABLE(); - #else - __HAL_RCC_SDIO_FORCE_RESET(); - delay(2); - __HAL_RCC_SDIO_RELEASE_RESET(); - delay(2); - __HAL_RCC_SDIO_CLK_ENABLE(); + __HAL_RCC_DMA2_FORCE_RESET(); + delay(2); + __HAL_RCC_DMA2_RELEASE_RESET(); + delay(2); + __HAL_RCC_DMA2_CLK_ENABLE(); + #endif - __HAL_RCC_DMA2_FORCE_RESET(); - delay(2); - __HAL_RCC_DMA2_RELEASE_RESET(); - delay(2); - __HAL_RCC_DMA2_CLK_ENABLE(); - #endif + //Initialize the SDIO (with initial <400Khz Clock) + tempreg = 0; //Reset value + tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled + tempreg |= SDIO_INIT_CLK_DIV; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz + // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable + SDIO->CLKCR = tempreg; - //Initialize the SDIO (with initial <400Khz Clock) - tempreg = 0; //Reset value - tempreg |= SDIO_CLKCR_CLKEN; // Clock enabled - tempreg |= SDIO_INIT_CLK_DIV; // Clock Divider. Clock = 48000 / (118 + 2) = 400Khz - // Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable - SDIO->CLKCR = tempreg; + // Power up the SDIO + SDIO_PowerState_ON(SDIO); + hsd.Instance = SDIO; +} - // Power up the SDIO - SDIO_PowerState_ON(SDIO); - hsd.Instance = SDIO; +void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init + UNUSED(hsd); // Prevent unused argument(s) compilation warning + __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock +} + +bool SDIO_Init() { + uint8_t retryCnt = SDIO_READ_RETRIES; + + bool status; + hsd.Instance = SDIO; + hsd.State = HAL_SD_STATE_RESET; + + SD_LowLevel_Init(); + + uint8_t retry_Cnt = retryCnt; + for (;;) { + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted } - void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init - UNUSED(hsd); // Prevent unused argument(s) compilation warning - __HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock - } + go_to_transfer_speed(); - bool SDIO_Init() { - uint8_t retryCnt = SDIO_READ_RETRIES; - - bool status; - hsd.Instance = SDIO; - hsd.State = HAL_SD_STATE_RESET; - - SD_LowLevel_Init(); - - uint8_t retry_Cnt = retryCnt; + #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined + retry_Cnt = retryCnt; for (;;) { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted + if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required + if (!--retry_Cnt) break; } - - go_to_transfer_speed(); - - #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined + if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode + hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET + SD_LowLevel_Init(); retry_Cnt = retryCnt; for (;;) { TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required - if (!--retry_Cnt) break; + status = (bool) HAL_SD_Init(&hsd); + if (!status) break; + if (!--retry_Cnt) return false; // return failing status if retries are exhausted } - if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode - hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET - SD_LowLevel_Init(); - retry_Cnt = retryCnt; - for (;;) { - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - status = (bool) HAL_SD_Init(&hsd); - if (!status) break; - if (!--retry_Cnt) return false; // return failing status if retries are exhausted - } - go_to_transfer_speed(); - } - #endif + go_to_transfer_speed(); + } + #endif - return true; + return true; +} + +static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t *dst) { + if (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) return false; + + TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); + + HAL_StatusTypeDef ret; + if (src) { + hdma_sdio.Init.Direction = DMA_MEMORY_TO_PERIPH; + HAL_DMA_Init(&hdma_sdio); + ret = HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)src, block, 1); + } + else { + hdma_sdio.Init.Direction = DMA_PERIPH_TO_MEMORY; + HAL_DMA_Init(&hdma_sdio); + ret = HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)dst, block, 1); } - static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t *dst) { - if (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) return false; + if (ret != HAL_OK) { + HAL_DMA_Abort_IT(&hdma_sdio); + HAL_DMA_DeInit(&hdma_sdio); + return false; + } - TERN_(USE_WATCHDOG, HAL_watchdog_refresh()); - - HAL_StatusTypeDef ret; - if (src) { - hdma_sdio.Init.Direction = DMA_MEMORY_TO_PERIPH; - HAL_DMA_Init(&hdma_sdio); - ret = HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)src, block, 1); - } - else { - hdma_sdio.Init.Direction = DMA_PERIPH_TO_MEMORY; - HAL_DMA_Init(&hdma_sdio); - ret = HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)dst, block, 1); - } - - if (ret != HAL_OK) { + millis_t timeout = millis() + 500; + // Wait the transfer + while (hsd.State != HAL_SD_STATE_READY) { + if (ELAPSED(millis(), timeout)) { HAL_DMA_Abort_IT(&hdma_sdio); HAL_DMA_DeInit(&hdma_sdio); return false; } - - millis_t timeout = millis() + 500; - // Wait the transfer - while (hsd.State != HAL_SD_STATE_READY) { - if (ELAPSED(millis(), timeout)) { - HAL_DMA_Abort_IT(&hdma_sdio); - HAL_DMA_DeInit(&hdma_sdio); - return false; - } - } - - while (__HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_sdio)) != 0 - || __HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_sdio)) != 0) { /* nada */ } - - HAL_DMA_Abort_IT(&hdma_sdio); - HAL_DMA_DeInit(&hdma_sdio); - - timeout = millis() + 500; - while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) if (ELAPSED(millis(), timeout)) return false; - - return true; } - bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { - uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, NULL, dst)) return true; - return false; - } + while (__HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_sdio)) != 0 + || __HAL_DMA_GET_FLAG(&hdma_sdio, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_sdio)) != 0) { /* nada */ } - bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { - uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, NULL)) return true; - return false; - } + HAL_DMA_Abort_IT(&hdma_sdio); + HAL_DMA_DeInit(&hdma_sdio); - #if defined(STM32F1xx) - #define DMA_IRQ_HANDLER DMA2_Channel4_5_IRQHandler - #elif defined(STM32F4xx) - #define DMA_IRQ_HANDLER DMA2_Stream3_IRQHandler - #else - #error "Unknown STM32 architecture." - #endif + timeout = millis() + 500; + while (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) if (ELAPSED(millis(), timeout)) return false; - extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); } - extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); } + return true; +} + +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, NULL, dst)) return true; + return false; +} + +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, NULL)) return true; + return false; +} + +bool SDIO_IsReady() { + return hsd.State == HAL_SD_STATE_READY; +} + +uint32_t SDIO_GetCardSize() { + return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize); +} + +#if defined(STM32F1xx) + #define DMA_IRQ_HANDLER DMA2_Channel4_5_IRQHandler +#elif defined(STM32F4xx) + #define DMA_IRQ_HANDLER DMA2_Stream3_IRQHandler +#else + #error "Unknown STM32 architecture." +#endif + +extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); } +extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); } -#endif // !USBD_USE_CDC_COMPOSITE #endif // SDIO_SUPPORT #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index 98f75d89f0..70a719d665 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -19,10 +19,10 @@ #if HAS_SD_HOST_DRIVE +#include "../shared/Marduino.h" #include "msc_sd.h" #include "usbd_core.h" -#include "../shared/Marduino.h" #include "../../sd/cardreader.h" #include diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index ffa6db1206..6e41d2cbf1 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -184,6 +184,10 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) { inline uint32_t SDIO_GetCardState() { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; } +// No F1 board with SDIO + MSC using Maple, that I aware of... +bool SDIO_IsReady() { return true; } +uint32_t SDIO_GetCardSize() { return 0; } + // ------------------------ // SD Commands and Responses // ------------------------ diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 1f53227553..b9a5f19d7c 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -594,9 +594,9 @@ #elif MB(BTT_E3_RRF) #include "stm32f4/pins_BTT_E3_RRF.h" // STM32F4 env:BIGTREE_E3_RRF #elif MB(BTT_SKR_V2_0_REV_A) - #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 + #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB #elif MB(BTT_SKR_V2_0_REV_B) - #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 + #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB #elif MB(BTT_OCTOPUS_V1_0) #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(BTT_OCTOPUS_V1_1) diff --git a/Marlin/src/sd/Sd2Card_sdio.h b/Marlin/src/sd/Sd2Card_sdio.h index 1580344805..cc29f5d46d 100644 --- a/Marlin/src/sd/Sd2Card_sdio.h +++ b/Marlin/src/sd/Sd2Card_sdio.h @@ -29,6 +29,8 @@ bool SDIO_Init(); bool SDIO_ReadBlock(uint32_t block, uint8_t *dst); bool SDIO_WriteBlock(uint32_t block, const uint8_t *src); +bool SDIO_IsReady(); +uint32_t SDIO_GetCardSize(); class DiskIODriver_SDIO : public DiskIODriver { public: @@ -36,20 +38,22 @@ class DiskIODriver_SDIO : public DiskIODriver { bool readCSD(csd_t *csd) override { return false; } - bool readStart(const uint32_t block) override { return false; } - bool readData(uint8_t *dst) override { return false; } - bool readStop() override { return false; } + bool readStart(const uint32_t block) override { curBlock = block; return true; } + bool readData(uint8_t *dst) override { return readBlock(curBlock++, dst); } + bool readStop() override { curBlock = -1; return true; } - bool writeStart(const uint32_t block, const uint32_t) override { return false; } - bool writeData(const uint8_t *src) override { return false; } - bool writeStop() override { return false; } + bool writeStart(const uint32_t block, const uint32_t) override { curBlock = block; return true; } + bool writeData(const uint8_t *src) override { return writeBlock(curBlock++, src); } + bool writeStop() override { curBlock = -1; return true; } bool readBlock(uint32_t block, uint8_t *dst) override { return SDIO_ReadBlock(block, dst); } bool writeBlock(uint32_t block, const uint8_t *src) override { return SDIO_WriteBlock(block, src); } - uint32_t cardSize() override { return 0; } + uint32_t cardSize() override { return SDIO_GetCardSize(); } - bool isReady() override { return true; } + bool isReady() override { return SDIO_IsReady(); } void idle() override {} + private: + uint32_t curBlock; }; diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 6067bbc3b8..ced410624f 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -243,6 +243,16 @@ build_flags = ${stm_flash_drive.build_flags} -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED +# +# BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Media Share Support +# +[env:BIGTREE_SKR_2_USB] +platform = ${common_stm32.platform} +extends = env:BIGTREE_SKR_2 +platform_packages = ${stm_flash_drive.platform_packages} +build_unflags = -DUSBD_USE_CDC +build_flags = ${env:BIGTREE_SKR_2.build_flags} -DUSBD_USE_CDC_MSC + # # BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) # From f479a2ef6f8335e7952ac099cb1b8336aa0a3c34 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 14 Jul 2021 18:57:26 +1200 Subject: [PATCH 0396/2168] =?UTF-8?q?=E2=9C=A8=20FLY=20Mini=20for=20stm32d?= =?UTF-8?q?uino=20(#22356)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- ini/stm32f1.ini | 16 ++++++++++++++++ 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b9a5f19d7c..20f24f8c21 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -552,7 +552,7 @@ #elif MB(TRIGORILLA_PRO) #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro #elif MB(FLY_MINI) - #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI + #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI env:FLY_MINI_maple #elif MB(FLSUN_HISPEED) #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 6c39d0b6fa..93e97654a4 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -259,3 +259,19 @@ board = malyanm200_f103cb build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + + +# +# FLY Mini (STM32F103RCT6) +# +[env:FLY_MINI] +platform = ${common_stm32.platform} +extends = common_stm32 +build_flags = ${common_stm32.build_flags} -DSS_TIMER=4 +board = genericSTM32F103RC +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x5000 +board_upload.offset_address = 0x08005000 +extra_scripts = ${common_stm32.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py From 7f5c9d273e7564dd18109772fe6cb45b4716eeb7 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 14 Jul 2021 00:03:24 -0700 Subject: [PATCH 0397/2168] =?UTF-8?q?=F0=9F=92=A1=20Update=20FLYmaker=20co?= =?UTF-8?q?mments,=20URL=20(#22355)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 6 +++--- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 2 +- ini/stm32f1.ini | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 9dc951e229..661a213b4b 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -249,7 +249,7 @@ #define BOARD_BTT_SKR_V1_4_TURBO 2508 // BigTreeTech SKR v1.4 TURBO (Power outputs: Hotend0, Hotend1, Fan, Bed) #define BOARD_MKS_SGEN_L_V2 2509 // MKS SGEN_L V2 (Power outputs: Hotend0, Hotend1, Bed, Fan) #define BOARD_BTT_SKR_E3_TURBO 2510 // BigTreeTech SKR E3 Turbo (Power outputs: Hotend0, Hotend1, Bed, Fan0, Fan1) -#define BOARD_FLY_CDY 2511 // FLY_CDY (Power outputs: Hotend0, Hotend1, Hotend2, Bed, Fan0, Fan1, Fan2) +#define BOARD_FLY_CDY 2511 // FLYmaker FLY CDY (Power outputs: Hotend0, Hotend1, Hotend2, Bed, Fan0, Fan1, Fan2) // // SAM3X8E ARM Cortex M3 @@ -340,7 +340,7 @@ #define BOARD_CREALITY_V452 4042 // Creality v4.5.2 (STM32F103RE) #define BOARD_CREALITY_V453 4043 // Creality v4.5.3 (STM32F103RE) #define BOARD_TRIGORILLA_PRO 4044 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4045 // FLY MINI (STM32F103RCT6) +#define BOARD_FLY_MINI 4045 // FLYmaker FLY MINI (STM32F103RCT6) #define BOARD_FLSUN_HISPEED 4046 // FLSUN HiSpeedV1 (STM32F103VET6) #define BOARD_BEAST 4047 // STM32F103RET6 Libmaple-based controller #define BOARD_MINGDA_MPX_ARM_MINI 4048 // STM32F103ZET6 Mingda MD-16 @@ -380,7 +380,7 @@ #define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6) #define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6) #define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4223 // FLYF407ZG (STM32F407ZG) +#define BOARD_FLYF407ZG 4223 // FLYmaker FLYF407ZG (STM32F407ZG) #define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) #define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) #define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index b94ec0c7f3..be0a622b1d 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" #define BOARD_INFO_NAME "FLY_MINI" -#define BOARD_WEBSITE_URL "github.com/FLYmaker" +#define BOARD_WEBSITE_URL "github.com/FLYmaker/FLY-MINI" #define DISABLE_JTAG // diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 93e97654a4..f1afb0e4d7 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -271,7 +271,7 @@ board = genericSTM32F103RC board_build.core = stm32 board_build.variant = MARLIN_F103Rx board_build.offset = 0x5000 -board_upload.offset_address = 0x08005000 +board_upload.offset_address = 0x08005000 extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py From 082c61ebb99454acbb3ac8cca3485b24f177de0e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 14 Jul 2021 02:14:55 -0500 Subject: [PATCH 0398/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20SD=20pins=20for?= =?UTF-8?q?=20MKS=20Robin=20Lite?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index fad36e8384..73c77d092a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -143,6 +143,6 @@ // #define SPI_DEVICE 2 #define SD_SCK_PIN PB13 -#define SD_MISO_PIN P1B4 -#define SD_MOSI_PIN P1B5 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 #define SD_SS_PIN PA15 From 826a34b0b156e27994c787071bbed519db3bcfa1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 14 Jul 2021 02:21:26 -0500 Subject: [PATCH 0399/2168] =?UTF-8?q?=F0=9F=8E=A8=20Remove=20extraneous=20?= =?UTF-8?q?pin=20defs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 141c6d4a76..178e75ab7f 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -181,8 +181,6 @@ #define MT_DET_1_PIN PA4 #define MT_DET_2_PIN PE6 #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE -#define PW_DET PA13 -#define PW_OFF PB2 #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN MT_DET_1_PIN @@ -192,9 +190,9 @@ #endif #ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PW_DET + #define POWER_LOSS_PIN PA13 // PW_DET #endif -#define PS_ON_PIN PW_OFF +#define PS_ON_PIN PB2 // PW_OFF // // Enable MKSPWC support From a13d90093d8e647fa9ecab7a7752009dcc9c55ae Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 14 Jul 2021 15:55:24 -0700 Subject: [PATCH 0400/2168] =?UTF-8?q?=F0=9F=A9=B9=20FLYmaker=20FLY=20Mini?= =?UTF-8?q?=20followup=20(#22364)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22355, #22356. --- ini/stm32f1-maple.ini | 14 ++++++++++++++ ini/stm32f1.ini | 2 +- 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index db1cc99217..ab1e6c54f4 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -342,3 +342,17 @@ build_unflags = ${common_stm32f1.build_unflags} platform = ${common_stm32f1.platform} extends = env:chitu_f103 build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX + +# +# FLYmaker FLY Mini (STM32F103RCT6) +# +[env:FLY_MINI_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +board_build.address = 0x08005000 +board_build.ldscript = fly_mini.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index f1afb0e4d7..58f1fc1058 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -261,7 +261,7 @@ build_flags = ${common_stm32.build_flags} src_filter = ${common.default_src_filter} + # -# FLY Mini (STM32F103RCT6) +# FLYmaker FLY Mini (STM32F103RCT6) # [env:FLY_MINI] platform = ${common_stm32.platform} From 3bc1d2dd857fd81631411f75f87048b8f62fe82f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 14 Jul 2021 18:51:58 -0500 Subject: [PATCH 0401/2168] =?UTF-8?q?=F0=9F=8E=A8=20Minor=20cleanup=20of?= =?UTF-8?q?=20TFT/FSMC=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 6 +--- Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h | 7 +---- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 18 ++++++----- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 24 ++++++++++----- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 30 ++++++++++++------- .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 21 ++++++------- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 15 +++++----- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 20 +++++++------ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 18 ++++++----- Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h | 26 +++++++++------- Marlin/src/pins/stm32f4/pins_ANET_ET4.h | 18 ++++++----- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 3 +- 12 files changed, 114 insertions(+), 92 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index 8f5893e3b9..e892d3e3f8 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -117,13 +117,9 @@ #define W25QXX_SCK_PIN PB13 // -// TronXY TFT Support +// TFT with FSMC interface // - #if HAS_FSMC_TFT - - // Shared FSMC - #define TOUCH_CS_PIN PB7 // SPI1_NSS #define TOUCH_SCK_PIN PA5 // SPI1_SCK #define TOUCH_MISO_PIN PA6 // SPI1_MISO diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index df49da1095..51bd7294a9 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -132,13 +132,9 @@ #define W25QXX_SCK_PIN PB13 // -// TronXY TFT Support +// TFT with FSMC interface // - #if HAS_FSMC_TFT - - // Shared FSMC - #define TOUCH_CS_PIN PB7 // SPI1_NSS #define TOUCH_SCK_PIN PA5 // SPI1_SCK #define TOUCH_MISO_PIN PA6 // SPI1_MISO @@ -152,7 +148,6 @@ #define FSMC_RS_PIN PD11 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #endif #if ENABLED(TFT_LVGL_UI) diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index c49c31e741..bdf3f48c3a 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -271,11 +271,9 @@ #error "FLSun HiSpeed default BEEPER_PIN is not a SPEAKER." #endif -#if HAS_FSMC_TFT || HAS_GRAPHICAL_TFT - #define TFT_CS_PIN PD7 // NE4 - #define TFT_RS_PIN PD11 // A0 -#endif - +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT /** * Note: MKS Robin TFT screens use various TFT controllers @@ -291,12 +289,16 @@ */ //#define TFT_RESET_PIN PC6 // FSMC_RST #define TFT_BACKLIGHT_PIN PD13 - #define FSMC_CS_PIN TFT_CS_PIN // NE4 - #define FSMC_RS_PIN TFT_RS_PIN // A0 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN TFT_CS_PIN + #define TFT_RS_PIN TFT_RS_PIN + #ifdef TFT_CLASSIC_UI #define TFT_MARLINBG_COLOR 0x3186 // Grey #define TFT_MARLINUI_COLOR 0xC7B6 // Green @@ -307,6 +309,8 @@ #elif HAS_GRAPHICAL_TFT #define TFT_RESET_PIN PC6 #define TFT_BACKLIGHT_PIN PD13 + #define TFT_CS_PIN PD7 // NE4 + #define TFT_RS_PIN PD11 // A0 #endif #if NEED_TOUCH_PINS diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 9f08f18bf7..bded0edd3a 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -26,6 +26,8 @@ * ║║ ╦╠═╣│ │├┬┘│ │├┬┘├─┤╠╣ │ │├┬┘│ ││││ │ │ ││││ * ╚╝╚═╝╩ ╩└─┘┴└─└─┘┴└─┴ ┴╚ └─┘┴└─└─┘┴ ┴o└─┘└─┘┴ ┴ * Pin assignments for 32-bit JGAurora A5S & A1 + * + * https://jgaurorawiki.com/_media/jgaurora_a5s_a1_pinout.png */ #include "env_validate.h" @@ -102,15 +104,20 @@ #define FIL_RUNOUT_PIN PC7 // -// LCD +// TFT with FSMC interface // -#define LCD_BACKLIGHT_PIN PF11 -#define FSMC_CS_PIN PD7 -#define FSMC_RS_PIN PG0 +#if HAS_FSMC_TFT + #define LCD_BACKLIGHT_PIN PF11 + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PG0 -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_DMA_DEV DMA2 -#define FSMC_DMA_CHANNEL DMA_CH5 + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN +#endif // // SD Card @@ -129,4 +136,7 @@ #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PA4 #define TOUCH_INT_PIN PC4 + #define TOUCH_MISO_PIN PA6 + #define TOUCH_MOSI_PIN PA7 + #define TOUCH_SCK_PIN PA5 #endif diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index fa708b248e..391610522d 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -117,20 +117,28 @@ //#undef Z_MAX_PIN // Uncomment if using ZMAX connector (PE5) #endif -#define TFT_RESET_PIN PC4 // pin 33 -#define TFT_BACKLIGHT_PIN PD12 // pin 59 -#define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 -#define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 + #define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_DMA_DEV DMA2 -#define FSMC_DMA_CHANNEL DMA_CH5 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN -#define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h -#define DOGLCD_SCK -1 + #define TFT_RESET_PIN PC4 // pin 33 + #define TFT_BACKLIGHT_PIN PD12 // pin 59 -// Buffer for Color UI -#define TFT_BUFFER_SIZE 3200 + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h + #define DOGLCD_SCK -1 + + // Buffer for Color UI + #define TFT_BUFFER_SIZE 3200 +#endif /** * Note: Alfawise U20/U30 boards DON'T use SPI2, as the hardware designer diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index 179c04a304..14f2ad981a 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -133,11 +133,9 @@ // #define BEEPER_PIN PE4 -/** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'LCD_RESET_PIN' - * to let the bootloader init the screen. - */ +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT /** * Note: MKS Robin TFT screens use various TFT controllers @@ -151,18 +149,17 @@ * Setting an 'TFT_RESET_PIN' may cause a flicker when entering the LCD menu * because Marlin uses the reset as a failsafe to revive a glitchy LCD. */ - #define TFT_CS_PIN PD7 // NE4 - #define TFT_RS_PIN PG0 // A0 - - #define FSMC_CS_PIN TFT_CS_PIN - #define FSMC_RS_PIN TFT_RS_PIN + #define TFT_RESET_PIN PF15 + #define TFT_BACKLIGHT_PIN PF11 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PG0 // A0 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #define TFT_RESET_PIN PF15 - #define TFT_BACKLIGHT_PIN PF11 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 8da4dcc9de..f912978051 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -155,7 +155,7 @@ #define WIFI_IO0_PIN PG1 // -// LCD screen +// TFT with FSMC interface // #if HAS_FSMC_TFT /** @@ -170,18 +170,17 @@ * Setting an 'TFT_RESET_PIN' may cause a flicker when entering the LCD menu * because Marlin uses the reset as a failsafe to revive a glitchy LCD. */ - #define TFT_CS_PIN PG12 // NE4 - #define TFT_RS_PIN PF0 // A0 - - #define FSMC_CS_PIN TFT_CS_PIN - #define FSMC_RS_PIN TFT_RS_PIN + #define TFT_RESET_PIN PF6 + #define TFT_BACKLIGHT_PIN PG11 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PG12 // NE4 + #define FSMC_RS_PIN PF0 // A0 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #define TFT_RESET_PIN PF6 - #define TFT_BACKLIGHT_PIN PG11 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 0a6186cf57..95d62f05a4 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -172,13 +172,18 @@ // #define BEEPER_PIN PC5 -/** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'TFT_RESET_PIN' - * to let the bootloader init the screen. - */ -// Shared FSMC Configs +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'TFT_RESET_PIN' + * to let the bootloader init the screen. + */ + #define TFT_RESET_PIN PC6 // FSMC_RST + #define TFT_BACKLIGHT_PIN PD13 + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h #define DOGLCD_SCK -1 @@ -187,9 +192,6 @@ #define TOUCH_MISO_PIN PB14 // SPI2_MISO #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI - #define TFT_RESET_PIN PC6 // FSMC_RST - #define TFT_BACKLIGHT_PIN PD13 - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_CS_PIN PD7 #define FSMC_RS_PIN PD11 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 129b640d97..7ff22cc1ce 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -205,12 +205,18 @@ #error "No custom SD drive cable defined for this board." #endif -/** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'LCD_RESET_PIN' - * to let the bootloader init the screen. - */ +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'LCD_RESET_PIN' + * to let the bootloader init the screen. + */ + #define TFT_RESET_PIN LCD_RESET_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN + #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 #define FSMC_DMA_DEV DMA2 @@ -221,8 +227,6 @@ #define LCD_RESET_PIN PF6 #define LCD_BACKLIGHT_PIN PD13 - #define TFT_RESET_PIN LCD_RESET_PIN - #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TFT_BUFFER_SIZE 14400 diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 5eefedb141..1de3729dcc 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -126,20 +126,24 @@ //#define POWER_LOSS_PIN PG2 // PG4 PW_DET #define FIL_RUNOUT_PIN PA15 // MT_DET -/** - * Note: MKS Robin TFT screens use various TFT controllers - * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) - * ILI9488 is not supported. - * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp - * - * If the screen stays white, disable 'LCD_RESET_PIN' to let the bootloader init the screen. - * - * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu - * because Marlin uses the reset as a failsafe to revive a glitchy LCD. - */ +// +// TFT with FSMC interface +// #if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers + * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) + * ILI9488 is not supported. + * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp + * + * If the screen stays white, disable 'LCD_RESET_PIN' to let the bootloader init the screen. + * + * Setting an 'LCD_RESET_PIN' may cause a flicker when entering the LCD menu + * because Marlin uses the reset as a failsafe to revive a glitchy LCD. + */ #define TFT_RESET_PIN PF11 #define TFT_BACKLIGHT_PIN PD13 + #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index 1e1f5251c1..d2ee2e013c 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -136,14 +136,18 @@ // // LCD / Controller // -#define TFT_RESET_PIN PE6 -#define TFT_CS_PIN PD7 -#define TFT_RS_PIN PD13 -#define TFT_INTERFACE_FSMC_8BIT +#if HAS_SPI_TFT || HAS_FSMC_TFT + #define TFT_RESET_PIN PE6 + #define TFT_CS_PIN PD7 + #define TFT_RS_PIN PD13 -#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT -#define FSMC_CS_PIN TFT_CS_PIN -#define FSMC_RS_PIN TFT_RS_PIN + #if HAS_FSMC_TFT + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN TFT_CS_PIN + #define FSMC_RS_PIN TFT_RS_PIN + #define TFT_INTERFACE_FSMC_8BIT + #endif +#endif // // Touch Screen diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index b92056ea86..3b75e7072a 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -230,9 +230,8 @@ #define BEEPER_PIN PC7 // -// LCD / Controller +// TFT with FSMC interface // - #if HAS_FSMC_TFT //#define TFT_DRIVER LERDGE_ST7796 From 972b1e2f00a1e4fdf7370f706d6f83899b3471ae Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Wed, 14 Jul 2021 16:56:02 -0700 Subject: [PATCH 0402/2168] =?UTF-8?q?=F0=9F=8E=A8=20Call=20millis()=20once?= =?UTF-8?q?=20in=20manage=5Finactivity=20(#22363)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3ec4a8193c..bb7b227b53 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -514,7 +514,6 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { constexpr millis_t HOME_DEBOUNCE_DELAY = 1000UL; static millis_t next_home_key_ms; // = 0 if (!IS_SD_PRINTING() && !READ(HOME_PIN)) { // HOME_PIN goes LOW when pressed - const millis_t ms = millis(); if (ELAPSED(ms, next_home_key_ms)) { next_home_key_ms = ms + HOME_DEBOUNCE_DELAY; LCD_MESSAGEPGM(MSG_AUTO_HOME); @@ -526,7 +525,6 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(CUSTOM_USER_BUTTONS) // Handle a custom user button if defined const bool printer_not_busy = !printingIsActive(); - const millis_t ms = millis(); #define HAS_CUSTOM_USER_BUTTON(N) (PIN_EXISTS(BUTTON##N) && defined(BUTTON##N##_HIT_STATE) && defined(BUTTON##N##_GCODE)) #define HAS_BETTER_USER_BUTTON(N) HAS_CUSTOM_USER_BUTTON(N) && defined(BUTTON##N##_DESC) #define _CHECK_CUSTOM_USER_BUTTON(N, CODE) do{ \ From 5ca9ebfa6b0ff814c3a122c3e613574533027803 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 14 Jul 2021 19:44:51 -0500 Subject: [PATCH 0403/2168] =?UTF-8?q?=F0=9F=94=A8=20Consolidate=20STM32=20?= =?UTF-8?q?extra=5Fscripts=20(#22365)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/STM32F103RC_fysetc.py | 2 +- .../share/PlatformIO/scripts/mks_encrypt.py | 29 -------- ...m32_bootloader.py => offset_and_rename.py} | 13 +++- ini/avr.ini | 3 +- ini/stm32f1.ini | 41 ++++-------- ini/stm32f4.ini | 66 +++++++------------ 6 files changed, 50 insertions(+), 104 deletions(-) delete mode 100644 buildroot/share/PlatformIO/scripts/mks_encrypt.py rename buildroot/share/PlatformIO/scripts/{stm32_bootloader.py => offset_and_rename.py} (83%) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 5a09dd3d14..668475dc01 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -10,7 +10,7 @@ Import("env") env.AddPostAction( join("$BUILD_DIR", "${PROGNAME}.elf"), env.VerboseAction(" ".join([ - "$OBJCOPY", "-O ihex", "$TARGET", # TARGET=.pio/build/fysetc_STM32F1/firmware.elf + "$OBJCOPY", "-O ihex", "$TARGET", "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path ]), "Building $TARGET")) diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py deleted file mode 100644 index bd3548ab36..0000000000 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ /dev/null @@ -1,29 +0,0 @@ -# -# buildroot/share/PlatformIO/scripts/mks_encrypt.py -# -# Apply encryption and save as 'build.firmware' for these environments: -# - env:mks_robin -# - env:mks_robin_e3 -# - env:flsun_hispeedv1 -# - env:mks_robin_nano35 -# -Import("env") - -from SCons.Script import DefaultEnvironment -board = DefaultEnvironment().BoardConfig() - -if 'encrypt' in board.get("build").keys(): - - import marlin - - # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt - def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) - - marlin.add_post_action(encrypt); - -else: - - import sys - print("You need to define output file via board_build.encrypt = 'filename' parameter", file=sys.stderr) - env.Exit(1); diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py similarity index 83% rename from buildroot/share/PlatformIO/scripts/stm32_bootloader.py rename to buildroot/share/PlatformIO/scripts/offset_and_rename.py index f3b1b273a2..b42b2f3531 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -1,5 +1,5 @@ # -# stm32_bootloader.py +# offset_and_rename.py # # - If 'build.offset' is provided, either by JSON or by the environment... # - Set linker flag LD_FLASH_OFFSET and relocate the VTAB based on 'build.offset'. @@ -36,6 +36,17 @@ if 'offset' in board_keys: if "-Wl,--defsym=LD_MAX_DATA_SIZE" in flag: env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) +# +# For build.encrypt rename and encode the firmware file. +# +if 'encrypt' in board_keys: + + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) + + marlin.add_post_action(encrypt); + # # For build.rename simply rename the firmware file. # diff --git a/ini/avr.ini b/ini/avr.ini index cd10f13499..88f54a723c 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -53,8 +53,7 @@ board = megaatmega1280 [mega_extended_optimized] extends = common_avr8 board_build.variant = MARLIN_MEGA_EXTENDED -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py +extra_scripts = ${env:mega2560ext.extra_scripts} upload_speed = 57600 build_flags = ${common.build_flags} -fno-tree-scev-cprop -fno-split-wide-types -Wl,--relax -mcall-prologues diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 58f1fc1058..d5f0741d41 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -34,6 +34,11 @@ src_filter = ${common.default_src_filter} + + Date: Thu, 15 Jul 2021 01:04:09 +0000 Subject: [PATCH 0404/2168] [cron] Bump distribution date (2021-07-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a218af3d3d..03855365ba 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-14" +//#define STRING_DISTRIBUTION_DATE "2021-07-15" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3db502c470..49a0b94f64 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 "2021-07-14" + #define STRING_DISTRIBUTION_DATE "2021-07-15" #endif /** From 7e50d8761d66cfa7c6e8a4e864f0754ddd645ada Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 15 Jul 2021 14:07:46 +1200 Subject: [PATCH 0405/2168] =?UTF-8?q?=F0=9F=94=A8=20More=20HAL/STM32=20tar?= =?UTF-8?q?gets=20(#22358)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 26 ++-- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 2 + ini/stm32f1-maple.ini | 26 ++-- ini/stm32f1.ini | 150 ++++++++++++++++++++++ 4 files changed, 178 insertions(+), 26 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 20f24f8c21..b5a81c6097 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -486,17 +486,17 @@ #elif MB(MKS_ROBIN) #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple #elif MB(MKS_ROBIN_MINI) - #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini + #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini env:mks_robin_mini_maple #elif MB(MKS_ROBIN_NANO) #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_NANO_V2) #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_LITE) - #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite + #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite env:mks_robin_lite_maple #elif MB(MKS_ROBIN_LITE3) - #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 + #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 env:mks_robin_lite3_maple #elif MB(MKS_ROBIN_PRO) - #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro + #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro env:mks_robin_pro_maple #elif MB(MKS_ROBIN_E3) #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple #elif MB(MKS_ROBIN_E3_V1_1) @@ -506,7 +506,7 @@ #elif MB(MKS_ROBIN_E3D_V1_1) #include "stm32f1/pins_MKS_ROBIN_E3D_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3P) - #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p + #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p env:mks_robin_e3p_maple #elif MB(BTT_SKR_MINI_V1_1) #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_0) @@ -522,21 +522,21 @@ #elif MB(BTT_SKR_CR6) #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(JGAURORA_A5S_A1) - #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 + #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 env:jgaurora_a5s_a1_maple #elif MB(FYSETC_AIO_II) - #include "stm32f1/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(FYSETC_CHEETAH) - #include "stm32f1/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(FYSETC_CHEETAH_V12) - #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc + #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(LONGER3D_LK) - #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer + #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer env:STM32F103VE_longer_maple #elif MB(CCROBOT_MEEB_3DP) #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb #elif MB(CHITU3D_V5) - #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_v5_gpio_init + #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple env:chitu_v5_gpio_init env:chitu_v5_gpio_init_maple #elif MB(CHITU3D_V6) - #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 + #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple #elif MB(CREALITY_V4) #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) @@ -550,7 +550,7 @@ #elif MB(CREALITY_V453) #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(TRIGORILLA_PRO) - #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro + #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple #elif MB(FLY_MINI) #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI env:FLY_MINI_maple #elif MB(FLSUN_HISPEED) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index e892d3e3f8..88dd28a401 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -134,6 +134,8 @@ #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #endif #if ENABLED(TFT_LVGL_UI) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index ab1e6c54f4..2a9ba83494 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -74,7 +74,7 @@ upload_protocol = dfu # # FYSETC STM32F103RC # -[env:STM32F103RC_fysetc] +[env:STM32F103RC_fysetc_maple] platform = ${common_stm32f1.platform} extends = common_STM32F103RC_maple extra_scripts = ${common_stm32f1.extra_scripts} @@ -173,7 +173,7 @@ upload_protocol = serial # # Longer 3D board in Alfawise U20 (STM32F103VET6) # -[env:STM32F103VE_longer] +[env:STM32F103VE_longer_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE @@ -190,7 +190,7 @@ build_unflags = ${common_stm32f1.build_unflags} # # MKS Robin Mini (STM32F103VET6) # -[env:mks_robin_mini] +[env:mks_robin_mini_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE @@ -228,7 +228,7 @@ build_flags = ${common_stm32f1.build_flags} # # MKS Robin Pro (STM32F103ZET6) # -[env:mks_robin_pro] +[env:mks_robin_pro_maple] platform = ${common_stm32f1.platform} extends = env:mks_robin_maple extra_scripts = ${common_stm32f1.extra_scripts} @@ -237,7 +237,7 @@ extra_scripts = ${common_stm32f1.extra_scripts} # # TRIGORILLA PRO (STM32F103ZET6) # -[env:trigorilla_pro] +[env:trigorilla_pro_maple] platform = ${common_stm32f1.platform} extends = env:mks_robin_maple extra_scripts = ${common_stm32f1.extra_scripts} @@ -259,7 +259,7 @@ build_flags = ${common_stm32f1.build_flags} # MKS Robin E3p (STM32F103VET6) # - LVGL UI # -[env:mks_robin_e3p] +[env:mks_robin_e3p_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE @@ -273,7 +273,7 @@ upload_protocol = jlink # # MKS Robin Lite/Lite2 (STM32F103RCT6) # -[env:mks_robin_lite] +[env:mks_robin_lite_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC @@ -283,7 +283,7 @@ extra_scripts = ${common_stm32f1.extra_scripts} # # MKS ROBIN LITE3 (STM32F103RCT6) # -[env:mks_robin_lite3] +[env:mks_robin_lite3_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC @@ -293,7 +293,7 @@ extra_scripts = ${common_stm32f1.extra_scripts} # # JGAurora A5S A1 (STM32F103ZET6) # -[env:jgaurora_a5s_a1] +[env:jgaurora_a5s_a1_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103ZE @@ -321,7 +321,7 @@ lib_ignore = ${common_stm32f1.lib_ignore} # # Chitu boards like Tronxy X5s (STM32F103ZET6) # -[env:chitu_f103] +[env:chitu_f103_maple] platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_CHITU_F103 @@ -338,10 +338,10 @@ build_unflags = ${common_stm32f1.build_unflags} # Some Chitu V5 boards have a problem with GPIO init. # Use this target if G28 or G29 are always failing. # -[env:chitu_v5_gpio_init] +[env:chitu_v5_gpio_init_maple] platform = ${common_stm32f1.platform} -extends = env:chitu_f103 -build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX +extends = env:chitu_f103_maple +build_flags = ${env:chitu_f103_maple.build_flags} -DCHITU_V5_Z_MIN_BUGFIX # # FLYmaker FLY Mini (STM32F103RCT6) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index d5f0741d41..f1446f3267 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -260,3 +260,153 @@ board_build.variant = MARLIN_F103Rx board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 extra_scripts = ${stm32f1_variant.extra_scripts} + +# +# MKS Robin Mini (STM32F103VET6) +# +[env:mks_robin_mini] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +board_build.core = stm32 +board_build.variant = MARLIN_F103Vx +board_build.offset = 0x7000 +board_build.encrypt = Robin_mini.bin +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE +board_upload.offset_address = 0x08007000 +extra_scripts = ${stm32f1_variant.extra_scripts} + +# +# MKS Robin Lite/Lite2 (STM32F103RCT6) +# +[env:mks_robin_lite] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103RC +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x5000 +board_build.encrypt = mksLite.bin +build_flags = ${common_stm32.build_flags} +board_upload.offset_address = 0x08005000 +extra_scripts = ${stm32f1_variant.extra_scripts} + +# +# MKS ROBIN LITE3 (STM32F103RCT6) +# +[env:mks_robin_lite3] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103RC +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x5000 +board_build.encrypt = mksLite3.bin +build_flags = ${common_stm32.build_flags} +board_upload.offset_address = 0x08005000 +extra_scripts = ${stm32f1_variant.extra_scripts} + +# +# MKS Robin Pro (STM32F103ZET6) +# +[env:mks_robin_pro] +platform = ${common_stm32.platform} +extends = env:mks_robin +board_build.encrypt = Robin_pro.bin + +# +# MKS Robin E3p (STM32F103VET6) +# - LVGL UI +# +[env:mks_robin_e3p] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +board_build.core = stm32 +board_build.variant = MARLIN_F103Vx +board_build.offset = 0x7000 +board_build.encrypt = Robin_e3p.bin +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 +board_upload.offset_address = 0x08007000 +extra_scripts = ${stm32f1_variant.extra_scripts} +debug_tool = jlink +upload_protocol = jlink + +# +# JGAurora A5S A1 (STM32F103ZET6) +# +[env:jgaurora_a5s_a1] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +board_build.core = stm32 +board_build.variant = MARLIN_F103Zx +board_build.offset = 0xA000 +board_build.rename = firmware_for_sd_upload.bin +build_flags = ${common_stm32.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY +board_build.address = 0x0800A000 +extra_scripts = ${stm32f1_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py + +# +# FYSETC STM32F103RC +# +[env:STM32F103RC_fysetc] +platform = ${common_stm32.platform} +extends = common_STM32F103RC +extra_scripts = ${stm32f1_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 +lib_ldf_mode = chain +debug_tool = stlink +upload_protocol = serial + +# +# Longer 3D board in Alfawise U20 (STM32F103VET6) +# +[env:STM32F103VE_longer] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +board_build.core = stm32 +board_build.variant = MARLIN_F103Zx +board_build.offset = 0x1000 +board_build.address = 0x08010000 +build_flags = ${common_stm32.build_flags} + -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 +build_unflags = ${common_stm32.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +extra_scripts = ${stm32f1_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py + +# +# TRIGORILLA PRO (STM32F103ZET6) +# +[env:trigorilla_pro] +platform = ${common_stm32.platform} +extends = env:mks_robin +extra_scripts = ${common_stm32.extra_scripts} + +# +# Chitu boards like Tronxy X5s (STM32F103ZET6) +# +[env:chitu_f103] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +board_build.core = stm32 +board_build.variant = MARLIN_F103Zx +extra_scripts = ${stm32f1_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/chitu_crypt.py +build_flags = ${common_stm32.build_flags} -DSTM32_XL_DENSITY +build_unflags = ${common_stm32.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + +# +# Some Chitu V5 boards have a problem with GPIO init. +# Use this target if G28 or G29 are always failing. +# +[env:chitu_v5_gpio_init] +platform = ${common_stm32.platform} +extends = env:chitu_f103 +build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX From 3be35a6bd6845a160c416629ea98392129cd6eb3 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Wed, 14 Jul 2021 21:13:08 -0600 Subject: [PATCH 0406/2168] =?UTF-8?q?=F0=9F=93=BA=20Fix=20Makefile=20build?= =?UTF-8?q?,=20improve=20Touch=20UI=20button=20titles=20(#22361)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/power.cpp | 4 ++++ .../extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp | 2 +- .../ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp | 2 +- .../extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp | 2 +- .../extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp | 2 +- .../generic/base_numeric_adjustment_screen.cpp | 2 +- .../extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/change_filament_screen.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp | 2 +- .../extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/interface_settings_screen.cpp | 4 ++-- .../ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp | 2 +- Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp | 2 +- Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp | 2 +- 25 files changed, 29 insertions(+), 25 deletions(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 9070fd7946..30bf0d764d 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -38,6 +38,8 @@ #include "../gcode/gcode.h" #endif +#if EITHER(PSU_CONTROL, AUTO_POWER_CONTROL) + Power powerManager; bool Power::psu_on; @@ -214,3 +216,5 @@ void Power::power_off() { #endif #endif // AUTO_POWER_CONTROL + +#endif // PSU_CONTROL || AUTO_POWER_CONTROL diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp index fd478c95a2..40ec16a9df 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp @@ -87,7 +87,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(13) .button(BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(14) .button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .colors(action_btn) - .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); #undef GRID_COLS #undef GRID_ROWS } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index ae5e7d8ab1..8109ecef76 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -54,7 +54,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(8).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(9).button(BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) - .tag(1).button(BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button(BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); } #undef GRID_COLS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp index 31021c31c0..2f94555784 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -54,7 +54,7 @@ void TuneMenu::onRedraw(draw_mode_t what) { .enabled(!isPrinting()).tag(5).button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) .enabled(!isPrinting()).tag(6).button(BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RAISE_PLUNGER)) .enabled(!isPrinting()).tag(7).button(BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) - .colors(action_btn) .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .colors(action_btn) .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); } #undef GRID_COLS #undef GRID_ROWS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp index d984dbe120..7549e8d54e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp @@ -67,7 +67,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(10).button(DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) .tag(11).button(RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index 6718fe0a41..d3950a7c6c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -71,7 +71,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { #undef GRID_COLS #define GRID_COLS 3 .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp index 8c15cae60f..d40b3be354 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp @@ -90,7 +90,7 @@ void LoadChocolateScreen::draw_buttons(draw_mode_t what) { cmd.tag(3).button(x, y, h, v, GET_TEXT_F(MSG_FULL_LOAD)); ui.bounds(POLY(load_screen_back_btn), x, y, h, v); - cmd.tag(1).colors(action_btn).button(x, y, h, v, GET_TEXT_F(MSG_BACK)); + cmd.tag(1).colors(action_btn).button(x, y, h, v, GET_TEXT_F(MSG_BUTTON_DONE)); } void LoadChocolateScreen::draw_text(draw_mode_t what) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index a990717fb3..3fe17b72d5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -68,7 +68,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(10).button(LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) .tag(11).button(ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp index 56e90ceb4d..424e0afa76 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -65,7 +65,7 @@ void PreheatMenu::onRedraw(draw_mode_t what) { } #endif cmd.colors(action_btn) - .tag(1) .button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .tag(1) .button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index 75b1fcc9c1..300878670e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -77,7 +77,7 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { CommandProcessor cmd; cmd.colors(normal_btn) .font(font_medium) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 68e50c90ac..3e07735edf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -94,7 +94,7 @@ void AboutScreen::onRedraw(draw_mode_t) { .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); #endif cmd.colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } bool AboutScreen::onTouchEnd(uint8_t tag) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index 503abbdb05..a83cc07515 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -111,7 +111,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .enabled(ENABLED(BACKLASH_GCODE)) .tag(8).button(BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index 90199783fd..d0ba74721c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -61,7 +61,7 @@ BaseNumericAdjustmentScreen::widgets_t::widgets_t(draw_mode_t what) : _what(what #else BTN_POS(15,7), BTN_SIZE(4,1), #endif - GET_TEXT_F(MSG_BACK), true, true + GET_TEXT_F(MSG_BUTTON_DONE), true, true ); _line = 1; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 3dfcd429a5..30b9d1c78a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -136,7 +136,7 @@ void BedMeshEditScreen::drawHighlightedPointValue() { if (mydata.highlight.x != NONE) draw_adjuster(cmd, Z_VALUE_POS, 3, getHighlightedValue(), GET_TEXT_F(MSG_UNITS_MM), 4, 3); cmd.colors(mydata.needSave ? normal_btn : action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_BACK)) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)) .colors(mydata.needSave ? action_btn : normal_btn) .enabled(mydata.needSave) .tag(2).button(SAVE_POS, GET_TEXT_F(MSG_TOUCHMI_SAVE)); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index 46d3a4ea1c..fa0748c17b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -224,7 +224,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { .tag(6) .enabled(t_ok).button (LOAD_MOMN_POS, GET_TEXT_F(MSG_MOMENTARY)) .tag(7).TOG_STYLE(tog7).enabled(t_ok).button (UNLD_CONT_POS, GET_TEXT_F(MSG_CONTINUOUS)) .tag(8).TOG_STYLE(tog8).enabled(t_ok).button (LOAD_CONT_POS, GET_TEXT_F(MSG_CONTINUOUS)) - .tag(1).colors(action_btn) .button (BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).colors(action_btn) .button (BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp index 5f8ff92922..8807480897 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -135,7 +135,7 @@ void CustomUserMenus::onRedraw(draw_mode_t what) { _USER_ITEM(20) #endif .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index d12cb32e20..c7042e760e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -120,7 +120,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { cmd.font(font_medium) .colors(action_btn) - .tag(1).button(BTN_POS(1,7), BTN_SIZE(6,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button(BTN_POS(1,7), BTN_SIZE(6,1), GET_TEXT_F(MSG_BUTTON_DONE)); #undef GRID_COLS #undef GRID_ROWS } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp index bd5fa96e8d..9c9e70cebf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_menu.cpp @@ -63,7 +63,7 @@ void FilamentMenu::onRedraw(draw_mode_t what) { .enabled(ENABLED(LIN_ADVANCE)) .tag(3).button(LIN_ADVANCE_POS, GET_TEXT_F(MSG_LINEAR_ADVANCE)) .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp index bf32502594..aa54e88967 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -168,7 +168,7 @@ void FilesScreen::drawFooter() { cmd.colors(normal_btn) .font(font_medium) .colors(has_selection ? normal_btn : action_btn) - .tag(back_tag).button(BTN_POS(4,y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BACK)) + .tag(back_tag).button(BTN_POS(4,y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_DONE)) .enabled(has_selection) .colors(has_selection ? action_btn : normal_btn); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp index a3febb39a2..ebefea2dcd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp @@ -108,11 +108,11 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .colors(normal_btn) .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) - .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); #else .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) - .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); #endif } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp index 3ba035f19b..b951844196 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp @@ -102,7 +102,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { .tag(5).button (BTN_POS(3,6), BTN_SIZE(2,1), getSoundSelection(PRINTING_FINISHED)) .tag(6).button (BTN_POS(3,7), BTN_SIZE(2,1), getSoundSelection(PRINTING_FAILED)) .colors(action_btn) - .tag(1).button (BTN_POS(1,9), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button (BTN_POS(1,9), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index acbc179891..e693bfb05c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -96,7 +96,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .tag(8).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) #endif .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index f7a0d6683a..3f614ec344 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -95,7 +95,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(11).button(CUSTOM_MENU_POS, GET_TEXT_F(MSG_CUSTOM_COMMANDS)) #endif .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp index 2153a1e1ad..b6d9770e9d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp @@ -63,7 +63,7 @@ void StatisticsScreen::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { cmd.font(Theme::font_medium) .colors(action_btn) - .tag(1).button(BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); + .tag(1).button(BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index a5e2460631..6f4beb6673 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -92,7 +92,7 @@ void TuneMenu::onRedraw(draw_mode_t what) { .tag(10).button(CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) .tag(11).button(ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(1).colors(action_btn) - .button(BACK_POS, GET_TEXT_F(MSG_BACK)); + .button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); } #undef GRID_COLS #undef GRID_ROWS From aec4a82a99fd6d1c3be7683068bcd7f5729904d0 Mon Sep 17 00:00:00 2001 From: Taylor Talkington Date: Thu, 15 Jul 2021 17:32:40 -0400 Subject: [PATCH 0407/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Filament=20Chang?= =?UTF-8?q?e=20menu=20(#22370)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22277 --- Marlin/src/lcd/menu/menu_filament.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index d70ed98aa8..53fd67dbb2 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -211,7 +211,7 @@ void menu_change_filament() { if (thermalManager.targetHotEnoughToExtrude(active_extruder)) queue.inject_P(PSTR("M600B0")); else - _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); + ui.goto_screen([]{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); #endif } From 0207569ca66a8fe60846d85ba1797f3c0204223c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 16 Jul 2021 00:59:11 +0000 Subject: [PATCH 0408/2168] [cron] Bump distribution date (2021-07-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 03855365ba..f21d618850 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-15" +//#define STRING_DISTRIBUTION_DATE "2021-07-16" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 49a0b94f64..6809c4b983 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 "2021-07-15" + #define STRING_DISTRIBUTION_DATE "2021-07-16" #endif /** From 5b43795f54f18bc956f1c4884640f18c9a7bdbce Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 16 Jul 2021 03:40:05 +0200 Subject: [PATCH 0409/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20HAL/ST?= =?UTF-8?q?M32=20targets=20(Longer3D=20timers)=20(#22369)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/variants/MARLIN_F103Vx/variant.h | 8 ++++++-- ini/stm32f1.ini | 16 +++++++--------- 2 files changed, 13 insertions(+), 11 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h index b622b39376..496d8817a1 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/variant.h @@ -132,8 +132,12 @@ extern "C" { // Timer Definitions (optional) // Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin -#define TIMER_TONE TIM3 -#define TIMER_SERVO TIM2 +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif // UART Definitions // Define here Serial instance number to map on Serial generic name diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index f1446f3267..bc4236b8f0 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -194,7 +194,7 @@ build_flags = ${env:STM32F103RE_btt.build_flags} ${env:stm32_flash_drive.b [env:flsun_hispeedv1] platform = ${common_stm32.platform} extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 board = genericSTM32F103VE board_build.core = stm32 board_build.variant = MARLIN_F103Vx @@ -210,7 +210,7 @@ extra_scripts = ${stm32f1_variant.extra_scripts} [env:mks_robin_nano35] platform = ${common_stm32.platform} extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 board = genericSTM32F103VE board_build.core = stm32 board_build.variant = MARLIN_F103Vx @@ -272,7 +272,7 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.offset = 0x7000 board_build.encrypt = Robin_mini.bin -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 board_upload.offset_address = 0x08007000 extra_scripts = ${stm32f1_variant.extra_scripts} @@ -326,7 +326,7 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.offset = 0x7000 board_build.encrypt = Robin_e3p.bin -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 board_upload.offset_address = 0x08007000 extra_scripts = ${stm32f1_variant.extra_scripts} debug_tool = jlink @@ -369,13 +369,11 @@ platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103VE board_build.core = stm32 -board_build.variant = MARLIN_F103Zx +board_build.variant = MARLIN_F103Vx board_build.offset = 0x1000 board_build.address = 0x08010000 -build_flags = ${common_stm32.build_flags} - -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 -build_unflags = ${common_stm32.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 +build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC extra_scripts = ${stm32f1_variant.extra_scripts} buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py From 5d6317329786f5d01eb6734b4c5e664a2fe9e6ba Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Thu, 15 Jul 2021 20:57:34 -0500 Subject: [PATCH 0410/2168] =?UTF-8?q?=E2=9C=A8=20MKS=20Mini12864=20v3=20fo?= =?UTF-8?q?r=20Robin=20E3/E3D=20(#22368)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 5 ++-- .../variants/MARLIN_F103Rx/variant.h | 24 +++++++++++++++---- ini/stm32f1.ini | 3 +-- 3 files changed, 23 insertions(+), 9 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 127dfb7c7a..bc47c9169f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -156,7 +156,6 @@ #define DOGLCD_MOSI PB15 #elif ENABLED(MKS_MINI_12864_V3) - #define ENABLE_SPI3 #define DOGLCD_CS PA4 #define DOGLCD_A0 PA5 #define LCD_PINS_DC DOGLCD_A0 @@ -165,7 +164,9 @@ #define NEOPIXEL_PIN PA7 #define DOGLCD_MOSI PB15 #define DOGLCD_SCK PB13 - + #define FORCE_SOFT_SPI + #define SOFTWARE_SPI + #else #define LCD_PINS_D4 PA6 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h index 7dcbb793d0..41b194abe0 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -101,11 +101,24 @@ extern "C" { #endif // Override default Arduino configuration + // SPI Definitions -#define PIN_SPI_SS PA4 -#define PIN_SPI_MOSI PA7 -#define PIN_SPI_MISO PA6 -#define PIN_SPI_SCK PA5 +#if DEFAULT_SPI == 3 + #define PIN_SPI_SS PA15 + #define PIN_SPI_MOSI PB3 + #define PIN_SPI_MISO PB4 + #define PIN_SPI_SCK PB5 +#elif DEFAULT_SPI == 2 + #define PIN_SPI_SS PB12 + #define PIN_SPI_MOSI PB13 + #define PIN_SPI_MISO PB14 + #define PIN_SPI_SCK PB15 +#else + #define PIN_SPI_SS PA4 + #define PIN_SPI_MOSI PA7 + #define PIN_SPI_MISO PA6 + #define PIN_SPI_SCK PA5 +#endif // I2C Definitions #define PIN_WIRE_SDA PB7 @@ -118,6 +131,7 @@ extern "C" { #ifndef TIMER_SERVO #define TIMER_SERVO TIM2 #endif + // UART Definitions // Define here Serial instance number to map on Serial generic name #define SERIAL_UART_INSTANCE 1 @@ -126,7 +140,7 @@ extern "C" { #define PIN_SERIAL_RX PA10 #define PIN_SERIAL_TX PA9 -/* Extra HAL modules */ +// Extra HAL modules #if defined(STM32F103xE) || defined(STM32F103xG) #define HAL_DAC_MODULE_ENABLED #endif diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index bc4236b8f0..6350afb40b 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -125,8 +125,7 @@ lib_deps = [env:mks_robin_e3] platform = ${common_stm32.platform} extends = common_STM32F103RC -build_flags = ${common_stm32.build_flags} - -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 +build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 -DDEFAULT_SPI=3 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC monitor_speed = 115200 board_build.offset = 0x5000 From 665cb5ea10b140a510c03318d55967b9c6633163 Mon Sep 17 00:00:00 2001 From: bilsef Date: Thu, 15 Jul 2021 18:59:52 -0700 Subject: [PATCH 0411/2168] =?UTF-8?q?=E2=9C=A8=20M115:=20Axis=20Count=20(#?= =?UTF-8?q?22219)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 49bb806377..3b88c6905e 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -54,6 +54,9 @@ void GcodeSuite::M115() { "PROTOCOL_VERSION:" PROTOCOL_VERSION " " "MACHINE_TYPE:" MACHINE_NAME " " "EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " " + #if LINEAR_AXES != XYZ + "AXIS_COUNT:" STRINGIFY(LINEAR_AXES) " " + #endif #ifdef MACHINE_UUID "UUID:" MACHINE_UUID #endif From 7b64bbf38424e5f6c03c2748a54e85320e577a29 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 17 Jul 2021 00:56:52 +0000 Subject: [PATCH 0412/2168] [cron] Bump distribution date (2021-07-17) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f21d618850..0d7518225c 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-16" +//#define STRING_DISTRIBUTION_DATE "2021-07-17" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6809c4b983..a825f38734 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 "2021-07-16" + #define STRING_DISTRIBUTION_DATE "2021-07-17" #endif /** From be1801703c4510dcd523de811e9dcff576b4caad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 17 Jul 2021 03:10:54 -0500 Subject: [PATCH 0413/2168] =?UTF-8?q?=F0=9F=8E=A8=20Add=20MMU2=20enabled()?= =?UTF-8?q?=20accessor?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/mmu/mmu2.cpp | 28 +++++++++---------- Marlin/src/feature/mmu/mmu2.h | 3 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- 3 files changed, 17 insertions(+), 16 deletions(-) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 8a4f5ae071..1acd26f331 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -75,7 +75,7 @@ MMU2 mmu2; #define MMU2_NO_TOOL 99 #define MMU_BAUD 115200 -bool MMU2::enabled, MMU2::ready, MMU2::mmu_print_saved; +bool MMU2::_enabled, MMU2::ready, MMU2::mmu_print_saved; #if HAS_PRUSA_MMU2S bool MMU2::mmu2s_triggered; #endif @@ -219,7 +219,7 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPAIR("MMU => ", finda, "\nMMU - ENABLED"); - enabled = true; + _enabled = true; state = 1; TERN_(HAS_PRUSA_MMU2S, mmu2s_triggered = false); } @@ -480,7 +480,7 @@ static void mmu2_not_responding() { */ void MMU2::tool_change(const uint8_t index) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -512,7 +512,7 @@ static void mmu2_not_responding() { * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. */ void MMU2::tool_change(const char *special) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -561,7 +561,7 @@ static void mmu2_not_responding() { * Handle tool change */ void MMU2::tool_change(const uint8_t index) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -599,7 +599,7 @@ static void mmu2_not_responding() { * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. */ void MMU2::tool_change(const char *special) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -665,7 +665,7 @@ static void mmu2_not_responding() { * Handle tool change */ void MMU2::tool_change(const uint8_t index) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -693,7 +693,7 @@ static void mmu2_not_responding() { * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. */ void MMU2::tool_change(const char *special) { - if (!enabled) return; + if (!_enabled) return; set_runout_valid(false); @@ -744,7 +744,7 @@ static void mmu2_not_responding() { * Set next command */ void MMU2::command(const uint8_t mmu_cmd) { - if (!enabled) return; + if (!_enabled) return; cmd = mmu_cmd; ready = false; } @@ -833,7 +833,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { } void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) { - if (!enabled) return; + if (!_enabled) return; cmd_arg = filamentType; command(MMU_CMD_F0 + index); @@ -892,7 +892,7 @@ void MMU2::filament_runout() { // Load filament into MMU2 void MMU2::load_filament(const uint8_t index) { - if (!enabled) return; + if (!_enabled) return; command(MMU_CMD_L0 + index); manage_response(false, false); @@ -904,7 +904,7 @@ void MMU2::load_filament(const uint8_t index) { */ bool MMU2::load_filament_to_nozzle(const uint8_t index) { - if (!enabled) return false; + if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); @@ -940,7 +940,7 @@ void MMU2::load_to_nozzle() { bool MMU2::eject_filament(const uint8_t index, const bool recover) { - if (!enabled) return false; + if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); @@ -989,7 +989,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { */ bool MMU2::unload() { - if (!enabled) return false; + if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 079a6ef79a..95338a5184 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -43,6 +43,7 @@ public: static void init(); static void reset(); + static inline bool enabled() { return _enabled; } static void mmu_loop(); static void tool_change(const uint8_t index); static void tool_change(const char *special); @@ -88,7 +89,7 @@ private: static void mmu_continue_loading(); #endif - static bool enabled, ready, mmu_print_saved; + static bool _enabled, ready, mmu_print_saved; static uint8_t cmd, cmd_arg, last_cmd, extruder; static int8_t state; diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index bc47c9169f..b5d02942f3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -166,7 +166,7 @@ #define DOGLCD_SCK PB13 #define FORCE_SOFT_SPI #define SOFTWARE_SPI - + #else #define LCD_PINS_D4 PA6 From cb461b5daffebfe86d1d2f96093be09e445cbd05 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 18 Jul 2021 00:16:57 +0200 Subject: [PATCH 0414/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Longer3D=20build?= =?UTF-8?q?=20environment=20(#22378)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/STM32F103VE_longer_maple | 23 +++++++++++++++++++++++ ini/stm32f1.ini | 7 +++++-- 2 files changed, 28 insertions(+), 2 deletions(-) create mode 100755 buildroot/tests/STM32F103VE_longer_maple diff --git a/buildroot/tests/STM32F103VE_longer_maple b/buildroot/tests/STM32F103VE_longer_maple new file mode 100755 index 0000000000..4570a3214d --- /dev/null +++ b/buildroot/tests/STM32F103VE_longer_maple @@ -0,0 +1,23 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103VET6 (using maple STM32F1 framework) +# + +# exit on first failure +set -e + +use_example_configs Alfawise/U20 +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "maple CLASSIC_UI U20 config" "$3" + +use_example_configs Alfawise/U20 +opt_enable BAUD_RATE_GCODE TFT_COLOR_UI +opt_disable TFT_CLASSIC_UI CUSTOM_STATUS_SCREEN_IMAGE +exec_test $1 $2 "maple COLOR_UI U20 config" "$3" + +use_example_configs Alfawise/U20-bltouch +opt_enable BAUD_RATE_GCODE +exec_test $1 $2 "maple BLTouch U20 config" + +# cleanup +restore_configs diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 6350afb40b..f487dc62fc 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -369,10 +369,13 @@ extends = common_stm32 board = genericSTM32F103VE board_build.core = stm32 board_build.variant = MARLIN_F103Vx -board_build.offset = 0x1000 +board_build.offset = 0x10000 board_build.address = 0x08010000 build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC + -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA -UPIN_WIRE_SCL -DPIN_WIRE_SDA=PB11 -DPIN_WIRE_SCL=PB10 + -DHAL_DAC_MODULE_DISABLED -DHAL_I2S_MODULE_DISABLED +build_unflags = ${common_stm32.build_unflags} + -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED extra_scripts = ${stm32f1_variant.extra_scripts} buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py From be5dec9795783b97aa3f8ab89c0a33091c5a4842 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 18 Jul 2021 01:00:12 +0000 Subject: [PATCH 0415/2168] [cron] Bump distribution date (2021-07-18) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0d7518225c..c1cd96ecac 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-17" +//#define STRING_DISTRIBUTION_DATE "2021-07-18" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a825f38734..b88141a5b7 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 "2021-07-17" + #define STRING_DISTRIBUTION_DATE "2021-07-18" #endif /** From 9d86241d30da0946aa1b16d77fe5f8ef95a9996b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 Jul 2021 00:45:17 -0500 Subject: [PATCH 0416/2168] =?UTF-8?q?=F0=9F=90=9B=20No=20translated=20seri?= =?UTF-8?q?al=20strings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 4 +--- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 ++-- Marlin/src/gcode/calibrate/M852.cpp | 2 +- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index bb7b227b53..1da030b249 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1273,9 +1273,7 @@ void setup() { if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); HAL_clear_reset_source(); - SERIAL_ECHOPGM_P(GET_TEXT(MSG_MARLIN)); - SERIAL_CHAR(' '); - SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); + SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); SERIAL_EOL(); #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index e1ed013cf2..f8e446cf81 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -916,11 +916,11 @@ void set_message_with_feedback(PGM_P const msg_P) { if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing if (parser.seen_test('B')) { - SERIAL_ECHOPGM_P(GET_TEXT(MSG_UBL_BC_INSERT)); + SERIAL_ECHOPGM("Place Shim & Measure"); LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); } else { - SERIAL_ECHOPGM_P(GET_TEXT(MSG_UBL_BC_INSERT2)); + SERIAL_ECHOPGM("Measure"); LCD_MESSAGEPGM(MSG_UBL_BC_INSERT2); } diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index 6f1e984bc3..73b18ad466 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -93,7 +93,7 @@ void GcodeSuite::M852() { if (!ijk) { SERIAL_ECHO_START(); - SERIAL_ECHOPGM_P(GET_TEXT(MSG_SKEW_FACTOR)); + SERIAL_ECHOPGM("Skew Factor"); SERIAL_ECHOPAIR_F(" XY: ", planner.skew_factor.xy, 6); #if ENABLED(SKEW_CORRECTION_FOR_Z) SERIAL_ECHOPAIR_F(" XZ: ", planner.skew_factor.xz, 6); From 49da4ee4e2942f6897b0833bf35c054f9fcab4fa Mon Sep 17 00:00:00 2001 From: squiddity Date: Sat, 17 Jul 2021 22:50:39 -0700 Subject: [PATCH 0417/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M913=20typos=20(?= =?UTF-8?q?#22385)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/trinamic/M911-M914.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index f90a30aab2..fca16c0630 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -260,10 +260,10 @@ #endif case Z_AXIS: - TERN_(Z_HAS_STEALTCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); - TERN_(Z2_HAS_STEALTCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); - TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); - TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); + TERN_(Z_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); break; #if E_STEPPERS case E_AXIS: { From e55427aaa2cbe2d37a9502a0f9ac73feceb183dc Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sat, 17 Jul 2021 23:10:13 -0700 Subject: [PATCH 0418/2168] =?UTF-8?q?=F0=9F=8E=A8=20Prefer=20DELAY=5FNS=20?= =?UTF-8?q?over=20DELAY=5FCYCLES=20(#22382)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/HAL_SPI.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index f42e8a9802..758640285b 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -240,7 +240,7 @@ } // all the others - static uint32_t spiDelayCyclesX4 = 4 * (F_CPU) / 1000000; // 4µs => 125khz + static uint16_t spiDelayNS = 4000; // 4000ns => 125khz static uint8_t spiTransferX(uint8_t b) { // using Mode 0 int bits = 8; @@ -249,12 +249,12 @@ b <<= 1; // little setup time WRITE(SD_SCK_PIN, HIGH); - DELAY_CYCLES(spiDelayCyclesX4); + DELAY_NS(spiDelayNS); b |= (READ(SD_MISO_PIN) != 0); WRITE(SD_SCK_PIN, LOW); - DELAY_CYCLES(spiDelayCyclesX4); + DELAY_NS(spiDelayNS); } while (--bits); return b; } @@ -510,7 +510,7 @@ spiRxBlock = (pfnSpiRxBlock)spiRxBlockX; break; default: - spiDelayCyclesX4 = ((F_CPU) / 1000000) >> (6 - spiRate) << 2; // spiRate of 2 gives the maximum error with current CPU + spiDelayNS = 4000 >> (6 - spiRate); // spiRate of 2 gives the maximum error with current CPU spiTransferTx = (pfnSpiTransfer)spiTransferX; spiTransferRx = (pfnSpiTransfer)spiTransferX; spiTxBlock = (pfnSpiTxBlock)spiTxBlockX; From b34a009bb1e114addf2d831171fab967d93a651f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 Jul 2021 19:56:28 -0500 Subject: [PATCH 0419/2168] =?UTF-8?q?=F0=9F=90=9B=20Change=20font=20for=20?= =?UTF-8?q?selected=20language=20(#22381)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/multi_language.h | 3 - Marlin/src/lcd/dogm/fontdata/langdata.h | 23 + Marlin/src/lcd/dogm/fontdata/langdata_an.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_bg.h | 23 +- Marlin/src/lcd/dogm/fontdata/langdata_ca.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_cz.h | 25 +- Marlin/src/lcd/dogm/fontdata/langdata_da.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_de.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_el.h | 27 +- Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h | 27 +- Marlin/src/lcd/dogm/fontdata/langdata_en.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_es.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_eu.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_fi.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_fr.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_gl.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_hr.h | 17 +- Marlin/src/lcd/dogm/fontdata/langdata_hu.h | 9 +- Marlin/src/lcd/dogm/fontdata/langdata_it.h | 7 +- .../src/lcd/dogm/fontdata/langdata_jp_kana.h | 31 +- Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h | 219 +++--- Marlin/src/lcd/dogm/fontdata/langdata_nl.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_pl.h | 19 +- Marlin/src/lcd/dogm/fontdata/langdata_pt.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_ro.h | 7 +- Marlin/src/lcd/dogm/fontdata/langdata_ru.h | 15 +- Marlin/src/lcd/dogm/fontdata/langdata_sk.h | 21 +- Marlin/src/lcd/dogm/fontdata/langdata_test.h | 13 +- Marlin/src/lcd/dogm/fontdata/langdata_tr.h | 13 +- Marlin/src/lcd/dogm/fontdata/langdata_uk.h | 23 +- Marlin/src/lcd/dogm/fontdata/langdata_vi.h | 97 +-- Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h | 719 +++++++++--------- Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h | 605 +++++++-------- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 36 +- Marlin/src/lcd/dogm/u8g_fontutf8.h | 3 + Marlin/src/lcd/language/language_zh_CN.h | 2 +- Marlin/src/lcd/marlinui.cpp | 8 + Marlin/src/lcd/marlinui.h | 12 +- 39 files changed, 1095 insertions(+), 1000 deletions(-) create mode 100644 Marlin/src/lcd/dogm/fontdata/langdata.h diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 5a26edf8d4..1eaef69305 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -42,15 +42,12 @@ typedef const char Language_Str[]; #ifndef LCD_LANGUAGE_2 #define LCD_LANGUAGE_2 LCD_LANGUAGE #endif - #ifndef LCD_LANGUAGE_3 #define LCD_LANGUAGE_3 LCD_LANGUAGE_2 #endif - #ifndef LCD_LANGUAGE_4 #define LCD_LANGUAGE_4 LCD_LANGUAGE_3 #endif - #ifndef LCD_LANGUAGE_5 #define LCD_LANGUAGE_5 LCD_LANGUAGE_4 #endif diff --git a/Marlin/src/lcd/dogm/fontdata/langdata.h b/Marlin/src/lcd/dogm/fontdata/langdata.h new file mode 100644 index 0000000000..746a3bd0b4 --- /dev/null +++ b/Marlin/src/lcd/dogm/fontdata/langdata.h @@ -0,0 +1,23 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 + +#include + +#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_an.h b/Marlin/src/lcd/dogm/fontdata/langdata_an.h index 7989690f1f..fb0fdcf893 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_an.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_an.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_an[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h index 8d5d7e8321..20cd7b9ed7 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_bg.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_bg.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_144_149[96] U8G_FONT_SECTION("fontpage_8_144_149") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0x95,0x00,0x07,0xFF,0x00, @@ -64,14 +66,13 @@ const u8g_fntpgm_uint8_t fontpage_8_206_207[39] U8G_FONT_SECTION("fontpage_8_206 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xA8,0xE8,0xA8,0x90,0x04,0x05,0x05,0x06, 0x01,0x00,0x70,0x90,0x70,0x50,0x90}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 144, 149, fontpage_8_144_149), // 'А' -- 'Е' - FONTDATA_ITEM(8, 151, 152, fontpage_8_151_152), // 'З' -- 'И' - FONTDATA_ITEM(8, 154, 164, fontpage_8_154_164), // 'К' -- 'Ф' - FONTDATA_ITEM(8, 166, 166, fontpage_8_166_166), // 'Ц' -- 'Ц' - FONTDATA_ITEM(8, 175, 195, fontpage_8_175_195), // 'Я' -- 'у' - FONTDATA_ITEM(8, 197, 200, fontpage_8_197_200), // 'х' -- 'ш' - FONTDATA_ITEM(8, 202, 202, fontpage_8_202_202), // 'ъ' -- 'ъ' - FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' +static const uxg_fontinfo_t g_fontinfo_bg[] PROGMEM = { + FONTDATA_ITEM(8, 144, 149, fontpage_8_144_149), // 'А' -- 'Е' + FONTDATA_ITEM(8, 151, 152, fontpage_8_151_152), // 'З' -- 'И' + FONTDATA_ITEM(8, 154, 164, fontpage_8_154_164), // 'К' -- 'Ф' + FONTDATA_ITEM(8, 166, 166, fontpage_8_166_166), // 'Ц' -- 'Ц' + FONTDATA_ITEM(8, 175, 195, fontpage_8_175_195), // 'Я' -- 'у' + FONTDATA_ITEM(8, 197, 200, fontpage_8_197_200), // 'х' -- 'ш' + FONTDATA_ITEM(8, 202, 202, fontpage_8_202_202), // 'ъ' -- 'ъ' + FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h index 7989690f1f..deac3678b5 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ca.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ca.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_ca[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h index e6894a8d30..39f03f3a97 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_cz.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_cz.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_140_141[47] U8G_FONT_SECTION("fontpage_2_140_141") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8D,0x00,0x0A,0x00,0x00, @@ -40,15 +42,14 @@ const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253 0x00,0x05,0x0A,0x0A,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x08,0x10,0x20,0x40,0x80, 0xF8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' - FONTDATA_ITEM(2, 143, 143, fontpage_2_143_143), // 'ď' -- 'ď' - FONTDATA_ITEM(2, 154, 155, fontpage_2_154_155), // 'Ě' -- 'ě' - FONTDATA_ITEM(2, 200, 200, fontpage_2_200_200), // 'ň' -- 'ň' - FONTDATA_ITEM(2, 216, 217, fontpage_2_216_217), // 'Ř' -- 'ř' - FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' - FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' - FONTDATA_ITEM(2, 239, 239, fontpage_2_239_239), // 'ů' -- 'ů' - FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_cz[] PROGMEM = { + FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' + FONTDATA_ITEM(2, 143, 143, fontpage_2_143_143), // 'ď' -- 'ď' + FONTDATA_ITEM(2, 154, 155, fontpage_2_154_155), // 'Ě' -- 'ě' + FONTDATA_ITEM(2, 200, 200, fontpage_2_200_200), // 'ň' -- 'ň' + FONTDATA_ITEM(2, 216, 217, fontpage_2_216_217), // 'Ř' -- 'ř' + FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' + FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' + FONTDATA_ITEM(2, 239, 239, fontpage_2_239_239), // 'ů' -- 'ů' + FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_da.h b/Marlin/src/lcd/dogm/fontdata/langdata_da.h index 7989690f1f..ad8df9a429 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_da.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_da.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_da[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_de.h b/Marlin/src/lcd/dogm/fontdata/langdata_de.h index 7989690f1f..44230fa302 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_de.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_de.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_de[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el.h b/Marlin/src/lcd/dogm/fontdata/langdata_el.h index f949f28ca6..6fefab9c61 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, @@ -75,16 +77,15 @@ const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_1 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA6,0xA6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xA8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' - FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' - FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' - FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' - FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' - FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' - FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' - FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' - FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' - FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' +static const uxg_fontinfo_t g_fontinfo_el[] PROGMEM = { + FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' + FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' + FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' + FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' + FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' + FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' + FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' + FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' + FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' + FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h index f949f28ca6..8d7cba8615 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_7_136_136[33] U8G_FONT_SECTION("fontpage_7_136_136") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x88,0x88,0x00,0x0A,0x00,0x00, @@ -75,16 +77,15 @@ const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_1 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA6,0xA6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xA8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' - FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' - FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' - FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' - FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' - FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' - FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' - FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' - FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' - FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' +static const uxg_fontinfo_t g_fontinfo_el_gr[] PROGMEM = { + FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' + FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' + FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' + FONTDATA_ITEM(7, 163, 167, fontpage_7_163_167), // 'Σ' -- 'Χ' + FONTDATA_ITEM(7, 172, 175, fontpage_7_172_175), // 'ά' -- 'ί' + FONTDATA_ITEM(7, 177, 181, fontpage_7_177_181), // 'α' -- 'ε' + FONTDATA_ITEM(7, 183, 199, fontpage_7_183_199), // 'η' -- 'χ' + FONTDATA_ITEM(7, 201, 201, fontpage_7_201_201), // 'ω' -- 'ω' + FONTDATA_ITEM(7, 204, 206, fontpage_7_204_206), // 'ό' -- 'ώ' + FONTDATA_ITEM(64, 166, 166, fontpage_64_166_166), // '…' -- '…' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_en.h b/Marlin/src/lcd/dogm/fontdata/langdata_en.h index 7989690f1f..a69161b562 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_en.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_en.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_en[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_es.h b/Marlin/src/lcd/dogm/fontdata/langdata_es.h index 7989690f1f..a8ddb44ce8 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_es.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_es.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_es[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h index 7989690f1f..3fdc0253bc 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_eu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_eu.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_eu[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h index 7989690f1f..25e1927537 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fi.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_fi[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h index 7989690f1f..a3cc160c97 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_fr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_fr.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_fr[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h index 7989690f1f..2f93d05dbe 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_gl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_gl.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_gl[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h index e5430834ad..b5e4d544cc 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_135_135[31] U8G_FONT_SECTION("fontpage_2_135_135") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x87,0x87,0x00,0x08,0x00,0x00, @@ -22,11 +24,10 @@ const u8g_fntpgm_uint8_t fontpage_2_254_254[31] U8G_FONT_SECTION("fontpage_2_254 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFE,0xFE,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' - FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' - FONTDATA_ITEM(2, 145, 145, fontpage_2_145_145), // 'đ' -- 'đ' - FONTDATA_ITEM(2, 225, 225, fontpage_2_225_225), // 'š' -- 'š' - FONTDATA_ITEM(2, 254, 254, fontpage_2_254_254), // 'ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_hr[] PROGMEM = { + FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' + FONTDATA_ITEM(2, 140, 141, fontpage_2_140_141), // 'Č' -- 'č' + FONTDATA_ITEM(2, 145, 145, fontpage_2_145_145), // 'đ' -- 'đ' + FONTDATA_ITEM(2, 225, 225, fontpage_2_225_225), // 'š' -- 'š' + FONTDATA_ITEM(2, 254, 254, fontpage_2_254_254), // 'ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h index eb43cbea0f..450662a8c9 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_hu.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_hu.h @@ -3,13 +3,14 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_241_241[31] U8G_FONT_SECTION("fontpage_2_241_241") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xF1,0xF1,0x00,0x08,0x00,0x00, 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x48,0x90,0x00,0x88,0x88,0x88,0x88,0x70}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 241, 241, fontpage_2_241_241), // 'ű' -- 'ű' +static const uxg_fontinfo_t g_fontinfo_hu[] PROGMEM = { + FONTDATA_ITEM(2, 241, 241, fontpage_2_241_241), // 'ű' -- 'ű' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_it.h b/Marlin/src/lcd/dogm/fontdata/langdata_it.h index 7989690f1f..1a41a794fa 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_it.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_it.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_it[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h index 4d0ec6ab4f..dc483b7d2b 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_jp_kana.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_97_161_164[65] U8G_FONT_SECTION("fontpage_97_161_164") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA1,0xA4,0x00,0x07,0x00,0x00, @@ -94,18 +96,17 @@ const u8g_fntpgm_uint8_t fontpage_97_252_252[25] U8G_FONT_SECTION("fontpage_97_2 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFC,0xFC,0x00,0x05,0x00,0x00, 0x00,0x05,0x02,0x02,0x06,0x00,0x03,0x80,0x78}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(97, 161, 164, fontpage_97_161_164), // 'ァ' -- 'イ' - FONTDATA_ITEM(97, 166, 166, fontpage_97_166_166), // 'ウ' -- 'ウ' - FONTDATA_ITEM(97, 168, 168, fontpage_97_168_168), // 'エ' -- 'エ' - FONTDATA_ITEM(97, 170, 187, fontpage_97_170_187), // 'オ' -- 'セ' - FONTDATA_ITEM(97, 189, 193, fontpage_97_189_193), // 'ソ' -- 'チ' - FONTDATA_ITEM(97, 195, 211, fontpage_97_195_211), // 'ッ' -- 'ビ' - FONTDATA_ITEM(97, 213, 217, fontpage_97_213_217), // 'フ' -- 'ベ' - FONTDATA_ITEM(97, 219, 220, fontpage_97_219_220), // 'ホ' -- 'ボ' - FONTDATA_ITEM(97, 222, 223, fontpage_97_222_223), // 'マ' -- 'ミ' - FONTDATA_ITEM(97, 225, 237, fontpage_97_225_237), // 'メ' -- 'ロ' - FONTDATA_ITEM(97, 242, 243, fontpage_97_242_243), // 'ヲ' -- 'ン' - FONTDATA_ITEM(97, 252, 252, fontpage_97_252_252), // 'ー' -- 'ー' +static const uxg_fontinfo_t g_fontinfo_jp_kana[] PROGMEM = { + FONTDATA_ITEM(97, 161, 164, fontpage_97_161_164), // 'ァ' -- 'イ' + FONTDATA_ITEM(97, 166, 166, fontpage_97_166_166), // 'ウ' -- 'ウ' + FONTDATA_ITEM(97, 168, 168, fontpage_97_168_168), // 'エ' -- 'エ' + FONTDATA_ITEM(97, 170, 187, fontpage_97_170_187), // 'オ' -- 'セ' + FONTDATA_ITEM(97, 189, 193, fontpage_97_189_193), // 'ソ' -- 'チ' + FONTDATA_ITEM(97, 195, 211, fontpage_97_195_211), // 'ッ' -- 'ビ' + FONTDATA_ITEM(97, 213, 217, fontpage_97_213_217), // 'フ' -- 'ベ' + FONTDATA_ITEM(97, 219, 220, fontpage_97_219_220), // 'ホ' -- 'ボ' + FONTDATA_ITEM(97, 222, 223, fontpage_97_222_223), // 'マ' -- 'ミ' + FONTDATA_ITEM(97, 225, 237, fontpage_97_225_237), // 'メ' -- 'ロ' + FONTDATA_ITEM(97, 242, 243, fontpage_97_242_243), // 'ヲ' -- 'ン' + FONTDATA_ITEM(97, 252, 252, fontpage_97_252_252), // 'ー' -- 'ー' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h index 23c84d6573..31cc0bca36 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ko_KR.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_344_240_240[34] U8G_FONT_SECTION("fontpage_344_240_240") = { 0x00,0x0B,0x0D,0x00,0xFD,0x00,0x00,0x00,0x00,0x00,0xF0,0xF0,0x00,0x09,0xFE,0x00, @@ -436,112 +438,111 @@ const u8g_fntpgm_uint8_t fontpage_431_136_136[34] U8G_FONT_SECTION("fontpage_431 0x00,0x08,0x0B,0x0B,0x0A,0x01,0xFE,0x71,0x01,0xFD,0x01,0x71,0x49,0x89,0x49,0x71, 0x01,0x01}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(344, 240, 240, fontpage_344_240_240), // '거' -- '거' - FONTDATA_ITEM(345, 224, 224, fontpage_345_224_224), // '고' -- '고' - FONTDATA_ITEM(347, 248, 248, fontpage_347_248_248), // '그' -- '그' - FONTDATA_ITEM(348, 137, 137, fontpage_348_137_137), // '급' -- '급' - FONTDATA_ITEM(348, 176, 176, fontpage_348_176_176), // '기' -- '기' - FONTDATA_ITEM(348, 197, 197, fontpage_348_197_197), // '깅' -- '깅' - FONTDATA_ITEM(352, 196, 196, fontpage_352_196_196), // '끄' -- '끄' - FONTDATA_ITEM(353, 180, 180, fontpage_353_180_180), // '내' -- '내' - FONTDATA_ITEM(354, 248, 248, fontpage_354_248_248), // '노' -- '노' - FONTDATA_ITEM(356, 132, 132, fontpage_356_132_132), // '누' -- '누' - FONTDATA_ITEM(356, 244, 244, fontpage_356_244_244), // '뉴' -- '뉴' - FONTDATA_ITEM(357, 200, 200, fontpage_357_200_200), // '니' -- '니' - FONTDATA_ITEM(357, 228, 228, fontpage_357_228_228), // '다' -- '다' - FONTDATA_ITEM(357, 249, 249, fontpage_357_249_249), // '당' -- '당' - FONTDATA_ITEM(359, 196, 196, fontpage_359_196_196), // '도' -- '도' - FONTDATA_ITEM(359, 204, 204, fontpage_359_204_204), // '돌' -- '돌' - FONTDATA_ITEM(359, 217, 217, fontpage_359_217_217), // '동' -- '동' - FONTDATA_ITEM(360, 152, 152, fontpage_360_152_152), // '되' -- '되' - FONTDATA_ITEM(360, 156, 156, fontpage_360_156_156), // '된' -- '된' - FONTDATA_ITEM(360, 168, 168, fontpage_360_168_168), // '됨' -- '됨' - FONTDATA_ITEM(361, 164, 164, fontpage_361_164_164), // '뒤' -- '뒤' - FONTDATA_ITEM(361, 220, 220, fontpage_361_220_220), // '드' -- '드' - FONTDATA_ITEM(362, 148, 148, fontpage_362_148_148), // '디' -- '디' - FONTDATA_ITEM(366, 252, 252, fontpage_366_252_252), // '라' -- '라' - FONTDATA_ITEM(367, 236, 236, fontpage_367_236_236), // '러' -- '러' - FONTDATA_ITEM(368, 136, 136, fontpage_368_136_136), // '레' -- '레' - FONTDATA_ITEM(368, 165, 165, fontpage_368_165_165), // '력' -- '력' - FONTDATA_ITEM(368, 220, 220, fontpage_368_220_220), // '로' -- '로' - FONTDATA_ITEM(369, 204, 204, fontpage_369_204_204), // '료' -- '료' - FONTDATA_ITEM(370, 244, 244, fontpage_370_244_244), // '르' -- '르' - FONTDATA_ITEM(371, 172, 172, fontpage_371_172_172), // '리' -- '리' - FONTDATA_ITEM(371, 176, 176, fontpage_371_176_176), // '린' -- '린' - FONTDATA_ITEM(371, 189, 189, fontpage_371_189_189), // '립' -- '립' - FONTDATA_ITEM(371, 193, 193, fontpage_371_193_193), // '링' -- '링' - FONTDATA_ITEM(372, 200, 200, fontpage_372_200_200), // '멈' -- '멈' - FONTDATA_ITEM(372, 212, 212, fontpage_372_212_212), // '메' -- '메' - FONTDATA_ITEM(372, 244, 244, fontpage_372_244_244), // '면' -- '면' - FONTDATA_ITEM(373, 168, 168, fontpage_373_168_168), // '모' -- '모' - FONTDATA_ITEM(373, 187, 187, fontpage_373_187_187), // '못' -- '못' - FONTDATA_ITEM(375, 248, 248, fontpage_375_248_248), // '미' -- '미' - FONTDATA_ITEM(376, 128, 128, fontpage_376_128_128), // '밀' -- '밀' - FONTDATA_ITEM(376, 148, 148, fontpage_376_148_148), // '바' -- '바' - FONTDATA_ITEM(377, 132, 132, fontpage_377_132_132), // '버' -- '버' - FONTDATA_ITEM(377, 160, 160, fontpage_377_160_160), // '베' -- '베' - FONTDATA_ITEM(377, 168, 168, fontpage_377_168_168), // '벨' -- '벨' - FONTDATA_ITEM(377, 248, 248, fontpage_377_248_248), // '본' -- '본' - FONTDATA_ITEM(380, 196, 196, fontpage_380_196_196), // '비' -- '비' - FONTDATA_ITEM(385, 172, 172, fontpage_385_172_172), // '사' -- '사' - FONTDATA_ITEM(385, 189, 189, fontpage_385_189_189), // '삽' -- '삽' - FONTDATA_ITEM(385, 200, 200, fontpage_385_200_200), // '새' -- '새' - FONTDATA_ITEM(386, 164, 164, fontpage_386_164_164), // '설' -- '설' - FONTDATA_ITEM(387, 140, 141, fontpage_387_140_141), // '소' -- '속' - FONTDATA_ITEM(389, 164, 164, fontpage_389_164_164), // '스' -- '스' - FONTDATA_ITEM(389, 172, 172, fontpage_389_172_172), // '슬' -- '슬' - FONTDATA_ITEM(389, 220, 221, fontpage_389_220_221), // '시' -- '식' - FONTDATA_ITEM(395, 180, 180, fontpage_395_180_180), // '어' -- '어' - FONTDATA_ITEM(395, 198, 198, fontpage_395_198_198), // '없' -- '없' - FONTDATA_ITEM(395, 209, 209, fontpage_395_209_209), // '엑' -- '엑' - FONTDATA_ITEM(395, 212, 212, fontpage_395_212_212), // '엔' -- '엔' - FONTDATA_ITEM(395, 244, 244, fontpage_395_244_244), // '열' -- '열' - FONTDATA_ITEM(396, 136, 136, fontpage_396_136_136), // '예' -- '예' - FONTDATA_ITEM(396, 164, 164, fontpage_396_164_164), // '오' -- '오' - FONTDATA_ITEM(396, 168, 168, fontpage_396_168_168), // '온' -- '온' - FONTDATA_ITEM(396, 196, 196, fontpage_396_196_196), // '완' -- '완' - FONTDATA_ITEM(397, 208, 208, fontpage_397_208_208), // '원' -- '원' - FONTDATA_ITEM(398, 132, 132, fontpage_398_132_132), // '위' -- '위' - FONTDATA_ITEM(398, 188, 188, fontpage_398_188_188), // '으' -- '으' - FONTDATA_ITEM(398, 204, 204, fontpage_398_204_204), // '음' -- '음' - FONTDATA_ITEM(398, 244, 244, fontpage_398_244_244), // '이' -- '이' - FONTDATA_ITEM(398, 252, 253, fontpage_398_252_253), // '일' -- '읽' - FONTDATA_ITEM(399, 133, 133, fontpage_399_133_133), // '입' -- '입' - FONTDATA_ITEM(399, 144, 145, fontpage_399_144_145), // '자' -- '작' - FONTDATA_ITEM(399, 152, 152, fontpage_399_152_152), // '잘' -- '잘' - FONTDATA_ITEM(399, 165, 165, fontpage_399_165_165), // '장' -- '장' - FONTDATA_ITEM(399, 172, 172, fontpage_399_172_172), // '재' -- '재' - FONTDATA_ITEM(400, 128, 128, fontpage_400_128_128), // '저' -- '저' - FONTDATA_ITEM(400, 132, 132, fontpage_400_132_132), // '전' -- '전' - FONTDATA_ITEM(400, 149, 149, fontpage_400_149_149), // '정' -- '정' - FONTDATA_ITEM(400, 156, 156, fontpage_400_156_156), // '제' -- '제' - FONTDATA_ITEM(401, 253, 253, fontpage_401_253_253), // '죽' -- '죽' - FONTDATA_ITEM(402, 128, 128, fontpage_402_128_128), // '준' -- '준' - FONTDATA_ITEM(402, 145, 145, fontpage_402_145_145), // '중' -- '중' - FONTDATA_ITEM(403, 144, 144, fontpage_403_144_144), // '즐' -- '즐' - FONTDATA_ITEM(403, 192, 192, fontpage_403_192_192), // '지' -- '지' - FONTDATA_ITEM(409, 152, 152, fontpage_409_152_152), // '처' -- '처' - FONTDATA_ITEM(410, 136, 136, fontpage_410_136_136), // '초' -- '초' - FONTDATA_ITEM(411, 149, 149, fontpage_411_149_149), // '축' -- '축' - FONTDATA_ITEM(411, 156, 156, fontpage_411_156_156), // '출' -- '출' - FONTDATA_ITEM(411, 164, 164, fontpage_411_164_164), // '춤' -- '춤' - FONTDATA_ITEM(411, 232, 232, fontpage_411_232_232), // '취' -- '취' - FONTDATA_ITEM(412, 216, 216, fontpage_412_216_216), // '치' -- '치' - FONTDATA_ITEM(412, 232, 232, fontpage_412_232_232), // '침' -- '침' - FONTDATA_ITEM(412, 244, 244, fontpage_412_244_244), // '카' -- '카' - FONTDATA_ITEM(414, 156, 156, fontpage_414_156_156), // '켜' -- '켜' - FONTDATA_ITEM(417, 209, 209, fontpage_417_209_209), // '탑' -- '탑' - FONTDATA_ITEM(418, 176, 176, fontpage_418_176_176), // '터' -- '터' - FONTDATA_ITEM(418, 204, 204, fontpage_418_204_204), // '테' -- '테' - FONTDATA_ITEM(419, 160, 160, fontpage_419_160_160), // '토' -- '토' - FONTDATA_ITEM(421, 184, 184, fontpage_421_184_184), // '트' -- '트' - FONTDATA_ITEM(423, 156, 156, fontpage_423_156_156), // '펜' -- '펜' - FONTDATA_ITEM(426, 132, 132, fontpage_426_132_132), // '프' -- '프' - FONTDATA_ITEM(426, 216, 216, fontpage_426_216_216), // '하' -- '하' - FONTDATA_ITEM(426, 233, 233, fontpage_426_233_233), // '합' -- '합' - FONTDATA_ITEM(428, 200, 200, fontpage_428_200_200), // '홈' -- '홈' - FONTDATA_ITEM(428, 212, 212, fontpage_428_212_212), // '화' -- '화' - FONTDATA_ITEM(431, 136, 136, fontpage_431_136_136), // '히' -- '히' +static const uxg_fontinfo_t g_fontinfo_ko_KR[] PROGMEM = { + FONTDATA_ITEM(344, 240, 240, fontpage_344_240_240), // '거' -- '거' + FONTDATA_ITEM(345, 224, 224, fontpage_345_224_224), // '고' -- '고' + FONTDATA_ITEM(347, 248, 248, fontpage_347_248_248), // '그' -- '그' + FONTDATA_ITEM(348, 137, 137, fontpage_348_137_137), // '급' -- '급' + FONTDATA_ITEM(348, 176, 176, fontpage_348_176_176), // '기' -- '기' + FONTDATA_ITEM(348, 197, 197, fontpage_348_197_197), // '깅' -- '깅' + FONTDATA_ITEM(352, 196, 196, fontpage_352_196_196), // '끄' -- '끄' + FONTDATA_ITEM(353, 180, 180, fontpage_353_180_180), // '내' -- '내' + FONTDATA_ITEM(354, 248, 248, fontpage_354_248_248), // '노' -- '노' + FONTDATA_ITEM(356, 132, 132, fontpage_356_132_132), // '누' -- '누' + FONTDATA_ITEM(356, 244, 244, fontpage_356_244_244), // '뉴' -- '뉴' + FONTDATA_ITEM(357, 200, 200, fontpage_357_200_200), // '니' -- '니' + FONTDATA_ITEM(357, 228, 228, fontpage_357_228_228), // '다' -- '다' + FONTDATA_ITEM(357, 249, 249, fontpage_357_249_249), // '당' -- '당' + FONTDATA_ITEM(359, 196, 196, fontpage_359_196_196), // '도' -- '도' + FONTDATA_ITEM(359, 204, 204, fontpage_359_204_204), // '돌' -- '돌' + FONTDATA_ITEM(359, 217, 217, fontpage_359_217_217), // '동' -- '동' + FONTDATA_ITEM(360, 152, 152, fontpage_360_152_152), // '되' -- '되' + FONTDATA_ITEM(360, 156, 156, fontpage_360_156_156), // '된' -- '된' + FONTDATA_ITEM(360, 168, 168, fontpage_360_168_168), // '됨' -- '됨' + FONTDATA_ITEM(361, 164, 164, fontpage_361_164_164), // '뒤' -- '뒤' + FONTDATA_ITEM(361, 220, 220, fontpage_361_220_220), // '드' -- '드' + FONTDATA_ITEM(362, 148, 148, fontpage_362_148_148), // '디' -- '디' + FONTDATA_ITEM(366, 252, 252, fontpage_366_252_252), // '라' -- '라' + FONTDATA_ITEM(367, 236, 236, fontpage_367_236_236), // '러' -- '러' + FONTDATA_ITEM(368, 136, 136, fontpage_368_136_136), // '레' -- '레' + FONTDATA_ITEM(368, 165, 165, fontpage_368_165_165), // '력' -- '력' + FONTDATA_ITEM(368, 220, 220, fontpage_368_220_220), // '로' -- '로' + FONTDATA_ITEM(369, 204, 204, fontpage_369_204_204), // '료' -- '료' + FONTDATA_ITEM(370, 244, 244, fontpage_370_244_244), // '르' -- '르' + FONTDATA_ITEM(371, 172, 172, fontpage_371_172_172), // '리' -- '리' + FONTDATA_ITEM(371, 176, 176, fontpage_371_176_176), // '린' -- '린' + FONTDATA_ITEM(371, 189, 189, fontpage_371_189_189), // '립' -- '립' + FONTDATA_ITEM(371, 193, 193, fontpage_371_193_193), // '링' -- '링' + FONTDATA_ITEM(372, 200, 200, fontpage_372_200_200), // '멈' -- '멈' + FONTDATA_ITEM(372, 212, 212, fontpage_372_212_212), // '메' -- '메' + FONTDATA_ITEM(372, 244, 244, fontpage_372_244_244), // '면' -- '면' + FONTDATA_ITEM(373, 168, 168, fontpage_373_168_168), // '모' -- '모' + FONTDATA_ITEM(373, 187, 187, fontpage_373_187_187), // '못' -- '못' + FONTDATA_ITEM(375, 248, 248, fontpage_375_248_248), // '미' -- '미' + FONTDATA_ITEM(376, 128, 128, fontpage_376_128_128), // '밀' -- '밀' + FONTDATA_ITEM(376, 148, 148, fontpage_376_148_148), // '바' -- '바' + FONTDATA_ITEM(377, 132, 132, fontpage_377_132_132), // '버' -- '버' + FONTDATA_ITEM(377, 160, 160, fontpage_377_160_160), // '베' -- '베' + FONTDATA_ITEM(377, 168, 168, fontpage_377_168_168), // '벨' -- '벨' + FONTDATA_ITEM(377, 248, 248, fontpage_377_248_248), // '본' -- '본' + FONTDATA_ITEM(380, 196, 196, fontpage_380_196_196), // '비' -- '비' + FONTDATA_ITEM(385, 172, 172, fontpage_385_172_172), // '사' -- '사' + FONTDATA_ITEM(385, 189, 189, fontpage_385_189_189), // '삽' -- '삽' + FONTDATA_ITEM(385, 200, 200, fontpage_385_200_200), // '새' -- '새' + FONTDATA_ITEM(386, 164, 164, fontpage_386_164_164), // '설' -- '설' + FONTDATA_ITEM(387, 140, 141, fontpage_387_140_141), // '소' -- '속' + FONTDATA_ITEM(389, 164, 164, fontpage_389_164_164), // '스' -- '스' + FONTDATA_ITEM(389, 172, 172, fontpage_389_172_172), // '슬' -- '슬' + FONTDATA_ITEM(389, 220, 221, fontpage_389_220_221), // '시' -- '식' + FONTDATA_ITEM(395, 180, 180, fontpage_395_180_180), // '어' -- '어' + FONTDATA_ITEM(395, 198, 198, fontpage_395_198_198), // '없' -- '없' + FONTDATA_ITEM(395, 209, 209, fontpage_395_209_209), // '엑' -- '엑' + FONTDATA_ITEM(395, 212, 212, fontpage_395_212_212), // '엔' -- '엔' + FONTDATA_ITEM(395, 244, 244, fontpage_395_244_244), // '열' -- '열' + FONTDATA_ITEM(396, 136, 136, fontpage_396_136_136), // '예' -- '예' + FONTDATA_ITEM(396, 164, 164, fontpage_396_164_164), // '오' -- '오' + FONTDATA_ITEM(396, 168, 168, fontpage_396_168_168), // '온' -- '온' + FONTDATA_ITEM(396, 196, 196, fontpage_396_196_196), // '완' -- '완' + FONTDATA_ITEM(397, 208, 208, fontpage_397_208_208), // '원' -- '원' + FONTDATA_ITEM(398, 132, 132, fontpage_398_132_132), // '위' -- '위' + FONTDATA_ITEM(398, 188, 188, fontpage_398_188_188), // '으' -- '으' + FONTDATA_ITEM(398, 204, 204, fontpage_398_204_204), // '음' -- '음' + FONTDATA_ITEM(398, 244, 244, fontpage_398_244_244), // '이' -- '이' + FONTDATA_ITEM(398, 252, 253, fontpage_398_252_253), // '일' -- '읽' + FONTDATA_ITEM(399, 133, 133, fontpage_399_133_133), // '입' -- '입' + FONTDATA_ITEM(399, 144, 145, fontpage_399_144_145), // '자' -- '작' + FONTDATA_ITEM(399, 152, 152, fontpage_399_152_152), // '잘' -- '잘' + FONTDATA_ITEM(399, 165, 165, fontpage_399_165_165), // '장' -- '장' + FONTDATA_ITEM(399, 172, 172, fontpage_399_172_172), // '재' -- '재' + FONTDATA_ITEM(400, 128, 128, fontpage_400_128_128), // '저' -- '저' + FONTDATA_ITEM(400, 132, 132, fontpage_400_132_132), // '전' -- '전' + FONTDATA_ITEM(400, 149, 149, fontpage_400_149_149), // '정' -- '정' + FONTDATA_ITEM(400, 156, 156, fontpage_400_156_156), // '제' -- '제' + FONTDATA_ITEM(401, 253, 253, fontpage_401_253_253), // '죽' -- '죽' + FONTDATA_ITEM(402, 128, 128, fontpage_402_128_128), // '준' -- '준' + FONTDATA_ITEM(402, 145, 145, fontpage_402_145_145), // '중' -- '중' + FONTDATA_ITEM(403, 144, 144, fontpage_403_144_144), // '즐' -- '즐' + FONTDATA_ITEM(403, 192, 192, fontpage_403_192_192), // '지' -- '지' + FONTDATA_ITEM(409, 152, 152, fontpage_409_152_152), // '처' -- '처' + FONTDATA_ITEM(410, 136, 136, fontpage_410_136_136), // '초' -- '초' + FONTDATA_ITEM(411, 149, 149, fontpage_411_149_149), // '축' -- '축' + FONTDATA_ITEM(411, 156, 156, fontpage_411_156_156), // '출' -- '출' + FONTDATA_ITEM(411, 164, 164, fontpage_411_164_164), // '춤' -- '춤' + FONTDATA_ITEM(411, 232, 232, fontpage_411_232_232), // '취' -- '취' + FONTDATA_ITEM(412, 216, 216, fontpage_412_216_216), // '치' -- '치' + FONTDATA_ITEM(412, 232, 232, fontpage_412_232_232), // '침' -- '침' + FONTDATA_ITEM(412, 244, 244, fontpage_412_244_244), // '카' -- '카' + FONTDATA_ITEM(414, 156, 156, fontpage_414_156_156), // '켜' -- '켜' + FONTDATA_ITEM(417, 209, 209, fontpage_417_209_209), // '탑' -- '탑' + FONTDATA_ITEM(418, 176, 176, fontpage_418_176_176), // '터' -- '터' + FONTDATA_ITEM(418, 204, 204, fontpage_418_204_204), // '테' -- '테' + FONTDATA_ITEM(419, 160, 160, fontpage_419_160_160), // '토' -- '토' + FONTDATA_ITEM(421, 184, 184, fontpage_421_184_184), // '트' -- '트' + FONTDATA_ITEM(423, 156, 156, fontpage_423_156_156), // '펜' -- '펜' + FONTDATA_ITEM(426, 132, 132, fontpage_426_132_132), // '프' -- '프' + FONTDATA_ITEM(426, 216, 216, fontpage_426_216_216), // '하' -- '하' + FONTDATA_ITEM(426, 233, 233, fontpage_426_233_233), // '합' -- '합' + FONTDATA_ITEM(428, 200, 200, fontpage_428_200_200), // '홈' -- '홈' + FONTDATA_ITEM(428, 212, 212, fontpage_428_212_212), // '화' -- '화' + FONTDATA_ITEM(431, 136, 136, fontpage_431_136_136), // '히' -- '히' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h index 7989690f1f..e76eff3348 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_nl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_nl.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_nl[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h index 11163d9177..e89a6c159a 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pl.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pl.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_132_133[45] U8G_FONT_SECTION("fontpage_2_132_133") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x84,0x85,0x00,0x07,0xFE,0x00, @@ -29,12 +31,11 @@ const u8g_fntpgm_uint8_t fontpage_2_252_252[30] U8G_FONT_SECTION("fontpage_2_252 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xFC,0xFC,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 132, 133, fontpage_2_132_133), // 'Ą' -- 'ą' - FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' - FONTDATA_ITEM(2, 153, 153, fontpage_2_153_153), // 'ę' -- 'ę' - FONTDATA_ITEM(2, 193, 196, fontpage_2_193_196), // 'Ł' -- 'ń' - FONTDATA_ITEM(2, 218, 219, fontpage_2_218_219), // 'Ś' -- 'ś' - FONTDATA_ITEM(2, 252, 252, fontpage_2_252_252), // 'ż' -- 'ż' +static const uxg_fontinfo_t g_fontinfo_pl[] PROGMEM = { + FONTDATA_ITEM(2, 132, 133, fontpage_2_132_133), // 'Ą' -- 'ą' + FONTDATA_ITEM(2, 135, 135, fontpage_2_135_135), // 'ć' -- 'ć' + FONTDATA_ITEM(2, 153, 153, fontpage_2_153_153), // 'ę' -- 'ę' + FONTDATA_ITEM(2, 193, 196, fontpage_2_193_196), // 'Ł' -- 'ń' + FONTDATA_ITEM(2, 218, 219, fontpage_2_218_219), // 'Ś' -- 'ś' + FONTDATA_ITEM(2, 252, 252, fontpage_2_252_252), // 'ż' -- 'ż' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h index 7989690f1f..61f857e587 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_pt[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h index 7989690f1f..b0ed5ad5cf 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_pt_br.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_pt_br[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h index 7989690f1f..6be4863553 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h @@ -3,7 +3,8 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = {}; +#include "langdata.h" + +static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = {}; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h index 617119dde3..3f857a1b3f 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_144_168[348] U8G_FONT_SECTION("fontpage_8_144_168") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x90,0xA8,0x00,0x0A,0xFE,0x00, @@ -64,10 +66,9 @@ const u8g_fntpgm_uint8_t fontpage_8_209_209[30] U8G_FONT_SECTION("fontpage_8_209 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xD1,0xD1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0xF0,0x80,0x70}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 144, 168, fontpage_8_144_168), // 'А' -- 'Ш' - FONTDATA_ITEM(8, 171, 173, fontpage_8_171_173), // 'Ы' -- 'Э' - FONTDATA_ITEM(8, 175, 207, fontpage_8_175_207), // 'Я' -- 'я' - FONTDATA_ITEM(8, 209, 209, fontpage_8_209_209), // 'ё' -- 'ё' +static const uxg_fontinfo_t g_fontinfo_ru[] PROGMEM = { + FONTDATA_ITEM(8, 144, 168, fontpage_8_144_168), // 'А' -- 'Ш' + FONTDATA_ITEM(8, 171, 173, fontpage_8_171_173), // 'Ы' -- 'Э' + FONTDATA_ITEM(8, 175, 207, fontpage_8_175_207), // 'Я' -- 'я' + FONTDATA_ITEM(8, 209, 209, fontpage_8_209_209), // 'ё' -- 'ё' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h index 152d74bbda..4580ce5b7b 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_sk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_sk.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_140_143[79] U8G_FONT_SECTION("fontpage_2_140_143") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x8C,0x8F,0x00,0x0A,0x00,0x00, @@ -37,13 +39,12 @@ const u8g_fntpgm_uint8_t fontpage_2_253_254[47] U8G_FONT_SECTION("fontpage_2_253 0x00,0x05,0x0A,0x0A,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x08,0x10,0x20,0x40,0x80, 0xF8,0x05,0x08,0x08,0x06,0x00,0x00,0x50,0x20,0x00,0xF8,0x10,0x20,0x40,0xF8}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 140, 143, fontpage_2_140_143), // 'Č' -- 'ď' - FONTDATA_ITEM(2, 186, 186, fontpage_2_186_186), // 'ĺ' -- 'ĺ' - FONTDATA_ITEM(2, 189, 190, fontpage_2_189_190), // 'Ľ' -- 'ľ' - FONTDATA_ITEM(2, 199, 200, fontpage_2_199_200), // 'Ň' -- 'ň' - FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' - FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' - FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' +static const uxg_fontinfo_t g_fontinfo_sk[] PROGMEM = { + FONTDATA_ITEM(2, 140, 143, fontpage_2_140_143), // 'Č' -- 'ď' + FONTDATA_ITEM(2, 186, 186, fontpage_2_186_186), // 'ĺ' -- 'ĺ' + FONTDATA_ITEM(2, 189, 190, fontpage_2_189_190), // 'Ľ' -- 'ľ' + FONTDATA_ITEM(2, 199, 200, fontpage_2_199_200), // 'Ň' -- 'ň' + FONTDATA_ITEM(2, 224, 225, fontpage_2_224_225), // 'Š' -- 'š' + FONTDATA_ITEM(2, 229, 229, fontpage_2_229_229), // 'ť' -- 'ť' + FONTDATA_ITEM(2, 253, 254, fontpage_2_253_254), // 'Ž' -- 'ž' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_test.h b/Marlin/src/lcd/dogm/fontdata/langdata_test.h index ca6e369eb1..da76a31041 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_test.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_test.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_128_255[1677] U8G_FONT_SECTION("fontpage_8_128_255") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x80,0xFF,0x00,0x0A,0xFE,0x00, @@ -223,9 +225,8 @@ const u8g_fntpgm_uint8_t fontpage_97_193_255[822] U8G_FONT_SECTION("fontpage_97_ 0x06,0x00,0x02,0x28,0x28,0x00,0x80,0x60,0x10,0x08,0x05,0x06,0x06,0x06,0x00,0x00, 0xF8,0x08,0x08,0x08,0x08,0x08}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 128, 255, fontpage_8_128_255), // 'Ѐ' -- 'ѿ' - FONTDATA_ITEM(97, 129, 191, fontpage_97_129_191), // 'め' -- 'タ' - FONTDATA_ITEM(97, 193, 255, fontpage_97_193_255), // 'チ' -- 'ヿ' +static const uxg_fontinfo_t g_fontinfo_test[] PROGMEM = { + FONTDATA_ITEM(8, 128, 255, fontpage_8_128_255), // 'Ѐ' -- 'ѿ' + FONTDATA_ITEM(97, 129, 191, fontpage_97_129_191), // 'め' -- 'タ' + FONTDATA_ITEM(97, 193, 255, fontpage_97_193_255), // 'チ' -- 'ヿ' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h index aeb1124cf2..0ac02435a5 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_tr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_tr.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_158_159[49] U8G_FONT_SECTION("fontpage_2_158_159") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9E,0x9F,0x00,0x0A,0xFE,0x00, @@ -19,9 +21,8 @@ const u8g_fntpgm_uint8_t fontpage_2_222_223[45] U8G_FONT_SECTION("fontpage_2_222 0x00,0x05,0x09,0x09,0x06,0x00,0xFE,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x10,0x60, 0x05,0x07,0x07,0x06,0x00,0xFE,0x78,0x80,0x70,0x08,0xF0,0x10,0x60}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 158, 159, fontpage_2_158_159), // 'Ğ' -- 'ğ' - FONTDATA_ITEM(2, 176, 177, fontpage_2_176_177), // 'İ' -- 'ı' - FONTDATA_ITEM(2, 222, 223, fontpage_2_222_223), // 'Ş' -- 'ş' +static const uxg_fontinfo_t g_fontinfo_tr[] PROGMEM = { + FONTDATA_ITEM(2, 158, 159, fontpage_2_158_159), // 'Ğ' -- 'ğ' + FONTDATA_ITEM(2, 176, 177, fontpage_2_176_177), // 'İ' -- 'ı' + FONTDATA_ITEM(2, 222, 223, fontpage_2_222_223), // 'Ş' -- 'ş' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h index fe409d4e3c..b25e2f6db4 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_8_134_134[30] U8G_FONT_SECTION("fontpage_8_134_134") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, @@ -72,14 +74,13 @@ const u8g_fntpgm_uint8_t fontpage_8_214_215[41] U8G_FONT_SECTION("fontpage_8_214 0x00,0x03,0x06,0x06,0x06,0x01,0x00,0x40,0x00,0xC0,0x40,0x40,0xE0,0x03,0x06,0x06, 0x06,0x01,0x00,0xA0,0x00,0xC0,0x40,0x40,0xE0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 134, 134, fontpage_8_134_134), // 'І' -- 'І' - FONTDATA_ITEM(8, 144, 169, fontpage_8_144_169), // 'А' -- 'Щ' - FONTDATA_ITEM(8, 172, 172, fontpage_8_172_172), // 'Ь' -- 'Ь' - FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' - FONTDATA_ITEM(8, 204, 204, fontpage_8_204_204), // 'ь' -- 'ь' - FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' - FONTDATA_ITEM(8, 212, 212, fontpage_8_212_212), // 'є' -- 'є' - FONTDATA_ITEM(8, 214, 215, fontpage_8_214_215), // 'і' -- 'ї' +static const uxg_fontinfo_t g_fontinfo_uk[] PROGMEM = { + FONTDATA_ITEM(8, 134, 134, fontpage_8_134_134), // 'І' -- 'І' + FONTDATA_ITEM(8, 144, 169, fontpage_8_144_169), // 'А' -- 'Щ' + FONTDATA_ITEM(8, 172, 172, fontpage_8_172_172), // 'Ь' -- 'Ь' + FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' + FONTDATA_ITEM(8, 204, 204, fontpage_8_204_204), // 'ь' -- 'ь' + FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' + FONTDATA_ITEM(8, 212, 212, fontpage_8_212_212), // 'є' -- 'є' + FONTDATA_ITEM(8, 214, 215, fontpage_8_214_215), // 'і' -- 'ї' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h index 998ae44af1..303c4c66d6 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_vi.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_vi.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_2_131_131[31] U8G_FONT_SECTION("fontpage_2_131_131") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, @@ -177,51 +179,50 @@ const u8g_fntpgm_uint8_t fontpage_61_241_241[32] U8G_FONT_SECTION("fontpage_61_2 0x00,0x06,0x09,0x09,0x07,0x00,0xFE,0x0C,0x04,0x88,0x88,0x88,0x88,0x70,0x00,0x20 }; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' - FONTDATA_ITEM(2, 144, 145, fontpage_2_144_145), // 'Đ' -- 'đ' - FONTDATA_ITEM(2, 169, 169, fontpage_2_169_169), // 'ĩ' -- 'ĩ' - FONTDATA_ITEM(3, 161, 161, fontpage_3_161_161), // 'ơ' -- 'ơ' - FONTDATA_ITEM(3, 175, 176, fontpage_3_175_176), // 'Ư' -- 'ư' - FONTDATA_ITEM(6, 131, 131, fontpage_6_131_131), // '̃' -- '̃' - FONTDATA_ITEM(6, 137, 137, fontpage_6_137_137), // '̉' -- '̉' - FONTDATA_ITEM(6, 163, 163, fontpage_6_163_163), // '̣' -- '̣' - FONTDATA_ITEM(6, 192, 193, fontpage_6_192_193), // '̀' -- '́' - FONTDATA_ITEM(61, 161, 161, fontpage_61_161_161), // 'ạ' -- 'ạ' - FONTDATA_ITEM(61, 163, 163, fontpage_61_163_163), // 'ả' -- 'ả' - FONTDATA_ITEM(61, 165, 165, fontpage_61_165_165), // 'ấ' -- 'ấ' - FONTDATA_ITEM(61, 167, 167, fontpage_61_167_167), // 'ầ' -- 'ầ' - FONTDATA_ITEM(61, 169, 169, fontpage_61_169_169), // 'ẩ' -- 'ẩ' - FONTDATA_ITEM(61, 173, 173, fontpage_61_173_173), // 'ậ' -- 'ậ' - FONTDATA_ITEM(61, 175, 175, fontpage_61_175_175), // 'ắ' -- 'ắ' - FONTDATA_ITEM(61, 177, 177, fontpage_61_177_177), // 'ằ' -- 'ằ' - FONTDATA_ITEM(61, 179, 179, fontpage_61_179_179), // 'ẳ' -- 'ẳ' - FONTDATA_ITEM(61, 181, 181, fontpage_61_181_181), // 'ẵ' -- 'ẵ' - FONTDATA_ITEM(61, 183, 183, fontpage_61_183_183), // 'ặ' -- 'ặ' - FONTDATA_ITEM(61, 191, 191, fontpage_61_191_191), // 'ế' -- 'ế' - FONTDATA_ITEM(61, 193, 193, fontpage_61_193_193), // 'ề' -- 'ề' - FONTDATA_ITEM(61, 195, 195, fontpage_61_195_195), // 'ể' -- 'ể' - FONTDATA_ITEM(61, 199, 199, fontpage_61_199_199), // 'ệ' -- 'ệ' - FONTDATA_ITEM(61, 201, 201, fontpage_61_201_201), // 'ỉ' -- 'ỉ' - FONTDATA_ITEM(61, 203, 203, fontpage_61_203_203), // 'ị' -- 'ị' - FONTDATA_ITEM(61, 205, 205, fontpage_61_205_205), // 'ọ' -- 'ọ' - FONTDATA_ITEM(61, 207, 207, fontpage_61_207_207), // 'ỏ' -- 'ỏ' - FONTDATA_ITEM(61, 209, 209, fontpage_61_209_209), // 'ố' -- 'ố' - FONTDATA_ITEM(61, 211, 211, fontpage_61_211_211), // 'ồ' -- 'ồ' - FONTDATA_ITEM(61, 213, 213, fontpage_61_213_213), // 'ổ' -- 'ổ' - FONTDATA_ITEM(61, 215, 215, fontpage_61_215_215), // 'ỗ' -- 'ỗ' - FONTDATA_ITEM(61, 217, 217, fontpage_61_217_217), // 'ộ' -- 'ộ' - FONTDATA_ITEM(61, 219, 219, fontpage_61_219_219), // 'ớ' -- 'ớ' - FONTDATA_ITEM(61, 221, 221, fontpage_61_221_221), // 'ờ' -- 'ờ' - FONTDATA_ITEM(61, 223, 223, fontpage_61_223_223), // 'ở' -- 'ở' - FONTDATA_ITEM(61, 225, 225, fontpage_61_225_225), // 'ỡ' -- 'ỡ' - FONTDATA_ITEM(61, 227, 227, fontpage_61_227_227), // 'ợ' -- 'ợ' - FONTDATA_ITEM(61, 229, 229, fontpage_61_229_229), // 'ụ' -- 'ụ' - FONTDATA_ITEM(61, 231, 231, fontpage_61_231_231), // 'ủ' -- 'ủ' - FONTDATA_ITEM(61, 233, 233, fontpage_61_233_233), // 'ứ' -- 'ứ' - FONTDATA_ITEM(61, 235, 235, fontpage_61_235_235), // 'ừ' -- 'ừ' - FONTDATA_ITEM(61, 237, 237, fontpage_61_237_237), // 'ử' -- 'ử' - FONTDATA_ITEM(61, 239, 239, fontpage_61_239_239), // 'ữ' -- 'ữ' - FONTDATA_ITEM(61, 241, 241, fontpage_61_241_241), // 'ự' -- 'ự' +static const uxg_fontinfo_t g_fontinfo_vi[] PROGMEM = { + FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' + FONTDATA_ITEM(2, 144, 145, fontpage_2_144_145), // 'Đ' -- 'đ' + FONTDATA_ITEM(2, 169, 169, fontpage_2_169_169), // 'ĩ' -- 'ĩ' + FONTDATA_ITEM(3, 161, 161, fontpage_3_161_161), // 'ơ' -- 'ơ' + FONTDATA_ITEM(3, 175, 176, fontpage_3_175_176), // 'Ư' -- 'ư' + FONTDATA_ITEM(6, 131, 131, fontpage_6_131_131), // '̃' -- '̃' + FONTDATA_ITEM(6, 137, 137, fontpage_6_137_137), // '̉' -- '̉' + FONTDATA_ITEM(6, 163, 163, fontpage_6_163_163), // '̣' -- '̣' + FONTDATA_ITEM(6, 192, 193, fontpage_6_192_193), // '̀' -- '́' + FONTDATA_ITEM(61, 161, 161, fontpage_61_161_161), // 'ạ' -- 'ạ' + FONTDATA_ITEM(61, 163, 163, fontpage_61_163_163), // 'ả' -- 'ả' + FONTDATA_ITEM(61, 165, 165, fontpage_61_165_165), // 'ấ' -- 'ấ' + FONTDATA_ITEM(61, 167, 167, fontpage_61_167_167), // 'ầ' -- 'ầ' + FONTDATA_ITEM(61, 169, 169, fontpage_61_169_169), // 'ẩ' -- 'ẩ' + FONTDATA_ITEM(61, 173, 173, fontpage_61_173_173), // 'ậ' -- 'ậ' + FONTDATA_ITEM(61, 175, 175, fontpage_61_175_175), // 'ắ' -- 'ắ' + FONTDATA_ITEM(61, 177, 177, fontpage_61_177_177), // 'ằ' -- 'ằ' + FONTDATA_ITEM(61, 179, 179, fontpage_61_179_179), // 'ẳ' -- 'ẳ' + FONTDATA_ITEM(61, 181, 181, fontpage_61_181_181), // 'ẵ' -- 'ẵ' + FONTDATA_ITEM(61, 183, 183, fontpage_61_183_183), // 'ặ' -- 'ặ' + FONTDATA_ITEM(61, 191, 191, fontpage_61_191_191), // 'ế' -- 'ế' + FONTDATA_ITEM(61, 193, 193, fontpage_61_193_193), // 'ề' -- 'ề' + FONTDATA_ITEM(61, 195, 195, fontpage_61_195_195), // 'ể' -- 'ể' + FONTDATA_ITEM(61, 199, 199, fontpage_61_199_199), // 'ệ' -- 'ệ' + FONTDATA_ITEM(61, 201, 201, fontpage_61_201_201), // 'ỉ' -- 'ỉ' + FONTDATA_ITEM(61, 203, 203, fontpage_61_203_203), // 'ị' -- 'ị' + FONTDATA_ITEM(61, 205, 205, fontpage_61_205_205), // 'ọ' -- 'ọ' + FONTDATA_ITEM(61, 207, 207, fontpage_61_207_207), // 'ỏ' -- 'ỏ' + FONTDATA_ITEM(61, 209, 209, fontpage_61_209_209), // 'ố' -- 'ố' + FONTDATA_ITEM(61, 211, 211, fontpage_61_211_211), // 'ồ' -- 'ồ' + FONTDATA_ITEM(61, 213, 213, fontpage_61_213_213), // 'ổ' -- 'ổ' + FONTDATA_ITEM(61, 215, 215, fontpage_61_215_215), // 'ỗ' -- 'ỗ' + FONTDATA_ITEM(61, 217, 217, fontpage_61_217_217), // 'ộ' -- 'ộ' + FONTDATA_ITEM(61, 219, 219, fontpage_61_219_219), // 'ớ' -- 'ớ' + FONTDATA_ITEM(61, 221, 221, fontpage_61_221_221), // 'ờ' -- 'ờ' + FONTDATA_ITEM(61, 223, 223, fontpage_61_223_223), // 'ở' -- 'ở' + FONTDATA_ITEM(61, 225, 225, fontpage_61_225_225), // 'ỡ' -- 'ỡ' + FONTDATA_ITEM(61, 227, 227, fontpage_61_227_227), // 'ợ' -- 'ợ' + FONTDATA_ITEM(61, 229, 229, fontpage_61_229_229), // 'ụ' -- 'ụ' + FONTDATA_ITEM(61, 231, 231, fontpage_61_231_231), // 'ủ' -- 'ủ' + FONTDATA_ITEM(61, 233, 233, fontpage_61_233_233), // 'ứ' -- 'ứ' + FONTDATA_ITEM(61, 235, 235, fontpage_61_235_235), // 'ừ' -- 'ừ' + FONTDATA_ITEM(61, 237, 237, fontpage_61_237_237), // 'ử' -- 'ử' + FONTDATA_ITEM(61, 239, 239, fontpage_61_239_239), // 'ữ' -- 'ữ' + FONTDATA_ITEM(61, 241, 241, fontpage_61_241_241), // 'ự' -- 'ự' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h index 8d74ba4414..664fa5f4bf 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9D,0x9D,0x00,0x07,0x00,0x00, @@ -1462,362 +1464,361 @@ const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9A,0x9A,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0C,0x06,0x01,0xC0,0xC0,0x00,0x00,0x00,0xC0,0xC0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' - FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' - FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' - FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' - FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' - FONTDATA_ITEM(156, 147, 147, fontpage_156_147_147), // '专' -- '专' - FONTDATA_ITEM(156, 157, 157, fontpage_156_157_157), // '丝' -- '丝' - FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' - FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' - FONTDATA_ITEM(156, 186, 187, fontpage_156_186_187), // '为' -- '主' - FONTDATA_ITEM(156, 201, 201, fontpage_156_201_201), // '义' -- '义' - FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' - FONTDATA_ITEM(157, 134, 134, fontpage_157_134_134), // '了' -- '了' - FONTDATA_ITEM(157, 140, 140, fontpage_157_140_140), // '二' -- '二' - FONTDATA_ITEM(157, 142, 142, fontpage_157_142_142), // '于' -- '于' - FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' - FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' - FONTDATA_ITEM(157, 206, 206, fontpage_157_206_206), // '从' -- '从' - FONTDATA_ITEM(157, 228, 229, fontpage_157_228_229), // '令' -- '以' - FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' - FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' - FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' - FONTDATA_ITEM(158, 160, 160, fontpage_158_160_160), // '传' -- '传' - FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' - FONTDATA_ITEM(158, 211, 211, fontpage_158_211_211), // '体' -- '体' - FONTDATA_ITEM(158, 217, 217, fontpage_158_217_217), // '余' -- '余' - FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' - FONTDATA_ITEM(158, 255, 255, fontpage_158_255_255), // '使' -- '使' - FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' - FONTDATA_ITEM(159, 181, 181, fontpage_159_181_181), // '侵' -- '侵' - FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' - FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' - FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' - FONTDATA_ITEM(160, 190, 190, fontpage_160_190_190), // '倾' -- '倾' - FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' - FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' - FONTDATA_ITEM(161, 168, 168, fontpage_161_168_168), // '储' -- '储' - FONTDATA_ITEM(161, 207, 207, fontpage_161_207_207), // '像' -- '像' - FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' - FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' - FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' - FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' - FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' - FONTDATA_ITEM(162, 243, 243, fontpage_162_243_243), // '关' -- '关' - FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' - FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' - FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' - FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' - FONTDATA_ITEM(163, 250, 251, fontpage_163_250_251), // '出' -- '击' - FONTDATA_ITEM(164, 134, 135, fontpage_164_134_135), // '分' -- '切' - FONTDATA_ITEM(164, 155, 155, fontpage_164_155_155), // '创' -- '创' - FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' - FONTDATA_ITEM(164, 171, 171, fontpage_164_171_171), // '别' -- '别' - FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' - FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' - FONTDATA_ITEM(164, 242, 242, fontpage_164_242_242), // '割' -- '割' - FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' - FONTDATA_ITEM(165, 159, 160, fontpage_165_159_160), // '功' -- '加' - FONTDATA_ITEM(165, 168, 168, fontpage_165_168_168), // '动' -- '动' - FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' - FONTDATA_ITEM(166, 199, 199, fontpage_166_199_199), // '升' -- '升' - FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' - FONTDATA_ITEM(166, 207, 207, fontpage_166_207_207), // '协' -- '协' - FONTDATA_ITEM(166, 213, 213, fontpage_166_213_213), // '单' -- '单' - FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' - FONTDATA_ITEM(166, 240, 241, fontpage_166_240_241), // '印' -- '危' - FONTDATA_ITEM(166, 244, 244, fontpage_166_244_244), // '却' -- '却' - FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' - FONTDATA_ITEM(167, 139, 139, fontpage_167_139_139), // '压' -- '压' - FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' - FONTDATA_ITEM(167, 204, 205, fontpage_167_204_205), // '双' -- '反' - FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' - FONTDATA_ITEM(167, 216, 216, fontpage_167_216_216), // '变' -- '变' - FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' - FONTDATA_ITEM(168, 131, 131, fontpage_168_131_131), // '吃' -- '吃' - FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' - FONTDATA_ITEM(168, 141, 142, fontpage_168_141_142), // '名' -- '后' - FONTDATA_ITEM(168, 145, 145, fontpage_168_145_145), // '向' -- '向' - FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' - FONTDATA_ITEM(168, 175, 175, fontpage_168_175_175), // '启' -- '启' - FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' - FONTDATA_ITEM(168, 232, 232, fontpage_168_232_232), // '周' -- '周' - FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' - FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' - FONTDATA_ITEM(169, 205, 205, fontpage_169_205_205), // '响' -- '响' - FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' - FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' - FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' - FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' - FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' - FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' - FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' - FONTDATA_ITEM(173, 254, 254, fontpage_173_254_254), // '图' -- '图' - FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' - FONTDATA_ITEM(174, 207, 207, fontpage_174_207_207), // '坏' -- '坏' - FONTDATA_ITEM(174, 215, 215, fontpage_174_215_215), // '块' -- '块' - FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' - FONTDATA_ITEM(175, 171, 171, fontpage_175_171_171), // '垫' -- '垫' - FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' - FONTDATA_ITEM(177, 243, 243, fontpage_177_243_243), // '壳' -- '壳' - FONTDATA_ITEM(178, 135, 135, fontpage_178_135_135), // '备' -- '备' - FONTDATA_ITEM(178, 141, 141, fontpage_178_141_141), // '复' -- '复' - FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' - FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' - FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' - FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' - FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' - FONTDATA_ITEM(178, 180, 180, fontpage_178_180_180), // '头' -- '头' - FONTDATA_ITEM(178, 253, 253, fontpage_178_253_253), // '好' -- '好' - FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' - FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' - FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' - FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' - FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' - FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' - FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' - FONTDATA_ITEM(183, 171, 171, fontpage_183_171_171), // '宫' -- '宫' - FONTDATA_ITEM(183, 249, 249, fontpage_183_249_249), // '对' -- '对' - FONTDATA_ITEM(184, 134, 134, fontpage_184_134_134), // '将' -- '将' - FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' - FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' - FONTDATA_ITEM(184, 207, 207, fontpage_184_207_207), // '屏' -- '屏' - FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' - FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' - FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' - FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' - FONTDATA_ITEM(188, 246, 246, fontpage_188_246_246), // '并' -- '并' - FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' - FONTDATA_ITEM(189, 148, 148, fontpage_189_148_148), // '应' -- '应' - FONTDATA_ITEM(189, 159, 159, fontpage_189_159_159), // '废' -- '废' - FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' - FONTDATA_ITEM(190, 128, 128, fontpage_190_128_128), // '开' -- '开' - FONTDATA_ITEM(190, 131, 131, fontpage_190_131_131), // '弃' -- '弃' - FONTDATA_ITEM(190, 143, 143, fontpage_190_143_143), // '式' -- '式' - FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' - FONTDATA_ITEM(190, 185, 185, fontpage_190_185_185), // '弹' -- '弹' - FONTDATA_ITEM(190, 210, 210, fontpage_190_210_210), // '归' -- '归' - FONTDATA_ITEM(191, 132, 133, fontpage_191_132_133), // '径' -- '待' - FONTDATA_ITEM(191, 170, 170, fontpage_191_170_170), // '循' -- '循' - FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' - FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' - FONTDATA_ITEM(191, 253, 253, fontpage_191_253_253), // '忽' -- '忽' - FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' - FONTDATA_ITEM(192, 187, 187, fontpage_192_187_187), // '总' -- '总' - FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' - FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' - FONTDATA_ITEM(194, 159, 159, fontpage_194_159_159), // '感' -- '感' - FONTDATA_ITEM(196, 143, 144, fontpage_196_143_144), // '戏' -- '成' - FONTDATA_ITEM(196, 183, 183, fontpage_196_183_183), // '户' -- '户' - FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' - FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' - FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' - FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' - FONTDATA_ITEM(196, 231, 231, fontpage_196_231_231), // '执' -- '执' - FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' - FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' - FONTDATA_ITEM(197, 165, 165, fontpage_197_165_165), // '报' -- '报' - FONTDATA_ITEM(197, 172, 172, fontpage_197_172_172), // '抬' -- '抬' - FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' - FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' - FONTDATA_ITEM(197, 233, 233, fontpage_197_233_233), // '择' -- '择' - FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' - FONTDATA_ITEM(198, 161, 161, fontpage_198_161_161), // '挡' -- '挡' - FONTDATA_ITEM(198, 164, 164, fontpage_198_164_164), // '挤' -- '挤' - FONTDATA_ITEM(198, 223, 223, fontpage_198_223_223), // '损' -- '损' - FONTDATA_ITEM(198, 226, 226, fontpage_198_226_226), // '换' -- '换' - FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' - FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' - FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' - FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' - FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' - FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' - FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' - FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' - FONTDATA_ITEM(202, 240, 240, fontpage_202_240_240), // '数' -- '数' - FONTDATA_ITEM(202, 242, 242, fontpage_202_242_242), // '敲' -- '敲' - FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' - FONTDATA_ITEM(203, 135, 135, fontpage_203_135_135), // '文' -- '文' - FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' - FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' - FONTDATA_ITEM(203, 173, 173, fontpage_203_173_173), // '断' -- '断' - FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' - FONTDATA_ITEM(203, 185, 185, fontpage_203_185_185), // '方' -- '方' - FONTDATA_ITEM(203, 224, 224, fontpage_203_224_224), // '无' -- '无' - FONTDATA_ITEM(203, 246, 246, fontpage_203_246_246), // '时' -- '时' - FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' - FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' - FONTDATA_ITEM(205, 130, 130, fontpage_205_130_130), // '暂' -- '暂' - FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' - FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' - FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' - FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' - FONTDATA_ITEM(206, 159, 159, fontpage_206_159_159), // '期' -- '期' - FONTDATA_ITEM(206, 186, 186, fontpage_206_186_186), // '机' -- '机' - FONTDATA_ITEM(206, 192, 192, fontpage_206_192_192), // '杀' -- '杀' - FONTDATA_ITEM(206, 223, 223, fontpage_206_223_223), // '束' -- '束' - FONTDATA_ITEM(206, 225, 225, fontpage_206_225_225), // '条' -- '条' - FONTDATA_ITEM(206, 229, 229, fontpage_206_229_229), // '来' -- '来' - FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' - FONTDATA_ITEM(207, 151, 151, fontpage_207_151_151), // '林' -- '林' - FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' - FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' - FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' - FONTDATA_ITEM(209, 175, 175, fontpage_209_175_175), // '梯' -- '梯' - FONTDATA_ITEM(209, 192, 192, fontpage_209_192_192), // '检' -- '检' - FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' - FONTDATA_ITEM(212, 161, 161, fontpage_212_161_161), // '模' -- '模' - FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' - FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' - FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' - FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' - FONTDATA_ITEM(217, 161, 161, fontpage_217_161_161), // '没' -- '没' - FONTDATA_ITEM(217, 226, 226, fontpage_217_226_226), // '波' -- '波' - FONTDATA_ITEM(217, 232, 232, fontpage_217_232_232), // '注' -- '注' - FONTDATA_ITEM(218, 151, 151, fontpage_218_151_151), // '洗' -- '洗' - FONTDATA_ITEM(218, 187, 187, fontpage_218_187_187), // '活' -- '活' - FONTDATA_ITEM(218, 193, 193, fontpage_218_193_193), // '流' -- '流' - FONTDATA_ITEM(218, 203, 203, fontpage_218_203_203), // '测' -- '测' - FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' - FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' - FONTDATA_ITEM(219, 247, 247, fontpage_219_247_247), // '混' -- '混' - FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' - FONTDATA_ITEM(220, 169, 169, fontpage_220_169_169), // '温' -- '温' - FONTDATA_ITEM(220, 184, 184, fontpage_220_184_184), // '游' -- '游' - FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' - FONTDATA_ITEM(221, 162, 162, fontpage_221_162_162), // '溢' -- '溢' - FONTDATA_ITEM(221, 209, 209, fontpage_221_209_209), // '滑' -- '滑' - FONTDATA_ITEM(222, 143, 143, fontpage_222_143_143), // '漏' -- '漏' - FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' - FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' - FONTDATA_ITEM(225, 185, 185, fontpage_225_185_185), // '点' -- '点' - FONTDATA_ITEM(225, 237, 237, fontpage_225_237_237), // '热' -- '热' - FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' - FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' - FONTDATA_ITEM(228, 249, 249, fontpage_228_249_249), // '特' -- '特' - FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' - FONTDATA_ITEM(231, 175, 175, fontpage_231_175_175), // '环' -- '环' - FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' - FONTDATA_ITEM(234, 181, 181, fontpage_234_181_181), // '电' -- '电' - FONTDATA_ITEM(234, 229, 229, fontpage_234_229_229), // '略' -- '略' - FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' - FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' - FONTDATA_ITEM(237, 209, 209, fontpage_237_209_209), // '监' -- '监' - FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' - FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' - FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' - FONTDATA_ITEM(240, 238, 238, fontpage_240_238_238), // '确' -- '确' - FONTDATA_ITEM(243, 187, 187, fontpage_243_187_187), // '离' -- '离' - FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' - FONTDATA_ITEM(244, 250, 250, fontpage_244_250_250), // '空' -- '空' - FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' - FONTDATA_ITEM(246, 172, 172, fontpage_246_172_172), // '第' -- '第' - FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' - FONTDATA_ITEM(247, 128, 128, fontpage_247_128_128), // '简' -- '简' - FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' - FONTDATA_ITEM(248, 251, 251, fontpage_248_251_251), // '类' -- '类' - FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' - FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' - FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' - FONTDATA_ITEM(253, 167, 167, fontpage_253_167_167), // '级' -- '级' - FONTDATA_ITEM(253, 191, 191, fontpage_253_191_191), // '线' -- '线' - FONTDATA_ITEM(253, 198, 198, fontpage_253_198_198), // '细' -- '细' - FONTDATA_ITEM(253, 200, 200, fontpage_253_200_200), // '终' -- '终' - FONTDATA_ITEM(253, 211, 211, fontpage_253_211_211), // '结' -- '结' - FONTDATA_ITEM(253, 217, 217, fontpage_253_217_217), // '给' -- '给' - FONTDATA_ITEM(253, 223, 223, fontpage_253_223_223), // '统' -- '统' - FONTDATA_ITEM(253, 231, 231, fontpage_253_231_231), // '继' -- '继' - FONTDATA_ITEM(253, 234, 234, fontpage_253_234_234), // '绪' -- '绪' - FONTDATA_ITEM(253, 237, 237, fontpage_253_237_237), // '续' -- '续' - FONTDATA_ITEM(253, 255, 255, fontpage_253_255_255), // '绿' -- '绿' - FONTDATA_ITEM(254, 150, 150, fontpage_254_150_150), // '编' -- '编' - FONTDATA_ITEM(254, 186, 186, fontpage_254_186_186), // '缺' -- '缺' - FONTDATA_ITEM(254, 209, 209, fontpage_254_209_209), // '网' -- '网' - FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' - FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' - FONTDATA_ITEM(256, 133, 133, fontpage_256_133_133), // '者' -- '者' - FONTDATA_ITEM(256, 234, 234, fontpage_256_234_234), // '聪' -- '聪' - FONTDATA_ITEM(257, 253, 253, fontpage_257_253_253), // '能' -- '能' - FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' - FONTDATA_ITEM(259, 243, 243, fontpage_259_243_243), // '至' -- '至' - FONTDATA_ITEM(263, 220, 220, fontpage_263_220_220), // '菜' -- '菜' - FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' - FONTDATA_ITEM(269, 199, 199, fontpage_269_199_199), // '蛇' -- '蛇' - FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' - FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' - FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' - FONTDATA_ITEM(275, 129, 129, fontpage_275_129_129), // '要' -- '要' - FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' - FONTDATA_ITEM(279, 161, 161, fontpage_279_161_161), // '计' -- '计' - FONTDATA_ITEM(279, 174, 174, fontpage_279_174_174), // '议' -- '议' - FONTDATA_ITEM(279, 190, 190, fontpage_279_190_190), // '设' -- '设' - FONTDATA_ITEM(279, 213, 213, fontpage_279_213_213), // '试' -- '试' - FONTDATA_ITEM(279, 239, 239, fontpage_279_239_239), // '误' -- '误' - FONTDATA_ITEM(279, 247, 247, fontpage_279_247_247), // '请' -- '请' - FONTDATA_ITEM(279, 251, 251, fontpage_279_251_251), // '读' -- '读' - FONTDATA_ITEM(280, 131, 131, fontpage_280_131_131), // '调' -- '调' - FONTDATA_ITEM(282, 165, 165, fontpage_282_165_165), // '败' -- '败' - FONTDATA_ITEM(282, 170, 170, fontpage_282_170_170), // '贪' -- '贪' - FONTDATA_ITEM(282, 247, 247, fontpage_282_247_247), // '起' -- '起' - FONTDATA_ITEM(283, 133, 133, fontpage_283_133_133), // '超' -- '超' - FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' - FONTDATA_ITEM(286, 236, 236, fontpage_286_236_236), // '转' -- '转' - FONTDATA_ITEM(286, 239, 239, fontpage_286_239_239), // '软' -- '软' - FONTDATA_ITEM(286, 244, 244, fontpage_286_244_244), // '轴' -- '轴' - FONTDATA_ITEM(286, 253, 253, fontpage_286_253_253), // '载' -- '载' - FONTDATA_ITEM(287, 145, 145, fontpage_287_145_145), // '辑' -- '辑' - FONTDATA_ITEM(287, 147, 147, fontpage_287_147_147), // '输' -- '输' - FONTDATA_ITEM(287, 185, 185, fontpage_287_185_185), // '边' -- '边' - FONTDATA_ITEM(287, 193, 193, fontpage_287_193_193), // '迁' -- '迁' - FONTDATA_ITEM(287, 208, 209, fontpage_287_208_209), // '运' -- '近' - FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' - FONTDATA_ITEM(287, 216, 216, fontpage_287_216_216), // '还' -- '还' - FONTDATA_ITEM(287, 219, 219, fontpage_287_219_219), // '进' -- '进' - FONTDATA_ITEM(287, 222, 222, fontpage_287_222_222), // '连' -- '连' - FONTDATA_ITEM(287, 247, 247, fontpage_287_247_247), // '迷' -- '迷' - FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' - FONTDATA_ITEM(288, 137, 137, fontpage_288_137_137), // '选' -- '选' - FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' - FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' - FONTDATA_ITEM(290, 205, 205, fontpage_290_205_205), // '配' -- '配' - FONTDATA_ITEM(291, 202, 202, fontpage_291_202_202), // '释' -- '释' - FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' - FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' - FONTDATA_ITEM(297, 136, 136, fontpage_297_136_136), // '针' -- '针' - FONTDATA_ITEM(297, 174, 174, fontpage_297_174_174), // '钮' -- '钮' - FONTDATA_ITEM(298, 153, 153, fontpage_298_153_153), // '错' -- '错' - FONTDATA_ITEM(298, 220, 220, fontpage_298_220_220), // '镜' -- '镜' - FONTDATA_ITEM(298, 255, 255, fontpage_298_255_255), // '长' -- '长' - FONTDATA_ITEM(299, 237, 237, fontpage_299_237_237), // '闭' -- '闭' - FONTDATA_ITEM(299, 242, 242, fontpage_299_242_242), // '闲' -- '闲' - FONTDATA_ITEM(299, 244, 244, fontpage_299_244_244), // '间' -- '间' - FONTDATA_ITEM(300, 136, 136, fontpage_300_136_136), // '阈' -- '阈' - FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' - FONTDATA_ITEM(300, 208, 208, fontpage_300_208_208), // '限' -- '限' - FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' - FONTDATA_ITEM(300, 233, 233, fontpage_300_233_233), // '险' -- '险' - FONTDATA_ITEM(301, 246, 246, fontpage_301_246_246), // '零' -- '零' - FONTDATA_ITEM(302, 128, 128, fontpage_302_128_128), // '需' -- '需' - FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' - FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' - FONTDATA_ITEM(302, 224, 224, fontpage_302_224_224), // '靠' -- '靠' - FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' - FONTDATA_ITEM(304, 245, 245, fontpage_304_245_245), // '页' -- '页' - FONTDATA_ITEM(304, 249, 249, fontpage_304_249_249), // '项' -- '项' - FONTDATA_ITEM(305, 132, 132, fontpage_305_132_132), // '预' -- '预' - FONTDATA_ITEM(305, 145, 145, fontpage_305_145_145), // '频' -- '频' - FONTDATA_ITEM(305, 157, 157, fontpage_305_157_157), // '额' -- '额' - FONTDATA_ITEM(305, 206, 206, fontpage_305_206_206), // '风' -- '风' - FONTDATA_ITEM(306, 241, 241, fontpage_306_241_241), // '饱' -- '饱' - FONTDATA_ITEM(308, 236, 236, fontpage_308_236_236), // '马' -- '马' - FONTDATA_ITEM(308, 241, 241, fontpage_308_241_241), // '驱' -- '驱' - FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' - FONTDATA_ITEM(317, 196, 196, fontpage_317_196_196), // '黄' -- '黄' - FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' - FONTDATA_ITEM(318, 208, 208, fontpage_318_208_208), // '齐' -- '齐' - FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' +static const uxg_fontinfo_t g_fontinfo_zh_CN[] PROGMEM = { + FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' + FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' + FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' + FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' + FONTDATA_ITEM(156, 147, 147, fontpage_156_147_147), // '专' -- '专' + FONTDATA_ITEM(156, 157, 157, fontpage_156_157_157), // '丝' -- '丝' + FONTDATA_ITEM(156, 170, 170, fontpage_156_170_170), // '个' -- '个' + FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' + FONTDATA_ITEM(156, 186, 187, fontpage_156_186_187), // '为' -- '主' + FONTDATA_ITEM(156, 201, 201, fontpage_156_201_201), // '义' -- '义' + FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' + FONTDATA_ITEM(157, 134, 134, fontpage_157_134_134), // '了' -- '了' + FONTDATA_ITEM(157, 140, 140, fontpage_157_140_140), // '二' -- '二' + FONTDATA_ITEM(157, 142, 142, fontpage_157_142_142), // '于' -- '于' + FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' + FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' + FONTDATA_ITEM(157, 206, 206, fontpage_157_206_206), // '从' -- '从' + FONTDATA_ITEM(157, 228, 229, fontpage_157_228_229), // '令' -- '以' + FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' + FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' + FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' + FONTDATA_ITEM(158, 160, 160, fontpage_158_160_160), // '传' -- '传' + FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' + FONTDATA_ITEM(158, 211, 211, fontpage_158_211_211), // '体' -- '体' + FONTDATA_ITEM(158, 217, 217, fontpage_158_217_217), // '余' -- '余' + FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' + FONTDATA_ITEM(158, 255, 255, fontpage_158_255_255), // '使' -- '使' + FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' + FONTDATA_ITEM(159, 181, 181, fontpage_159_181_181), // '侵' -- '侵' + FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' + FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' + FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' + FONTDATA_ITEM(160, 190, 190, fontpage_160_190_190), // '倾' -- '倾' + FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' + FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' + FONTDATA_ITEM(161, 168, 168, fontpage_161_168_168), // '储' -- '储' + FONTDATA_ITEM(161, 207, 207, fontpage_161_207_207), // '像' -- '像' + FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' + FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' + FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' + FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' + FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' + FONTDATA_ITEM(162, 243, 243, fontpage_162_243_243), // '关' -- '关' + FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' + FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' + FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' + FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' + FONTDATA_ITEM(163, 250, 251, fontpage_163_250_251), // '出' -- '击' + FONTDATA_ITEM(164, 134, 135, fontpage_164_134_135), // '分' -- '切' + FONTDATA_ITEM(164, 155, 155, fontpage_164_155_155), // '创' -- '创' + FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' + FONTDATA_ITEM(164, 171, 171, fontpage_164_171_171), // '别' -- '别' + FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' + FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' + FONTDATA_ITEM(164, 242, 242, fontpage_164_242_242), // '割' -- '割' + FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' + FONTDATA_ITEM(165, 159, 160, fontpage_165_159_160), // '功' -- '加' + FONTDATA_ITEM(165, 168, 168, fontpage_165_168_168), // '动' -- '动' + FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' + FONTDATA_ITEM(166, 199, 199, fontpage_166_199_199), // '升' -- '升' + FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' + FONTDATA_ITEM(166, 207, 207, fontpage_166_207_207), // '协' -- '协' + FONTDATA_ITEM(166, 213, 213, fontpage_166_213_213), // '单' -- '单' + FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' + FONTDATA_ITEM(166, 240, 241, fontpage_166_240_241), // '印' -- '危' + FONTDATA_ITEM(166, 244, 244, fontpage_166_244_244), // '却' -- '却' + FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' + FONTDATA_ITEM(167, 139, 139, fontpage_167_139_139), // '压' -- '压' + FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' + FONTDATA_ITEM(167, 204, 205, fontpage_167_204_205), // '双' -- '反' + FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' + FONTDATA_ITEM(167, 216, 216, fontpage_167_216_216), // '变' -- '变' + FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' + FONTDATA_ITEM(168, 131, 131, fontpage_168_131_131), // '吃' -- '吃' + FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' + FONTDATA_ITEM(168, 141, 142, fontpage_168_141_142), // '名' -- '后' + FONTDATA_ITEM(168, 145, 145, fontpage_168_145_145), // '向' -- '向' + FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' + FONTDATA_ITEM(168, 175, 175, fontpage_168_175_175), // '启' -- '启' + FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' + FONTDATA_ITEM(168, 232, 232, fontpage_168_232_232), // '周' -- '周' + FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' + FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' + FONTDATA_ITEM(169, 205, 205, fontpage_169_205_205), // '响' -- '响' + FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' + FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' + FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' + FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' + FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' + FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' + FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' + FONTDATA_ITEM(173, 254, 254, fontpage_173_254_254), // '图' -- '图' + FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' + FONTDATA_ITEM(174, 207, 207, fontpage_174_207_207), // '坏' -- '坏' + FONTDATA_ITEM(174, 215, 215, fontpage_174_215_215), // '块' -- '块' + FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' + FONTDATA_ITEM(175, 171, 171, fontpage_175_171_171), // '垫' -- '垫' + FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' + FONTDATA_ITEM(177, 243, 243, fontpage_177_243_243), // '壳' -- '壳' + FONTDATA_ITEM(178, 135, 135, fontpage_178_135_135), // '备' -- '备' + FONTDATA_ITEM(178, 141, 141, fontpage_178_141_141), // '复' -- '复' + FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' + FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' + FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' + FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' + FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' + FONTDATA_ITEM(178, 180, 180, fontpage_178_180_180), // '头' -- '头' + FONTDATA_ITEM(178, 253, 253, fontpage_178_253_253), // '好' -- '好' + FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' + FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' + FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' + FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' + FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' + FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' + FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' + FONTDATA_ITEM(183, 171, 171, fontpage_183_171_171), // '宫' -- '宫' + FONTDATA_ITEM(183, 249, 249, fontpage_183_249_249), // '对' -- '对' + FONTDATA_ITEM(184, 134, 134, fontpage_184_134_134), // '将' -- '将' + FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' + FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' + FONTDATA_ITEM(184, 207, 207, fontpage_184_207_207), // '屏' -- '屏' + FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' + FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' + FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' + FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' + FONTDATA_ITEM(188, 246, 246, fontpage_188_246_246), // '并' -- '并' + FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' + FONTDATA_ITEM(189, 148, 148, fontpage_189_148_148), // '应' -- '应' + FONTDATA_ITEM(189, 159, 159, fontpage_189_159_159), // '废' -- '废' + FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' + FONTDATA_ITEM(190, 128, 128, fontpage_190_128_128), // '开' -- '开' + FONTDATA_ITEM(190, 131, 131, fontpage_190_131_131), // '弃' -- '弃' + FONTDATA_ITEM(190, 143, 143, fontpage_190_143_143), // '式' -- '式' + FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' + FONTDATA_ITEM(190, 185, 185, fontpage_190_185_185), // '弹' -- '弹' + FONTDATA_ITEM(190, 210, 210, fontpage_190_210_210), // '归' -- '归' + FONTDATA_ITEM(191, 132, 133, fontpage_191_132_133), // '径' -- '待' + FONTDATA_ITEM(191, 170, 170, fontpage_191_170_170), // '循' -- '循' + FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' + FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' + FONTDATA_ITEM(191, 253, 253, fontpage_191_253_253), // '忽' -- '忽' + FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' + FONTDATA_ITEM(192, 187, 187, fontpage_192_187_187), // '总' -- '总' + FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' + FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' + FONTDATA_ITEM(194, 159, 159, fontpage_194_159_159), // '感' -- '感' + FONTDATA_ITEM(196, 143, 144, fontpage_196_143_144), // '戏' -- '成' + FONTDATA_ITEM(196, 183, 183, fontpage_196_183_183), // '户' -- '户' + FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' + FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' + FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' + FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' + FONTDATA_ITEM(196, 231, 231, fontpage_196_231_231), // '执' -- '执' + FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' + FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' + FONTDATA_ITEM(197, 165, 165, fontpage_197_165_165), // '报' -- '报' + FONTDATA_ITEM(197, 172, 172, fontpage_197_172_172), // '抬' -- '抬' + FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' + FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' + FONTDATA_ITEM(197, 233, 233, fontpage_197_233_233), // '择' -- '择' + FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' + FONTDATA_ITEM(198, 161, 161, fontpage_198_161_161), // '挡' -- '挡' + FONTDATA_ITEM(198, 164, 164, fontpage_198_164_164), // '挤' -- '挤' + FONTDATA_ITEM(198, 223, 223, fontpage_198_223_223), // '损' -- '损' + FONTDATA_ITEM(198, 226, 226, fontpage_198_226_226), // '换' -- '换' + FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' + FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' + FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' + FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' + FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' + FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' + FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' + FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' + FONTDATA_ITEM(202, 240, 240, fontpage_202_240_240), // '数' -- '数' + FONTDATA_ITEM(202, 242, 242, fontpage_202_242_242), // '敲' -- '敲' + FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' + FONTDATA_ITEM(203, 135, 135, fontpage_203_135_135), // '文' -- '文' + FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' + FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' + FONTDATA_ITEM(203, 173, 173, fontpage_203_173_173), // '断' -- '断' + FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' + FONTDATA_ITEM(203, 185, 185, fontpage_203_185_185), // '方' -- '方' + FONTDATA_ITEM(203, 224, 224, fontpage_203_224_224), // '无' -- '无' + FONTDATA_ITEM(203, 246, 246, fontpage_203_246_246), // '时' -- '时' + FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' + FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' + FONTDATA_ITEM(205, 130, 130, fontpage_205_130_130), // '暂' -- '暂' + FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' + FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' + FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' + FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' + FONTDATA_ITEM(206, 159, 159, fontpage_206_159_159), // '期' -- '期' + FONTDATA_ITEM(206, 186, 186, fontpage_206_186_186), // '机' -- '机' + FONTDATA_ITEM(206, 192, 192, fontpage_206_192_192), // '杀' -- '杀' + FONTDATA_ITEM(206, 223, 223, fontpage_206_223_223), // '束' -- '束' + FONTDATA_ITEM(206, 225, 225, fontpage_206_225_225), // '条' -- '条' + FONTDATA_ITEM(206, 229, 229, fontpage_206_229_229), // '来' -- '来' + FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' + FONTDATA_ITEM(207, 151, 151, fontpage_207_151_151), // '林' -- '林' + FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' + FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' + FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' + FONTDATA_ITEM(209, 175, 175, fontpage_209_175_175), // '梯' -- '梯' + FONTDATA_ITEM(209, 192, 192, fontpage_209_192_192), // '检' -- '检' + FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' + FONTDATA_ITEM(212, 161, 161, fontpage_212_161_161), // '模' -- '模' + FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' + FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' + FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' + FONTDATA_ITEM(217, 161, 161, fontpage_217_161_161), // '没' -- '没' + FONTDATA_ITEM(217, 226, 226, fontpage_217_226_226), // '波' -- '波' + FONTDATA_ITEM(217, 232, 232, fontpage_217_232_232), // '注' -- '注' + FONTDATA_ITEM(218, 151, 151, fontpage_218_151_151), // '洗' -- '洗' + FONTDATA_ITEM(218, 187, 187, fontpage_218_187_187), // '活' -- '活' + FONTDATA_ITEM(218, 193, 193, fontpage_218_193_193), // '流' -- '流' + FONTDATA_ITEM(218, 203, 203, fontpage_218_203_203), // '测' -- '测' + FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' + FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' + FONTDATA_ITEM(219, 247, 247, fontpage_219_247_247), // '混' -- '混' + FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' + FONTDATA_ITEM(220, 169, 169, fontpage_220_169_169), // '温' -- '温' + FONTDATA_ITEM(220, 184, 184, fontpage_220_184_184), // '游' -- '游' + FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' + FONTDATA_ITEM(221, 162, 162, fontpage_221_162_162), // '溢' -- '溢' + FONTDATA_ITEM(221, 209, 209, fontpage_221_209_209), // '滑' -- '滑' + FONTDATA_ITEM(222, 143, 143, fontpage_222_143_143), // '漏' -- '漏' + FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' + FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' + FONTDATA_ITEM(225, 185, 185, fontpage_225_185_185), // '点' -- '点' + FONTDATA_ITEM(225, 237, 237, fontpage_225_237_237), // '热' -- '热' + FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' + FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' + FONTDATA_ITEM(228, 249, 249, fontpage_228_249_249), // '特' -- '特' + FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' + FONTDATA_ITEM(231, 175, 175, fontpage_231_175_175), // '环' -- '环' + FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' + FONTDATA_ITEM(234, 181, 181, fontpage_234_181_181), // '电' -- '电' + FONTDATA_ITEM(234, 229, 229, fontpage_234_229_229), // '略' -- '略' + FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' + FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' + FONTDATA_ITEM(237, 209, 209, fontpage_237_209_209), // '监' -- '监' + FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' + FONTDATA_ITEM(238, 129, 129, fontpage_238_129_129), // '省' -- '省' + FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' + FONTDATA_ITEM(240, 238, 238, fontpage_240_238_238), // '确' -- '确' + FONTDATA_ITEM(243, 187, 187, fontpage_243_187_187), // '离' -- '离' + FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' + FONTDATA_ITEM(244, 250, 250, fontpage_244_250_250), // '空' -- '空' + FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' + FONTDATA_ITEM(246, 172, 172, fontpage_246_172_172), // '第' -- '第' + FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' + FONTDATA_ITEM(247, 128, 128, fontpage_247_128_128), // '简' -- '简' + FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' + FONTDATA_ITEM(248, 251, 251, fontpage_248_251_251), // '类' -- '类' + FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' + FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' + FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' + FONTDATA_ITEM(253, 167, 167, fontpage_253_167_167), // '级' -- '级' + FONTDATA_ITEM(253, 191, 191, fontpage_253_191_191), // '线' -- '线' + FONTDATA_ITEM(253, 198, 198, fontpage_253_198_198), // '细' -- '细' + FONTDATA_ITEM(253, 200, 200, fontpage_253_200_200), // '终' -- '终' + FONTDATA_ITEM(253, 211, 211, fontpage_253_211_211), // '结' -- '结' + FONTDATA_ITEM(253, 217, 217, fontpage_253_217_217), // '给' -- '给' + FONTDATA_ITEM(253, 223, 223, fontpage_253_223_223), // '统' -- '统' + FONTDATA_ITEM(253, 231, 231, fontpage_253_231_231), // '继' -- '继' + FONTDATA_ITEM(253, 234, 234, fontpage_253_234_234), // '绪' -- '绪' + FONTDATA_ITEM(253, 237, 237, fontpage_253_237_237), // '续' -- '续' + FONTDATA_ITEM(253, 255, 255, fontpage_253_255_255), // '绿' -- '绿' + FONTDATA_ITEM(254, 150, 150, fontpage_254_150_150), // '编' -- '编' + FONTDATA_ITEM(254, 186, 186, fontpage_254_186_186), // '缺' -- '缺' + FONTDATA_ITEM(254, 209, 209, fontpage_254_209_209), // '网' -- '网' + FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' + FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' + FONTDATA_ITEM(256, 133, 133, fontpage_256_133_133), // '者' -- '者' + FONTDATA_ITEM(256, 234, 234, fontpage_256_234_234), // '聪' -- '聪' + FONTDATA_ITEM(257, 253, 253, fontpage_257_253_253), // '能' -- '能' + FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' + FONTDATA_ITEM(259, 243, 243, fontpage_259_243_243), // '至' -- '至' + FONTDATA_ITEM(263, 220, 220, fontpage_263_220_220), // '菜' -- '菜' + FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' + FONTDATA_ITEM(269, 199, 199, fontpage_269_199_199), // '蛇' -- '蛇' + FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' + FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' + FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' + FONTDATA_ITEM(275, 129, 129, fontpage_275_129_129), // '要' -- '要' + FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' + FONTDATA_ITEM(279, 161, 161, fontpage_279_161_161), // '计' -- '计' + FONTDATA_ITEM(279, 174, 174, fontpage_279_174_174), // '议' -- '议' + FONTDATA_ITEM(279, 190, 190, fontpage_279_190_190), // '设' -- '设' + FONTDATA_ITEM(279, 213, 213, fontpage_279_213_213), // '试' -- '试' + FONTDATA_ITEM(279, 239, 239, fontpage_279_239_239), // '误' -- '误' + FONTDATA_ITEM(279, 247, 247, fontpage_279_247_247), // '请' -- '请' + FONTDATA_ITEM(279, 251, 251, fontpage_279_251_251), // '读' -- '读' + FONTDATA_ITEM(280, 131, 131, fontpage_280_131_131), // '调' -- '调' + FONTDATA_ITEM(282, 165, 165, fontpage_282_165_165), // '败' -- '败' + FONTDATA_ITEM(282, 170, 170, fontpage_282_170_170), // '贪' -- '贪' + FONTDATA_ITEM(282, 247, 247, fontpage_282_247_247), // '起' -- '起' + FONTDATA_ITEM(283, 133, 133, fontpage_283_133_133), // '超' -- '超' + FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' + FONTDATA_ITEM(286, 236, 236, fontpage_286_236_236), // '转' -- '转' + FONTDATA_ITEM(286, 239, 239, fontpage_286_239_239), // '软' -- '软' + FONTDATA_ITEM(286, 244, 244, fontpage_286_244_244), // '轴' -- '轴' + FONTDATA_ITEM(286, 253, 253, fontpage_286_253_253), // '载' -- '载' + FONTDATA_ITEM(287, 145, 145, fontpage_287_145_145), // '辑' -- '辑' + FONTDATA_ITEM(287, 147, 147, fontpage_287_147_147), // '输' -- '输' + FONTDATA_ITEM(287, 185, 185, fontpage_287_185_185), // '边' -- '边' + FONTDATA_ITEM(287, 193, 193, fontpage_287_193_193), // '迁' -- '迁' + FONTDATA_ITEM(287, 208, 209, fontpage_287_208_209), // '运' -- '近' + FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' + FONTDATA_ITEM(287, 216, 216, fontpage_287_216_216), // '还' -- '还' + FONTDATA_ITEM(287, 219, 219, fontpage_287_219_219), // '进' -- '进' + FONTDATA_ITEM(287, 222, 222, fontpage_287_222_222), // '连' -- '连' + FONTDATA_ITEM(287, 247, 247, fontpage_287_247_247), // '迷' -- '迷' + FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' + FONTDATA_ITEM(288, 137, 137, fontpage_288_137_137), // '选' -- '选' + FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' + FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' + FONTDATA_ITEM(290, 205, 205, fontpage_290_205_205), // '配' -- '配' + FONTDATA_ITEM(291, 202, 202, fontpage_291_202_202), // '释' -- '释' + FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' + FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' + FONTDATA_ITEM(297, 136, 136, fontpage_297_136_136), // '针' -- '针' + FONTDATA_ITEM(297, 174, 174, fontpage_297_174_174), // '钮' -- '钮' + FONTDATA_ITEM(298, 153, 153, fontpage_298_153_153), // '错' -- '错' + FONTDATA_ITEM(298, 220, 220, fontpage_298_220_220), // '镜' -- '镜' + FONTDATA_ITEM(298, 255, 255, fontpage_298_255_255), // '长' -- '长' + FONTDATA_ITEM(299, 237, 237, fontpage_299_237_237), // '闭' -- '闭' + FONTDATA_ITEM(299, 242, 242, fontpage_299_242_242), // '闲' -- '闲' + FONTDATA_ITEM(299, 244, 244, fontpage_299_244_244), // '间' -- '间' + FONTDATA_ITEM(300, 136, 136, fontpage_300_136_136), // '阈' -- '阈' + FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' + FONTDATA_ITEM(300, 208, 208, fontpage_300_208_208), // '限' -- '限' + FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' + FONTDATA_ITEM(300, 233, 233, fontpage_300_233_233), // '险' -- '险' + FONTDATA_ITEM(301, 246, 246, fontpage_301_246_246), // '零' -- '零' + FONTDATA_ITEM(302, 128, 128, fontpage_302_128_128), // '需' -- '需' + FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' + FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' + FONTDATA_ITEM(302, 224, 224, fontpage_302_224_224), // '靠' -- '靠' + FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' + FONTDATA_ITEM(304, 245, 245, fontpage_304_245_245), // '页' -- '页' + FONTDATA_ITEM(304, 249, 249, fontpage_304_249_249), // '项' -- '项' + FONTDATA_ITEM(305, 132, 132, fontpage_305_132_132), // '预' -- '预' + FONTDATA_ITEM(305, 145, 145, fontpage_305_145_145), // '频' -- '频' + FONTDATA_ITEM(305, 157, 157, fontpage_305_157_157), // '额' -- '额' + FONTDATA_ITEM(305, 206, 206, fontpage_305_206_206), // '风' -- '风' + FONTDATA_ITEM(306, 241, 241, fontpage_306_241_241), // '饱' -- '饱' + FONTDATA_ITEM(308, 236, 236, fontpage_308_236_236), // '马' -- '马' + FONTDATA_ITEM(308, 241, 241, fontpage_308_241_241), // '驱' -- '驱' + FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' + FONTDATA_ITEM(317, 196, 196, fontpage_317_196_196), // '黄' -- '黄' + FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' + FONTDATA_ITEM(318, 208, 208, fontpage_318_208_208), // '齐' -- '齐' + FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h index 51344936be..093629cd16 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_TW.h @@ -3,7 +3,9 @@ * Contents will be REPLACED by future processing! * Use genallfont.sh to generate font data for updated languages. */ -#include +#pragma once + +#include "langdata.h" const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xBF,0xBF,0x00,0x05,0x00,0x00, @@ -1217,305 +1219,304 @@ const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x9A,0x9A,0x00,0x08,0x00,0x00, 0x00,0x02,0x07,0x07,0x0C,0x06,0x01,0xC0,0xC0,0x00,0x00,0x00,0xC0,0xC0}; -#define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } -static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' - FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' - FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' - FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' - FONTDATA_ITEM(156, 166, 166, fontpage_156_166_166), // '並' -- '並' - FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' - FONTDATA_ITEM(156, 187, 187, fontpage_156_187_187), // '主' -- '主' - FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' - FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' - FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' - FONTDATA_ITEM(157, 228, 228, fontpage_157_228_228), // '令' -- '令' - FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' - FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' - FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' - FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' - FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' - FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' - FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' - FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' - FONTDATA_ITEM(160, 139, 139, fontpage_160_139_139), // '個' -- '個' - FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' - FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' - FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' - FONTDATA_ITEM(160, 245, 245, fontpage_160_245_245), // '偵' -- '偵' - FONTDATA_ITEM(161, 153, 153, fontpage_161_153_153), // '備' -- '備' - FONTDATA_ITEM(161, 179, 179, fontpage_161_179_179), // '傳' -- '傳' - FONTDATA_ITEM(161, 190, 190, fontpage_161_190_190), // '傾' -- '傾' - FONTDATA_ITEM(162, 178, 178, fontpage_162_178_178), // '儲' -- '儲' - FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' - FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' - FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' - FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' - FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' - FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' - FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' - FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' - FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' - FONTDATA_ITEM(163, 250, 250, fontpage_163_250_250), // '出' -- '出' - FONTDATA_ITEM(164, 134, 134, fontpage_164_134_134), // '分' -- '分' - FONTDATA_ITEM(164, 151, 151, fontpage_164_151_151), // '列' -- '列' - FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' - FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' - FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' - FONTDATA_ITEM(164, 245, 245, fontpage_164_245_245), // '創' -- '創' - FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' - FONTDATA_ITEM(165, 160, 160, fontpage_165_160_160), // '加' -- '加' - FONTDATA_ITEM(165, 213, 213, fontpage_165_213_213), // '動' -- '動' - FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' - FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' - FONTDATA_ITEM(166, 212, 212, fontpage_166_212_212), // '協' -- '協' - FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' - FONTDATA_ITEM(166, 240, 240, fontpage_166_240_240), // '印' -- '印' - FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' - FONTDATA_ITEM(166, 251, 251, fontpage_166_251_251), // '卻' -- '卻' - FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' - FONTDATA_ITEM(167, 205, 205, fontpage_167_205_205), // '反' -- '反' - FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' - FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' - FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' - FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' - FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' - FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' - FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' - FONTDATA_ITEM(170, 223, 223, fontpage_170_223_223), // '啟' -- '啟' - FONTDATA_ITEM(171, 174, 174, fontpage_171_174_174), // '單' -- '單' - FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' - FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' - FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' - FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' - FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' - FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' - FONTDATA_ITEM(174, 150, 150, fontpage_174_150_150), // '圖' -- '圖' - FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' - FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' - FONTDATA_ITEM(175, 247, 247, fontpage_175_247_247), // '執' -- '執' - FONTDATA_ITEM(176, 202, 202, fontpage_176_202_202), // '塊' -- '塊' - FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' - FONTDATA_ITEM(177, 138, 138, fontpage_177_138_138), // '墊' -- '墊' - FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' - FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' - FONTDATA_ITEM(178, 160, 160, fontpage_178_160_160), // '夠' -- '夠' - FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' - FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' - FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' - FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' - FONTDATA_ITEM(181, 146, 146, fontpage_181_146_146), // '媒' -- '媒' - FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' - FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' - FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' - FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' - FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' - FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' - FONTDATA_ITEM(183, 185, 185, fontpage_183_185_185), // '容' -- '容' - FONTDATA_ITEM(184, 141, 141, fontpage_184_141_141), // '對' -- '對' - FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' - FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' - FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' - FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' - FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' - FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' - FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' - FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' - FONTDATA_ITEM(189, 226, 226, fontpage_189_226_226), // '廢' -- '廢' - FONTDATA_ITEM(189, 250, 250, fontpage_189_250_250), // '建' -- '建' - FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' - FONTDATA_ITEM(191, 133, 133, fontpage_191_133_133), // '待' -- '待' - FONTDATA_ITEM(191, 140, 140, fontpage_191_140_140), // '後' -- '後' - FONTDATA_ITEM(191, 145, 145, fontpage_191_145_145), // '徑' -- '徑' - FONTDATA_ITEM(191, 158, 158, fontpage_191_158_158), // '從' -- '從' - FONTDATA_ITEM(191, 169, 169, fontpage_191_169_169), // '復' -- '復' - FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' - FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' - FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' - FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' - FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' - FONTDATA_ITEM(195, 182, 182, fontpage_195_182_182), // '憶' -- '憶' - FONTDATA_ITEM(195, 201, 201, fontpage_195_201_201), // '應' -- '應' - FONTDATA_ITEM(196, 144, 144, fontpage_196_144_144), // '成' -- '成' - FONTDATA_ITEM(196, 182, 182, fontpage_196_182_182), // '戶' -- '戶' - FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' - FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' - FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' - FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' - FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' - FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' - FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' - FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' - FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' - FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' - FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' - FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' - FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' - FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' - FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' - FONTDATA_ITEM(199, 219, 219, fontpage_199_219_219), // '換' -- '換' - FONTDATA_ITEM(201, 199, 199, fontpage_201_199_199), // '擇' -- '擇' - FONTDATA_ITEM(201, 202, 203, fontpage_201_202_203), // '擊' -- '擋' - FONTDATA_ITEM(201, 224, 224, fontpage_201_224_224), // '擠' -- '擠' - FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' - FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' - FONTDATA_ITEM(202, 215, 215, fontpage_202_215_215), // '敗' -- '敗' - FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' - FONTDATA_ITEM(202, 248, 248, fontpage_202_248_248), // '數' -- '數' - FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' - FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' - FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' - FONTDATA_ITEM(203, 183, 183, fontpage_203_183_183), // '斷' -- '斷' - FONTDATA_ITEM(203, 188, 188, fontpage_203_188_188), // '於' -- '於' - FONTDATA_ITEM(204, 135, 135, fontpage_204_135_135), // '昇' -- '昇' - FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' - FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' - FONTDATA_ITEM(204, 194, 194, fontpage_204_194_194), // '時' -- '時' - FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' - FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' - FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' - FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' - FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' - FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' - FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' - FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' - FONTDATA_ITEM(209, 157, 157, fontpage_209_157_157), // '條' -- '條' - FONTDATA_ITEM(209, 196, 196, fontpage_209_196_196), // '棄' -- '棄' - FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' - FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' - FONTDATA_ITEM(212, 223, 223, fontpage_212_223_223), // '機' -- '機' - FONTDATA_ITEM(213, 162, 162, fontpage_213_162_162), // '檢' -- '檢' - FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' - FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' - FONTDATA_ITEM(214, 248, 248, fontpage_214_248_248), // '歸' -- '歸' - FONTDATA_ITEM(215, 188, 188, fontpage_215_188_188), // '殼' -- '殼' - FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' - FONTDATA_ITEM(217, 146, 146, fontpage_217_146_146), // '沒' -- '沒' - FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' - FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' - FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' - FONTDATA_ITEM(220, 172, 172, fontpage_220_172_172), // '測' -- '測' - FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' - FONTDATA_ITEM(221, 150, 150, fontpage_221_150_150), // '準' -- '準' - FONTDATA_ITEM(221, 171, 171, fontpage_221_171_171), // '溫' -- '溫' - FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' - FONTDATA_ITEM(226, 161, 161, fontpage_226_161_161), // '無' -- '無' - FONTDATA_ITEM(227, 177, 177, fontpage_227_177_177), // '熱' -- '熱' - FONTDATA_ITEM(227, 200, 200, fontpage_227_200_200), // '燈' -- '燈' - FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' - FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' - FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' - FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' - FONTDATA_ITEM(234, 204, 204, fontpage_234_204_204), // '界' -- '界' - FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' - FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' - FONTDATA_ITEM(237, 227, 227, fontpage_237_227_227), // '監' -- '監' - FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' - FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' - FONTDATA_ITEM(240, 141, 141, fontpage_240_141_141), // '砍' -- '砍' - FONTDATA_ITEM(241, 186, 186, fontpage_241_186_186), // '確' -- '確' - FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' - FONTDATA_ITEM(244, 205, 205, fontpage_244_205_205), // '積' -- '積' - FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' - FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' - FONTDATA_ITEM(247, 161, 161, fontpage_247_161_161), // '管' -- '管' - FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' - FONTDATA_ITEM(249, 251, 251, fontpage_249_251_251), // '系' -- '系' - FONTDATA_ITEM(250, 133, 133, fontpage_250_133_133), // '紅' -- '紅' - FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' - FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' - FONTDATA_ITEM(250, 176, 176, fontpage_250_176_176), // '細' -- '細' - FONTDATA_ITEM(250, 194, 194, fontpage_250_194_194), // '終' -- '終' - FONTDATA_ITEM(250, 241, 242, fontpage_250_241_242), // '統' -- '絲' - FONTDATA_ITEM(251, 160, 160, fontpage_251_160_160), // '綠' -- '綠' - FONTDATA_ITEM(251, 178, 178, fontpage_251_178_178), // '網' -- '網' - FONTDATA_ITEM(251, 210, 210, fontpage_251_210_210), // '緒' -- '緒' - FONTDATA_ITEM(251, 218, 218, fontpage_251_218_218), // '線' -- '線' - FONTDATA_ITEM(251, 232, 232, fontpage_251_232_232), // '編' -- '編' - FONTDATA_ITEM(252, 174, 174, fontpage_252_174_174), // '縮' -- '縮' - FONTDATA_ITEM(252, 189, 189, fontpage_252_189_189), // '總' -- '總' - FONTDATA_ITEM(252, 252, 252, fontpage_252_252_252), // '繼' -- '繼' - FONTDATA_ITEM(253, 140, 140, fontpage_253_140_140), // '續' -- '續' - FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' - FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' - FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' - FONTDATA_ITEM(256, 240, 240, fontpage_256_240_240), // '聰' -- '聰' - FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' - FONTDATA_ITEM(267, 205, 205, fontpage_267_205_205), // '藍' -- '藍' - FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' - FONTDATA_ITEM(272, 232, 232, fontpage_272_232_232), // '表' -- '表' - FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' - FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' - FONTDATA_ITEM(273, 221, 221, fontpage_273_221_221), // '裝' -- '裝' - FONTDATA_ITEM(274, 135, 135, fontpage_274_135_135), // '複' -- '複' - FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' - FONTDATA_ITEM(276, 136, 136, fontpage_276_136_136), // '計' -- '計' - FONTDATA_ITEM(276, 138, 138, fontpage_276_138_138), // '訊' -- '訊' - FONTDATA_ITEM(276, 152, 152, fontpage_276_152_152), // '記' -- '記' - FONTDATA_ITEM(276, 173, 173, fontpage_276_173_173), // '設' -- '設' - FONTDATA_ITEM(276, 230, 230, fontpage_276_230_230), // '試' -- '試' - FONTDATA_ITEM(277, 141, 141, fontpage_277_141_141), // '認' -- '認' - FONTDATA_ITEM(277, 164, 164, fontpage_277_164_164), // '誤' -- '誤' - FONTDATA_ITEM(277, 191, 191, fontpage_277_191_191), // '調' -- '調' - FONTDATA_ITEM(277, 203, 203, fontpage_277_203_203), // '請' -- '請' - FONTDATA_ITEM(278, 240, 240, fontpage_278_240_240), // '議' -- '議' - FONTDATA_ITEM(279, 128, 128, fontpage_279_128_128), // '讀' -- '讀' - FONTDATA_ITEM(279, 138, 138, fontpage_279_138_138), // '變' -- '變' - FONTDATA_ITEM(281, 199, 199, fontpage_281_199_199), // '資' -- '資' - FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' - FONTDATA_ITEM(285, 202, 202, fontpage_285_202_202), // '車' -- '車' - FONTDATA_ITEM(285, 223, 223, fontpage_285_223_223), // '軟' -- '軟' - FONTDATA_ITEM(285, 248, 248, fontpage_285_248_248), // '軸' -- '軸' - FONTDATA_ITEM(286, 137, 137, fontpage_286_137_137), // '載' -- '載' - FONTDATA_ITEM(286, 175, 175, fontpage_286_175_175), // '輯' -- '輯' - FONTDATA_ITEM(286, 184, 184, fontpage_286_184_184), // '輸' -- '輸' - FONTDATA_ITEM(286, 201, 201, fontpage_286_201_201), // '轉' -- '轉' - FONTDATA_ITEM(287, 209, 209, fontpage_287_209_209), // '近' -- '近' - FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' - FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' - FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' - FONTDATA_ITEM(288, 163, 163, fontpage_288_163_163), // '連' -- '連' - FONTDATA_ITEM(288, 178, 178, fontpage_288_178_178), // '進' -- '進' - FONTDATA_ITEM(288, 203, 203, fontpage_288_203_203), // '運' -- '運' - FONTDATA_ITEM(288, 212, 212, fontpage_288_212_212), // '達' -- '達' - FONTDATA_ITEM(288, 248, 248, fontpage_288_248_248), // '選' -- '選' - FONTDATA_ITEM(289, 132, 132, fontpage_289_132_132), // '還' -- '還' - FONTDATA_ITEM(289, 138, 138, fontpage_289_138_138), // '邊' -- '邊' - FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' - FONTDATA_ITEM(291, 203, 203, fontpage_291_203_203), // '釋' -- '釋' - FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' - FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' - FONTDATA_ITEM(291, 221, 221, fontpage_291_221_221), // '針' -- '針' - FONTDATA_ITEM(292, 149, 149, fontpage_292_149_149), // '鈕' -- '鈕' - FONTDATA_ITEM(294, 175, 175, fontpage_294_175_175), // '錯' -- '錯' - FONTDATA_ITEM(294, 245, 245, fontpage_294_245_245), // '鍵' -- '鍵' - FONTDATA_ITEM(298, 247, 247, fontpage_298_247_247), // '長' -- '長' - FONTDATA_ITEM(299, 137, 137, fontpage_299_137_137), // '閉' -- '閉' - FONTDATA_ITEM(299, 139, 139, fontpage_299_139_139), // '開' -- '開' - FONTDATA_ITEM(299, 147, 147, fontpage_299_147_147), // '間' -- '間' - FONTDATA_ITEM(299, 220, 220, fontpage_299_220_220), // '關' -- '關' - FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' - FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' - FONTDATA_ITEM(301, 142, 142, fontpage_301_142_142), // '階' -- '階' - FONTDATA_ITEM(301, 217, 217, fontpage_301_217_217), // '雙' -- '雙' - FONTDATA_ITEM(301, 226, 226, fontpage_301_226_226), // '離' -- '離' - FONTDATA_ITEM(301, 251, 251, fontpage_301_251_251), // '電' -- '電' - FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' - FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' - FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' - FONTDATA_ITEM(304, 133, 133, fontpage_304_133_133), // '項' -- '項' - FONTDATA_ITEM(304, 144, 144, fontpage_304_144_144), // '預' -- '預' - FONTDATA_ITEM(304, 205, 205, fontpage_304_205_205), // '額' -- '額' - FONTDATA_ITEM(304, 222, 222, fontpage_304_222_222), // '類' -- '類' - FONTDATA_ITEM(305, 168, 168, fontpage_305_168_168), // '風' -- '風' - FONTDATA_ITEM(305, 253, 253, fontpage_305_253_253), // '飽' -- '飽' - FONTDATA_ITEM(306, 152, 152, fontpage_306_152_152), // '餘' -- '餘' - FONTDATA_ITEM(307, 172, 172, fontpage_307_172_172), // '馬' -- '馬' - FONTDATA_ITEM(308, 197, 197, fontpage_308_197_197), // '驅' -- '驅' - FONTDATA_ITEM(309, 212, 212, fontpage_309_212_212), // '體' -- '體' - FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' - FONTDATA_ITEM(317, 195, 195, fontpage_317_195_195), // '黃' -- '黃' - FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' - FONTDATA_ITEM(318, 202, 202, fontpage_318_202_202), // '齊' -- '齊' - FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' +static const uxg_fontinfo_t g_fontinfo_zh_TW[] PROGMEM = { + FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' + FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' + FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' + FONTDATA_ITEM(156, 141, 141, fontpage_156_141_141), // '不' -- '不' + FONTDATA_ITEM(156, 166, 166, fontpage_156_166_166), // '並' -- '並' + FONTDATA_ITEM(156, 173, 173, fontpage_156_173_173), // '中' -- '中' + FONTDATA_ITEM(156, 187, 187, fontpage_156_187_187), // '主' -- '主' + FONTDATA_ITEM(156, 203, 203, fontpage_156_203_203), // '之' -- '之' + FONTDATA_ITEM(157, 164, 164, fontpage_157_164_164), // '交' -- '交' + FONTDATA_ITEM(157, 174, 174, fontpage_157_174_174), // '亮' -- '亮' + FONTDATA_ITEM(157, 228, 228, fontpage_157_228_228), // '令' -- '令' + FONTDATA_ITEM(157, 246, 246, fontpage_157_246_246), // '件' -- '件' + FONTDATA_ITEM(157, 253, 253, fontpage_157_253_253), // '份' -- '份' + FONTDATA_ITEM(158, 145, 145, fontpage_158_145_145), // '休' -- '休' + FONTDATA_ITEM(158, 205, 206, fontpage_158_205_206), // '位' -- '低' + FONTDATA_ITEM(158, 220, 220, fontpage_158_220_220), // '作' -- '作' + FONTDATA_ITEM(159, 155, 155, fontpage_159_155_155), // '供' -- '供' + FONTDATA_ITEM(159, 221, 221, fontpage_159_221_221), // '保' -- '保' + FONTDATA_ITEM(159, 225, 225, fontpage_159_225_225), // '信' -- '信' + FONTDATA_ITEM(160, 139, 139, fontpage_160_139_139), // '個' -- '個' + FONTDATA_ITEM(160, 188, 188, fontpage_160_188_188), // '值' -- '值' + FONTDATA_ITEM(160, 207, 207, fontpage_160_207_207), // '偏' -- '偏' + FONTDATA_ITEM(160, 220, 220, fontpage_160_220_220), // '停' -- '停' + FONTDATA_ITEM(160, 245, 245, fontpage_160_245_245), // '偵' -- '偵' + FONTDATA_ITEM(161, 153, 153, fontpage_161_153_153), // '備' -- '備' + FONTDATA_ITEM(161, 179, 179, fontpage_161_179_179), // '傳' -- '傳' + FONTDATA_ITEM(161, 190, 190, fontpage_161_190_190), // '傾' -- '傾' + FONTDATA_ITEM(162, 178, 178, fontpage_162_178_178), // '儲' -- '儲' + FONTDATA_ITEM(162, 197, 197, fontpage_162_197_197), // '充' -- '充' + FONTDATA_ITEM(162, 200, 201, fontpage_162_200_201), // '先' -- '光' + FONTDATA_ITEM(162, 229, 229, fontpage_162_229_229), // '入' -- '入' + FONTDATA_ITEM(162, 232, 232, fontpage_162_232_232), // '全' -- '全' + FONTDATA_ITEM(162, 241, 241, fontpage_162_241_241), // '共' -- '共' + FONTDATA_ITEM(162, 247, 247, fontpage_162_247_247), // '具' -- '具' + FONTDATA_ITEM(163, 151, 151, fontpage_163_151_151), // '冗' -- '冗' + FONTDATA_ITEM(163, 183, 183, fontpage_163_183_183), // '冷' -- '冷' + FONTDATA_ITEM(163, 198, 198, fontpage_163_198_198), // '准' -- '准' + FONTDATA_ITEM(163, 250, 250, fontpage_163_250_250), // '出' -- '出' + FONTDATA_ITEM(164, 134, 134, fontpage_164_134_134), // '分' -- '分' + FONTDATA_ITEM(164, 151, 151, fontpage_164_151_151), // '列' -- '列' + FONTDATA_ITEM(164, 157, 157, fontpage_164_157_157), // '初' -- '初' + FONTDATA_ITEM(164, 176, 176, fontpage_164_176_176), // '到' -- '到' + FONTDATA_ITEM(164, 182, 183, fontpage_164_182_183), // '制' -- '刷' + FONTDATA_ITEM(164, 245, 245, fontpage_164_245_245), // '創' -- '創' + FONTDATA_ITEM(165, 155, 155, fontpage_165_155_155), // '力' -- '力' + FONTDATA_ITEM(165, 160, 160, fontpage_165_160_160), // '加' -- '加' + FONTDATA_ITEM(165, 213, 213, fontpage_165_213_213), // '動' -- '動' + FONTDATA_ITEM(166, 150, 150, fontpage_166_150_150), // '化' -- '化' + FONTDATA_ITEM(166, 202, 202, fontpage_166_202_202), // '半' -- '半' + FONTDATA_ITEM(166, 212, 212, fontpage_166_212_212), // '協' -- '協' + FONTDATA_ITEM(166, 225, 225, fontpage_166_225_225), // '卡' -- '卡' + FONTDATA_ITEM(166, 240, 240, fontpage_166_240_240), // '印' -- '印' + FONTDATA_ITEM(166, 248, 248, fontpage_166_248_248), // '卸' -- '卸' + FONTDATA_ITEM(166, 251, 251, fontpage_166_251_251), // '卻' -- '卻' + FONTDATA_ITEM(167, 159, 159, fontpage_167_159_159), // '原' -- '原' + FONTDATA_ITEM(167, 205, 205, fontpage_167_205_205), // '反' -- '反' + FONTDATA_ITEM(167, 214, 214, fontpage_167_214_214), // '取' -- '取' + FONTDATA_ITEM(167, 240, 240, fontpage_167_240_240), // '台' -- '台' + FONTDATA_ITEM(168, 136, 136, fontpage_168_136_136), // '合' -- '合' + FONTDATA_ITEM(168, 166, 166, fontpage_168_166_166), // '否' -- '否' + FONTDATA_ITEM(168, 202, 202, fontpage_168_202_202), // '告' -- '告' + FONTDATA_ITEM(168, 253, 253, fontpage_168_253_253), // '命' -- '命' + FONTDATA_ITEM(169, 140, 140, fontpage_169_140_140), // '和' -- '和' + FONTDATA_ITEM(170, 223, 223, fontpage_170_223_223), // '啟' -- '啟' + FONTDATA_ITEM(171, 174, 174, fontpage_171_174_174), // '單' -- '單' + FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' + FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' + FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' + FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' + FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' + FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' + FONTDATA_ITEM(174, 150, 150, fontpage_174_150_150), // '圖' -- '圖' + FONTDATA_ITEM(174, 168, 168, fontpage_174_168_168), // '在' -- '在' + FONTDATA_ITEM(175, 139, 139, fontpage_175_139_139), // '型' -- '型' + FONTDATA_ITEM(175, 247, 247, fontpage_175_247_247), // '執' -- '執' + FONTDATA_ITEM(176, 202, 202, fontpage_176_202_202), // '塊' -- '塊' + FONTDATA_ITEM(176, 235, 235, fontpage_176_235_235), // '填' -- '填' + FONTDATA_ITEM(177, 138, 138, fontpage_177_138_138), // '墊' -- '墊' + FONTDATA_ITEM(178, 150, 150, fontpage_178_150_150), // '外' -- '外' + FONTDATA_ITEM(178, 154, 154, fontpage_178_154_154), // '多' -- '多' + FONTDATA_ITEM(178, 160, 160, fontpage_178_160_160), // '夠' -- '夠' + FONTDATA_ITEM(178, 167, 167, fontpage_178_167_167), // '大' -- '大' + FONTDATA_ITEM(178, 169, 170, fontpage_178_169_170), // '天' -- '太' + FONTDATA_ITEM(178, 177, 177, fontpage_178_177_177), // '失' -- '失' + FONTDATA_ITEM(179, 203, 203, fontpage_179_203_203), // '始' -- '始' + FONTDATA_ITEM(181, 146, 146, fontpage_181_146_146), // '媒' -- '媒' + FONTDATA_ITEM(182, 208, 208, fontpage_182_208_208), // '子' -- '子' + FONTDATA_ITEM(182, 216, 216, fontpage_182_216_216), // '存' -- '存' + FONTDATA_ITEM(183, 137, 137, fontpage_183_137_137), // '安' -- '安' + FONTDATA_ITEM(183, 140, 140, fontpage_183_140_140), // '完' -- '完' + FONTDATA_ITEM(183, 154, 154, fontpage_183_154_154), // '定' -- '定' + FONTDATA_ITEM(183, 162, 162, fontpage_183_162_162), // '客' -- '客' + FONTDATA_ITEM(183, 185, 185, fontpage_183_185_185), // '容' -- '容' + FONTDATA_ITEM(184, 141, 141, fontpage_184_141_141), // '對' -- '對' + FONTDATA_ITEM(184, 143, 143, fontpage_184_143_143), // '小' -- '小' + FONTDATA_ITEM(184, 177, 177, fontpage_184_177_177), // '就' -- '就' + FONTDATA_ITEM(187, 229, 229, fontpage_187_229_229), // '工' -- '工' + FONTDATA_ITEM(187, 238, 238, fontpage_187_238_238), // '差' -- '差' + FONTDATA_ITEM(187, 242, 242, fontpage_187_242_242), // '已' -- '已' + FONTDATA_ITEM(188, 243, 243, fontpage_188_243_243), // '平' -- '平' + FONTDATA_ITEM(189, 138, 138, fontpage_189_138_138), // '床' -- '床' + FONTDATA_ITEM(189, 166, 166, fontpage_189_166_166), // '度' -- '度' + FONTDATA_ITEM(189, 226, 226, fontpage_189_226_226), // '廢' -- '廢' + FONTDATA_ITEM(189, 250, 250, fontpage_189_250_250), // '建' -- '建' + FONTDATA_ITEM(190, 149, 149, fontpage_190_149_149), // '引' -- '引' + FONTDATA_ITEM(191, 133, 133, fontpage_191_133_133), // '待' -- '待' + FONTDATA_ITEM(191, 140, 140, fontpage_191_140_140), // '後' -- '後' + FONTDATA_ITEM(191, 145, 145, fontpage_191_145_145), // '徑' -- '徑' + FONTDATA_ITEM(191, 158, 158, fontpage_191_158_158), // '從' -- '從' + FONTDATA_ITEM(191, 169, 169, fontpage_191_169_169), // '復' -- '復' + FONTDATA_ITEM(191, 174, 174, fontpage_191_174_174), // '微' -- '微' + FONTDATA_ITEM(191, 195, 195, fontpage_191_195_195), // '心' -- '心' + FONTDATA_ITEM(192, 167, 167, fontpage_192_167_167), // '性' -- '性' + FONTDATA_ITEM(192, 226, 226, fontpage_192_226_226), // '恢' -- '恢' + FONTDATA_ITEM(192, 239, 239, fontpage_192_239_239), // '息' -- '息' + FONTDATA_ITEM(195, 182, 182, fontpage_195_182_182), // '憶' -- '憶' + FONTDATA_ITEM(195, 201, 201, fontpage_195_201_201), // '應' -- '應' + FONTDATA_ITEM(196, 144, 144, fontpage_196_144_144), // '成' -- '成' + FONTDATA_ITEM(196, 182, 182, fontpage_196_182_182), // '戶' -- '戶' + FONTDATA_ITEM(196, 192, 192, fontpage_196_192_192), // '所' -- '所' + FONTDATA_ITEM(196, 199, 199, fontpage_196_199_199), // '扇' -- '扇' + FONTDATA_ITEM(196, 203, 203, fontpage_196_203_203), // '手' -- '手' + FONTDATA_ITEM(196, 211, 211, fontpage_196_211_211), // '打' -- '打' + FONTDATA_ITEM(196, 249, 249, fontpage_196_249_249), // '批' -- '批' + FONTDATA_ITEM(197, 150, 150, fontpage_197_150_150), // '抖' -- '抖' + FONTDATA_ITEM(197, 189, 189, fontpage_197_189_189), // '抽' -- '抽' + FONTDATA_ITEM(197, 212, 212, fontpage_197_212_212), // '拔' -- '拔' + FONTDATA_ITEM(198, 137, 137, fontpage_198_137_137), // '按' -- '按' + FONTDATA_ITEM(199, 137, 137, fontpage_199_137_137), // '掉' -- '掉' + FONTDATA_ITEM(199, 162, 162, fontpage_199_162_162), // '探' -- '探' + FONTDATA_ITEM(199, 165, 165, fontpage_199_165_165), // '接' -- '接' + FONTDATA_ITEM(199, 167, 167, fontpage_199_167_167), // '控' -- '控' + FONTDATA_ITEM(199, 208, 208, fontpage_199_208_208), // '提' -- '提' + FONTDATA_ITEM(199, 210, 210, fontpage_199_210_210), // '插' -- '插' + FONTDATA_ITEM(199, 219, 219, fontpage_199_219_219), // '換' -- '換' + FONTDATA_ITEM(201, 199, 199, fontpage_201_199_199), // '擇' -- '擇' + FONTDATA_ITEM(201, 202, 203, fontpage_201_202_203), // '擊' -- '擋' + FONTDATA_ITEM(201, 224, 224, fontpage_201_224_224), // '擠' -- '擠' + FONTDATA_ITEM(202, 182, 182, fontpage_202_182_182), // '收' -- '收' + FONTDATA_ITEM(202, 190, 190, fontpage_202_190_190), // '放' -- '放' + FONTDATA_ITEM(202, 215, 215, fontpage_202_215_215), // '敗' -- '敗' + FONTDATA_ITEM(202, 244, 244, fontpage_202_244_244), // '整' -- '整' + FONTDATA_ITEM(202, 248, 248, fontpage_202_248_248), // '數' -- '數' + FONTDATA_ITEM(203, 153, 153, fontpage_203_153_153), // '料' -- '料' + FONTDATA_ITEM(203, 156, 156, fontpage_203_156_156), // '斜' -- '斜' + FONTDATA_ITEM(203, 176, 176, fontpage_203_176_176), // '新' -- '新' + FONTDATA_ITEM(203, 183, 183, fontpage_203_183_183), // '斷' -- '斷' + FONTDATA_ITEM(203, 188, 188, fontpage_203_188_188), // '於' -- '於' + FONTDATA_ITEM(204, 135, 135, fontpage_204_135_135), // '昇' -- '昇' + FONTDATA_ITEM(204, 142, 142, fontpage_204_142_142), // '明' -- '明' + FONTDATA_ITEM(204, 175, 175, fontpage_204_175_175), // '是' -- '是' + FONTDATA_ITEM(204, 194, 194, fontpage_204_194_194), // '時' -- '時' + FONTDATA_ITEM(205, 171, 171, fontpage_205_171_171), // '暫' -- '暫' + FONTDATA_ITEM(205, 244, 244, fontpage_205_244_244), // '更' -- '更' + FONTDATA_ITEM(206, 128, 128, fontpage_206_128_128), // '最' -- '最' + FONTDATA_ITEM(206, 137, 137, fontpage_206_137_137), // '有' -- '有' + FONTDATA_ITEM(206, 255, 255, fontpage_206_255_255), // '板' -- '板' + FONTDATA_ITEM(207, 241, 241, fontpage_207_241_241), // '柱' -- '柱' + FONTDATA_ITEM(208, 161, 161, fontpage_208_161_161), // '校' -- '校' + FONTDATA_ITEM(208, 188, 188, fontpage_208_188_188), // '格' -- '格' + FONTDATA_ITEM(209, 157, 157, fontpage_209_157_157), // '條' -- '條' + FONTDATA_ITEM(209, 196, 196, fontpage_209_196_196), // '棄' -- '棄' + FONTDATA_ITEM(211, 253, 253, fontpage_211_253_253), // '槽' -- '槽' + FONTDATA_ITEM(212, 217, 217, fontpage_212_217_217), // '橙' -- '橙' + FONTDATA_ITEM(212, 223, 223, fontpage_212_223_223), // '機' -- '機' + FONTDATA_ITEM(213, 162, 162, fontpage_213_162_162), // '檢' -- '檢' + FONTDATA_ITEM(214, 226, 227, fontpage_214_226_227), // '止' -- '正' + FONTDATA_ITEM(214, 229, 229, fontpage_214_229_229), // '步' -- '步' + FONTDATA_ITEM(214, 248, 248, fontpage_214_248_248), // '歸' -- '歸' + FONTDATA_ITEM(215, 188, 188, fontpage_215_188_188), // '殼' -- '殼' + FONTDATA_ITEM(215, 212, 212, fontpage_215_212_212), // '比' -- '比' + FONTDATA_ITEM(217, 146, 146, fontpage_217_146_146), // '沒' -- '沒' + FONTDATA_ITEM(219, 136, 136, fontpage_219_136_136), // '消' -- '消' + FONTDATA_ITEM(219, 225, 225, fontpage_219_225_225), // '淡' -- '淡' + FONTDATA_ITEM(220, 133, 133, fontpage_220_133_133), // '清' -- '清' + FONTDATA_ITEM(220, 172, 172, fontpage_220_172_172), // '測' -- '測' + FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' + FONTDATA_ITEM(221, 150, 150, fontpage_221_150_150), // '準' -- '準' + FONTDATA_ITEM(221, 171, 171, fontpage_221_171_171), // '溫' -- '溫' + FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' + FONTDATA_ITEM(226, 161, 161, fontpage_226_161_161), // '無' -- '無' + FONTDATA_ITEM(227, 177, 177, fontpage_227_177_177), // '熱' -- '熱' + FONTDATA_ITEM(227, 200, 200, fontpage_227_200_200), // '燈' -- '燈' + FONTDATA_ITEM(228, 199, 199, fontpage_228_199_199), // '片' -- '片' + FONTDATA_ITEM(228, 233, 233, fontpage_228_233_233), // '物' -- '物' + FONTDATA_ITEM(231, 135, 135, fontpage_231_135_135), // '率' -- '率' + FONTDATA_ITEM(234, 168, 168, fontpage_234_168_168), // '用' -- '用' + FONTDATA_ITEM(234, 204, 204, fontpage_234_204_204), // '界' -- '界' + FONTDATA_ITEM(236, 253, 253, fontpage_236_253_253), // '白' -- '白' + FONTDATA_ITEM(237, 132, 132, fontpage_237_132_132), // '的' -- '的' + FONTDATA_ITEM(237, 227, 227, fontpage_237_227_227), // '監' -- '監' + FONTDATA_ITEM(237, 244, 244, fontpage_237_244_244), // '直' -- '直' + FONTDATA_ITEM(238, 160, 160, fontpage_238_160_160), // '眠' -- '眠' + FONTDATA_ITEM(240, 141, 141, fontpage_240_141_141), // '砍' -- '砍' + FONTDATA_ITEM(241, 186, 186, fontpage_241_186_186), // '確' -- '確' + FONTDATA_ITEM(243, 251, 251, fontpage_243_251_251), // '移' -- '移' + FONTDATA_ITEM(244, 205, 205, fontpage_244_205_205), // '積' -- '積' + FONTDATA_ITEM(245, 239, 239, fontpage_245_239_239), // '端' -- '端' + FONTDATA_ITEM(246, 201, 201, fontpage_246_201_201), // '等' -- '等' + FONTDATA_ITEM(247, 161, 161, fontpage_247_161_161), // '管' -- '管' + FONTDATA_ITEM(247, 177, 177, fontpage_247_177_177), // '箱' -- '箱' + FONTDATA_ITEM(249, 251, 251, fontpage_249_251_251), // '系' -- '系' + FONTDATA_ITEM(250, 133, 133, fontpage_250_133_133), // '紅' -- '紅' + FONTDATA_ITEM(250, 162, 162, fontpage_250_162_162), // '索' -- '索' + FONTDATA_ITEM(250, 171, 171, fontpage_250_171_171), // '紫' -- '紫' + FONTDATA_ITEM(250, 176, 176, fontpage_250_176_176), // '細' -- '細' + FONTDATA_ITEM(250, 194, 194, fontpage_250_194_194), // '終' -- '終' + FONTDATA_ITEM(250, 241, 242, fontpage_250_241_242), // '統' -- '絲' + FONTDATA_ITEM(251, 160, 160, fontpage_251_160_160), // '綠' -- '綠' + FONTDATA_ITEM(251, 178, 178, fontpage_251_178_178), // '網' -- '網' + FONTDATA_ITEM(251, 210, 210, fontpage_251_210_210), // '緒' -- '緒' + FONTDATA_ITEM(251, 218, 218, fontpage_251_218_218), // '線' -- '線' + FONTDATA_ITEM(251, 232, 232, fontpage_251_232_232), // '編' -- '編' + FONTDATA_ITEM(252, 174, 174, fontpage_252_174_174), // '縮' -- '縮' + FONTDATA_ITEM(252, 189, 189, fontpage_252_189_189), // '總' -- '總' + FONTDATA_ITEM(252, 252, 252, fontpage_252_252_252), // '繼' -- '繼' + FONTDATA_ITEM(253, 140, 140, fontpage_253_140_140), // '續' -- '續' + FONTDATA_ITEM(253, 162, 162, fontpage_253_162_162), // '红' -- '红' + FONTDATA_ITEM(254, 238, 238, fontpage_254_238_238), // '置' -- '置' + FONTDATA_ITEM(254, 242, 242, fontpage_254_242_242), // '署' -- '署' + FONTDATA_ITEM(256, 240, 240, fontpage_256_240_240), // '聰' -- '聰' + FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' + FONTDATA_ITEM(267, 205, 205, fontpage_267_205_205), // '藍' -- '藍' + FONTDATA_ITEM(272, 204, 204, fontpage_272_204_204), // '行' -- '行' + FONTDATA_ITEM(272, 232, 232, fontpage_272_232_232), // '表' -- '表' + FONTDATA_ITEM(273, 171, 171, fontpage_273_171_171), // '被' -- '被' + FONTDATA_ITEM(273, 197, 197, fontpage_273_197_197), // '装' -- '装' + FONTDATA_ITEM(273, 221, 221, fontpage_273_221_221), // '裝' -- '裝' + FONTDATA_ITEM(274, 135, 135, fontpage_274_135_135), // '複' -- '複' + FONTDATA_ITEM(275, 210, 210, fontpage_275_210_210), // '角' -- '角' + FONTDATA_ITEM(276, 136, 136, fontpage_276_136_136), // '計' -- '計' + FONTDATA_ITEM(276, 138, 138, fontpage_276_138_138), // '訊' -- '訊' + FONTDATA_ITEM(276, 152, 152, fontpage_276_152_152), // '記' -- '記' + FONTDATA_ITEM(276, 173, 173, fontpage_276_173_173), // '設' -- '設' + FONTDATA_ITEM(276, 230, 230, fontpage_276_230_230), // '試' -- '試' + FONTDATA_ITEM(277, 141, 141, fontpage_277_141_141), // '認' -- '認' + FONTDATA_ITEM(277, 164, 164, fontpage_277_164_164), // '誤' -- '誤' + FONTDATA_ITEM(277, 191, 191, fontpage_277_191_191), // '調' -- '調' + FONTDATA_ITEM(277, 203, 203, fontpage_277_203_203), // '請' -- '請' + FONTDATA_ITEM(278, 240, 240, fontpage_278_240_240), // '議' -- '議' + FONTDATA_ITEM(279, 128, 128, fontpage_279_128_128), // '讀' -- '讀' + FONTDATA_ITEM(279, 138, 138, fontpage_279_138_138), // '變' -- '變' + FONTDATA_ITEM(281, 199, 199, fontpage_281_199_199), // '資' -- '資' + FONTDATA_ITEM(283, 221, 221, fontpage_283_221_221), // '距' -- '距' + FONTDATA_ITEM(285, 202, 202, fontpage_285_202_202), // '車' -- '車' + FONTDATA_ITEM(285, 223, 223, fontpage_285_223_223), // '軟' -- '軟' + FONTDATA_ITEM(285, 248, 248, fontpage_285_248_248), // '軸' -- '軸' + FONTDATA_ITEM(286, 137, 137, fontpage_286_137_137), // '載' -- '載' + FONTDATA_ITEM(286, 175, 175, fontpage_286_175_175), // '輯' -- '輯' + FONTDATA_ITEM(286, 184, 184, fontpage_286_184_184), // '輸' -- '輸' + FONTDATA_ITEM(286, 201, 201, fontpage_286_201_201), // '轉' -- '轉' + FONTDATA_ITEM(287, 209, 209, fontpage_287_209_209), // '近' -- '近' + FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' + FONTDATA_ITEM(288, 128, 128, fontpage_288_128_128), // '退' -- '退' + FONTDATA_ITEM(288, 159, 159, fontpage_288_159_159), // '速' -- '速' + FONTDATA_ITEM(288, 163, 163, fontpage_288_163_163), // '連' -- '連' + FONTDATA_ITEM(288, 178, 178, fontpage_288_178_178), // '進' -- '進' + FONTDATA_ITEM(288, 203, 203, fontpage_288_203_203), // '運' -- '運' + FONTDATA_ITEM(288, 212, 212, fontpage_288_212_212), // '達' -- '達' + FONTDATA_ITEM(288, 248, 248, fontpage_288_248_248), // '選' -- '選' + FONTDATA_ITEM(289, 132, 132, fontpage_289_132_132), // '還' -- '還' + FONTDATA_ITEM(289, 138, 138, fontpage_289_138_138), // '邊' -- '邊' + FONTDATA_ITEM(289, 232, 232, fontpage_289_232_232), // '部' -- '部' + FONTDATA_ITEM(291, 203, 203, fontpage_291_203_203), // '釋' -- '釋' + FONTDATA_ITEM(291, 205, 205, fontpage_291_205_205), // '重' -- '重' + FONTDATA_ITEM(291, 207, 207, fontpage_291_207_207), // '量' -- '量' + FONTDATA_ITEM(291, 221, 221, fontpage_291_221_221), // '針' -- '針' + FONTDATA_ITEM(292, 149, 149, fontpage_292_149_149), // '鈕' -- '鈕' + FONTDATA_ITEM(294, 175, 175, fontpage_294_175_175), // '錯' -- '錯' + FONTDATA_ITEM(294, 245, 245, fontpage_294_245_245), // '鍵' -- '鍵' + FONTDATA_ITEM(298, 247, 247, fontpage_298_247_247), // '長' -- '長' + FONTDATA_ITEM(299, 137, 137, fontpage_299_137_137), // '閉' -- '閉' + FONTDATA_ITEM(299, 139, 139, fontpage_299_139_139), // '開' -- '開' + FONTDATA_ITEM(299, 147, 147, fontpage_299_147_147), // '間' -- '間' + FONTDATA_ITEM(299, 220, 220, fontpage_299_220_220), // '關' -- '關' + FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' + FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' + FONTDATA_ITEM(301, 142, 142, fontpage_301_142_142), // '階' -- '階' + FONTDATA_ITEM(301, 217, 217, fontpage_301_217_217), // '雙' -- '雙' + FONTDATA_ITEM(301, 226, 226, fontpage_301_226_226), // '離' -- '離' + FONTDATA_ITEM(301, 251, 251, fontpage_301_251_251), // '電' -- '電' + FONTDATA_ITEM(302, 210, 210, fontpage_302_210_210), // '青' -- '青' + FONTDATA_ITEM(302, 222, 222, fontpage_302_222_222), // '非' -- '非' + FONTDATA_ITEM(302, 226, 226, fontpage_302_226_226), // '面' -- '面' + FONTDATA_ITEM(304, 133, 133, fontpage_304_133_133), // '項' -- '項' + FONTDATA_ITEM(304, 144, 144, fontpage_304_144_144), // '預' -- '預' + FONTDATA_ITEM(304, 205, 205, fontpage_304_205_205), // '額' -- '額' + FONTDATA_ITEM(304, 222, 222, fontpage_304_222_222), // '類' -- '類' + FONTDATA_ITEM(305, 168, 168, fontpage_305_168_168), // '風' -- '風' + FONTDATA_ITEM(305, 253, 253, fontpage_305_253_253), // '飽' -- '飽' + FONTDATA_ITEM(306, 152, 152, fontpage_306_152_152), // '餘' -- '餘' + FONTDATA_ITEM(307, 172, 172, fontpage_307_172_172), // '馬' -- '馬' + FONTDATA_ITEM(308, 197, 197, fontpage_308_197_197), // '驅' -- '驅' + FONTDATA_ITEM(309, 212, 212, fontpage_309_212_212), // '體' -- '體' + FONTDATA_ITEM(309, 216, 216, fontpage_309_216_216), // '高' -- '高' + FONTDATA_ITEM(317, 195, 195, fontpage_317_195_195), // '黃' -- '黃' + FONTDATA_ITEM(317, 222, 222, fontpage_317_222_222), // '點' -- '點' + FONTDATA_ITEM(318, 202, 202, fontpage_318_202_202), // '齊' -- '齊' + FONTDATA_ITEM(510, 154, 154, fontpage_510_154_154), // ':' -- ':' }; diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index f6ed227539..25e943a14d 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -79,6 +79,18 @@ U8G_CLASS u8g; #include LANGUAGE_DATA_INCL(LCD_LANGUAGE) +#ifdef LCD_LANGUAGE_2 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_2) +#endif +#ifdef LCD_LANGUAGE_3 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_3) +#endif +#ifdef LCD_LANGUAGE_4 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_4) +#endif +#ifdef LCD_LANGUAGE_5 + #include LANGUAGE_DATA_INCL(LCD_LANGUAGE_5) +#endif #if HAS_LCD_CONTRAST @@ -293,7 +305,29 @@ void MarlinUI::init_lcd() { TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); - uxg_SetUtf8Fonts(g_fontinfo, COUNT(g_fontinfo)); + update_language_font(); +} + +void MarlinUI::update_language_font() { + #if HAS_MULTI_LANGUAGE + switch (language) { + default: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE), COUNT(LANG_FONT_INFO(LCD_LANGUAGE))); break; + #ifdef LCD_LANGUAGE_2 + case 1: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_2), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_2))); break; + #endif + #ifdef LCD_LANGUAGE_3 + case 2: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_3), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_3))); break; + #endif + #ifdef LCD_LANGUAGE_4 + case 3: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_4), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_4))); break; + #endif + #ifdef LCD_LANGUAGE_5 + case 4: uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE_5), COUNT(LANG_FONT_INFO(LCD_LANGUAGE_5))); break; + #endif + } + #else + uxg_SetUtf8Fonts(LANG_FONT_INFO(LCD_LANGUAGE), COUNT(LANG_FONT_INFO(LCD_LANGUAGE))); + #endif } // The kill screen is displayed for unrecoverable conditions diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.h b/Marlin/src/lcd/dogm/u8g_fontutf8.h index d7ea618de0..9760ef106b 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.h +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.h @@ -35,3 +35,6 @@ int uxg_GetUtf8StrPixelWidth(u8g_t *pu8g, const char *utf8_msg); int uxg_GetUtf8StrPixelWidthP(u8g_t *pu8g, PGM_P utf8_msg); #define uxg_GetFont(puxg) ((puxg)->font) + +#define _LANG_FONT_INFO(L) g_fontinfo_##L +#define LANG_FONT_INFO(L) _LANG_FONT_INFO(L) diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 39093a7c6c..33eb7fca15 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -31,7 +31,7 @@ namespace Language_zh_CN { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 3; - PROGMEM Language_Str LANGUAGE = _UxGT("简体中文"); + PROGMEM Language_Str LANGUAGE = _UxGT("Simplified Chinese"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); //" ready." PROGMEM Language_Str MSG_MARLIN = _UxGT("马林"); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 206bae925a..346082986d 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -88,6 +88,14 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_MULTI_LANGUAGE uint8_t MarlinUI::language; // Initialized by settings.load() + void MarlinUI::set_language(const uint8_t lang) { + if (lang < NUM_LANGUAGES) { + language = lang; + TERN_(HAS_MARLINUI_U8GLIB, update_language_font()); + return_to_status(); + refresh(); + } + } #endif #if ENABLED(SOUND_MENU_ITEM) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index bf7215d383..4f11ded53f 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -200,13 +200,11 @@ public: #if HAS_MULTI_LANGUAGE static uint8_t language; - static inline void set_language(const uint8_t lang) { - if (lang < NUM_LANGUAGES) { - language = lang; - return_to_status(); - refresh(); - } - } + static void set_language(const uint8_t lang); + #endif + + #if HAS_MARLINUI_U8GLIB + static void update_language_font(); #endif #if ENABLED(SOUND_MENU_ITEM) From 1a0103d276696793429574bf5550034010f4303a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 19 Jul 2021 01:03:15 +0000 Subject: [PATCH 0420/2168] [cron] Bump distribution date (2021-07-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c1cd96ecac..ea80f51d28 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-18" +//#define STRING_DISTRIBUTION_DATE "2021-07-19" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b88141a5b7..29249b0b9b 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 "2021-07-18" + #define STRING_DISTRIBUTION_DATE "2021-07-19" #endif /** From 286f6ba0bd2ab4d405fc83d913399130fa063f9a Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Sun, 18 Jul 2021 20:11:24 -0500 Subject: [PATCH 0421/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Ammeter=20displa?= =?UTF-8?q?y=20on=20DOGM=20(#22384)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 6 +++--- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 4 ++++ 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 6aa2bab0da..dfbf7b4291 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -624,7 +624,7 @@ #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) #endif #ifndef STATUS_AMMETER_HEIGHT - #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp1) / (STATUS_AMMETER_BYTEWIDTH)) + #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp_mA) / (STATUS_AMMETER_BYTEWIDTH)) #endif #ifndef STATUS_AMMETER_Y #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) @@ -633,8 +633,8 @@ #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) #endif static_assert( - sizeof(status_ammeter_bmp1) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), - "Status ammeter bitmap (status_ammeter_bmp1) dimensions don't match data." + sizeof(status_ammeter_bmp_mA) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), + "Status ammeter bitmap (status_ammeter_bmp_mA) dimensions don't match data." ); #endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index d58be4dbaf..a66aca6d19 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -57,6 +57,10 @@ #include "../../feature/cooler.h" #endif +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + #if HAS_POWER_MONITOR #include "../../feature/power_monitor.h" #endif From 273ff6fedc4701733464ff33625fba3dbdf1a53c Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Sun, 18 Jul 2021 18:24:27 -0700 Subject: [PATCH 0422/2168] =?UTF-8?q?=F0=9F=90=9B=20Ensure=20Software=20SP?= =?UTF-8?q?I=20pins=20for=20Max=20Thermocouple=20(#22389)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fd2c260fd3..f8ccc0c067 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -107,6 +107,24 @@ #if (TEMP_SENSOR_0_USES_SW_SPI || TEMP_SENSOR_1_USES_SW_SPI) && !HAS_MAXTC_LIBRARIES #include "../libs/private_spi.h" #define HAS_MAXTC_SW_SPI 1 + + // Define pins for SPI-based sensors + #if TEMP_SENSOR_0_USES_SW_SPI + #define SW_SPI_SCK_PIN TEMP_0_SCK_PIN + #define SW_SPI_MISO_PIN TEMP_0_MISO_PIN + #if PIN_EXISTS(TEMP_0_MOSI) + #define SW_SPI_MOSI_PIN TEMP_0_MOSI_PIN + #endif + #else + #define SW_SPI_SCK_PIN TEMP_1_SCK_PIN + #define SW_SPI_MISO_PIN TEMP_1_MISO_PIN + #if PIN_EXISTS(TEMP_1_MOSI) + #define SW_SPI_MOSI_PIN TEMP_1_MOSI_PIN + #endif + #endif + #ifndef SW_SPI_MOSI_PIN + #define SW_SPI_MOSI_PIN SD_MOSI_PIN + #endif #endif #if ENABLED(PID_EXTRUSION_SCALING) @@ -198,7 +216,8 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, // Initialize SoftSPI for non-lib Software SPI; Libraries take care of it themselves. template SoftSPI SPIclass::softSPI; - SPIclass max_tc_spi; + SPIclass max_tc_spi; + #endif #define MAXTC_INIT(n, M) \ From 67019bc2778c00ec0ba80519078ad5ecc57f06ff Mon Sep 17 00:00:00 2001 From: Malderin <52313714+Malderin@users.noreply.github.com> Date: Mon, 19 Jul 2021 05:21:51 +0300 Subject: [PATCH 0423/2168] Fix MKS UI compile (#22388) Co-authored-by: Scott Lahteine --- Marlin/src/MarlinCore.cpp | 2 +- .../src/lcd/extui/mks_ui/draw_error_message.cpp | 7 +------ .../src/lcd/extui/mks_ui/draw_ready_print.cpp | 7 ++----- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 4 ++-- .../{mks_hardware_test.cpp => mks_hardware.cpp} | 7 +++---- .../{mks_hardware_test.h => mks_hardware.h} | 17 ++++++++++++----- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 7 +------ .../lcd/extui/mks_ui/tft_lvgl_configuration.cpp | 4 ++-- 8 files changed, 24 insertions(+), 31 deletions(-) rename Marlin/src/lcd/extui/mks_ui/{mks_hardware_test.cpp => mks_hardware.cpp} (99%) rename Marlin/src/lcd/extui/mks_ui/{mks_hardware_test.h => mks_hardware.h} (80%) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1da030b249..07a6a31b94 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -70,7 +70,7 @@ #if HAS_TFT_LVGL_UI #include "lcd/extui/mks_ui/tft_lvgl_configuration.h" #include "lcd/extui/mks_ui/draw_ui.h" - #include "lcd/extui/mks_ui/mks_hardware_test.h" + #include "lcd/extui/mks_ui/mks_hardware.h" #include #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index 7ee2617326..48ff56253b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -25,15 +25,10 @@ #include "draw_ui.h" #include - #include "tft_lvgl_configuration.h" - #include "SPI_TFT.h" #include "../../../inc/MarlinConfig.h" - -#if ENABLED(MKS_TEST) - #include "mks_hardware_test.h" -#endif +#include "mks_hardware.h" static lv_obj_t *scr; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index 83aec7613e..6f24d81b49 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -39,10 +39,7 @@ #include "draw_touch_calibration.h" #endif -#if ENABLED(MKS_TEST) - #include "mks_hardware_test.h" -#endif - +#include "mks_hardware.h" #include #define ICON_POS_Y 38 @@ -129,7 +126,7 @@ void lv_draw_ready_print() { ZERO(disp_state_stack._disp_state); scr = lv_screen_create(PRINT_READY_UI, ""); - if (mks_test_flag == 0x1E) { + if (TERN0(SDSUPPORT, mks_test_flag == 0x1E)) { // Create image buttons buttonTool = lv_imgbtn_create(scr, "F:/bmp_tool.bin", event_handler, ID_TOOL); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 30e08e03ed..1c1e5cc1f5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -52,7 +52,7 @@ #endif #if ENABLED(MKS_TEST) - #include "mks_hardware_test.h" + #include "mks_hardware.h" #endif CFG_ITMES gCfgItems; @@ -1366,7 +1366,7 @@ void print_time_count() { void LV_TASK_HANDLER() { lv_task_handler(); - #if ENABLED(MKS_TEST) + #if BOTH(MKS_TEST, SDSUPPORT) if (mks_test_flag == 0x1E) mks_hardware_test(); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp similarity index 99% rename from Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp rename to Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 125f8be0f6..cf9790ea9d 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -37,7 +37,7 @@ #if ENABLED(MKS_TEST) - #include "mks_hardware_test.h" + #include "mks_hardware.h" bool pw_det_sta, pw_off_sta, mt_det_sta; #if PIN_EXISTS(MT_DET_2) @@ -613,10 +613,9 @@ void disp_assets_update_progress(const char *msg) { disp_string(100, 165, buf, 0xFFFF, 0x0000); } -uint8_t mks_test_flag = 0; -const char *MKSTestPath = "MKS_TEST"; - #if ENABLED(SDSUPPORT) + uint8_t mks_test_flag = 0; + const char *MKSTestPath = "MKS_TEST"; void mks_test_get() { SdFile dir, root = card.getroot(); if (dir.open(&root, MKSTestPath, O_RDONLY)) diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h similarity index 80% rename from Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h rename to Marlin/src/lcd/extui/mks_ui/mks_hardware.h index 1b46d4b0e6..de0c3a738e 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware_test.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -21,15 +21,22 @@ */ #pragma once +#include "../../../inc/MarlinConfigPre.h" + #include -void mks_gpio_test(); -void mks_hardware_test(); -void mks_test_get(); +// Functions for MKS_TEST +#if ENABLED(MKS_TEST) + void mks_gpio_test(); + void mks_hardware_test(); + void mks_test_get(); +#endif -void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint16_t bkColor); +// String display and assets void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); void disp_assets_update(); void disp_assets_update_progress(const char *msg); -extern uint8_t mks_test_flag; +#if ENABLED(SDSUPPORT) + extern uint8_t mks_test_flag; +#endif diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 03e408e32a..68344e770c 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -27,14 +27,9 @@ #include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" - -#if ENABLED(MKS_TEST) - #include "mks_hardware_test.h" -#endif - +#include "mks_hardware.h" #include "SPIFlashStorage.h" #include "../../../libs/W25Qxx.h" - #include "../../../sd/cardreader.h" #include "../../../MarlinCore.h" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 7f84277ef0..d8c5fbd6ec 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -29,7 +29,7 @@ #include "draw_ready_print.h" #include "pic_manager.h" -#include "mks_hardware_test.h" +#include "mks_hardware.h" #include "draw_ui.h" #include "SPIFlashStorage.h" #include @@ -231,7 +231,7 @@ void tft_lvgl_init() { if (ready) lv_draw_ready_print(); - #if ENABLED(MKS_TEST) + #if BOTH(MKS_TEST, SDSUPPORT) if (mks_test_flag == 0x1E) mks_gpio_test(); #endif } From c2f72cde1024538a6026b9db794fcd4f6b7ca07a Mon Sep 17 00:00:00 2001 From: Serhiy-K <52166448+Serhiy-K@users.noreply.github.com> Date: Mon, 19 Jul 2021 05:39:01 +0300 Subject: [PATCH 0424/2168] =?UTF-8?q?=E2=9C=A8=20Laser=20support=20for=20T?= =?UTF-8?q?FT=20GLCD=20(#22391)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 322 ++++++++++++++------ 2 files changed, 226 insertions(+), 98 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 6cf0b82241..7e2239b3f6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -213,7 +213,7 @@ #define LCD_PROGRESS_BAR #endif #if ENABLED(TFTGLCD_PANEL_I2C) - #define LCD_I2C_ADDRESS 0x27 // Must be equal to panel's I2C slave addres + #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave addres #endif #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) #define STD_ENCODER_PULSES_PER_STEP 2 diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index edb17b69c0..3324819955 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -57,6 +57,18 @@ #include "../../gcode/parser.h" #endif +#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) + #include "../../feature/cooler.h" +#endif + +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + +#if HAS_CUTTER + #include "../../feature/spindle_laser.h" +#endif + #if ENABLED(AUTO_BED_LEVELING_UBL) #include "../../feature/bedlevel/bedlevel.h" #endif @@ -64,12 +76,12 @@ TFTGLCD lcd; #define ICON_LOGO B00000001 -#define ICON_TEMP1 B00000010 //hotend 1 -#define ICON_TEMP2 B00000100 //hotend 2 -#define ICON_TEMP3 B00001000 //hotend 3 +#define ICON_TEMP1 B00000010 // Hotend 1 +#define ICON_TEMP2 B00000100 // Hotend 2 +#define ICON_TEMP3 B00001000 // Hotend 3 #define ICON_BED B00010000 #define ICON_FAN B00100000 -#define ICON_HOT B01000000 //when any T > 50deg +#define ICON_HOT B01000000 // When any T > 50deg #define PIC_MASK 0x7F // LEDs not used, for compatibility with Smoothieware @@ -433,69 +445,161 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const lcd_put_u8str(value); } -FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { - uint8_t pic_hot_bits; - #if HAS_HEATED_BED - const bool isBed = heater_id < 0; - const celsius_t t1 = (isBed ? thermalManager.wholeDegBed() : thermalManager.wholeDegHotend(heater_id)), - t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); - #else - const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); - #endif +#if HAS_HOTEND || HAS_HEATED_BED - #if HOTENDS < 2 - if (heater_id == H_E0) { - lcd.setCursor(2, 5); lcd.print(prefix); //HE - lcd.setCursor(1, 6); lcd.print(i16tostr3rj(t1)); - lcd.setCursor(1, 7); - } - else { - lcd.setCursor(6, 5); lcd.print(prefix); //BED - lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1)); - lcd.setCursor(6, 7); - } - #else - if (heater_id > H_BED) { - lcd.setCursor(heater_id * 4, 5); lcd.print(prefix); // HE1 or HE2 or HE3 - lcd.setCursor(heater_id * 4, 6); lcd.print(i16tostr3rj(t1)); - lcd.setCursor(heater_id * 4, 7); - } - else { - lcd.setCursor(13, 5); lcd.print(prefix); //BED - lcd.setCursor(13, 6); lcd.print(i16tostr3rj(t1)); - lcd.setCursor(13, 7); - } - #endif // HOTENDS <= 1 + FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { + uint8_t pic_hot_bits; + #if HAS_HEATED_BED + const bool isBed = heater_id < 0; + const celsius_t t1 = (isBed ? thermalManager.wholeDegBed() : thermalManager.wholeDegHotend(heater_id)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); + #else + const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); + #endif - #if !HEATER_IDLE_HANDLER - UNUSED(blink); - #else - if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { - lcd.write(' '); - if (t2 >= 10) lcd.write(' '); - if (t2 >= 100) lcd.write(' '); - } - else - #endif // !HEATER_IDLE_HANDLER - lcd.print(i16tostr3rj(t2)); + #if HOTENDS < 2 + if (heater_id == H_E0) { + lcd.setCursor(2, 5); lcd.print(prefix); //HE + lcd.setCursor(1, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(1, 7); + } + else { + lcd.setCursor(6, 5); lcd.print(prefix); //BED + lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(6, 7); + } + #else + if (heater_id > H_BED) { + lcd.setCursor(heater_id * 4, 5); lcd.print(prefix); // HE1 or HE2 or HE3 + lcd.setCursor(heater_id * 4, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(heater_id * 4, 7); + } + else { + lcd.setCursor(13, 5); lcd.print(prefix); //BED + lcd.setCursor(13, 6); lcd.print(i16tostr3rj(t1)); + lcd.setCursor(13, 7); + } + #endif // HOTENDS <= 1 - switch (heater_id) { - case H_BED: pic_hot_bits = ICON_BED; break; - case H_E0: pic_hot_bits = ICON_TEMP1; break; - case H_E1: pic_hot_bits = ICON_TEMP2; break; - case H_E2: pic_hot_bits = ICON_TEMP3; - default: break; + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd.write(' '); + if (t2 >= 10) lcd.write(' '); + if (t2 >= 100) lcd.write(' '); + } + else + #endif // !HEATER_IDLE_HANDLER + lcd.print(i16tostr3rj(t2)); + + switch (heater_id) { + case H_BED: pic_hot_bits = ICON_BED; break; + case H_E0: pic_hot_bits = ICON_TEMP1; break; + case H_E1: pic_hot_bits = ICON_TEMP2; break; + case H_E2: pic_hot_bits = ICON_TEMP3; + default: break; + } + + if (t2) picBits |= pic_hot_bits; + else picBits &= ~pic_hot_bits; + + if (t1 > 50) hotBits |= pic_hot_bits; + else hotBits &= ~pic_hot_bits; + + if (hotBits) picBits |= ICON_HOT; + else picBits &= ~ICON_HOT; } - if (t2) picBits |= pic_hot_bits; - else picBits &= ~pic_hot_bits; +#endif // HAS_HOTEND || HAS_HEATED_BED - if (t1 > 50) hotBits |= pic_hot_bits; - else hotBits &= ~pic_hot_bits; +#if HAS_COOLER - if (hotBits) picBits |= ICON_HOT; - else picBits &= ~ICON_HOT; -} + FORCE_INLINE void _draw_cooler_status(const bool blink) { + const celsius_t t2 = thermalManager.degTargetCooler(); + + lcd.setCursor(0, 5); lcd_put_u8str_P(PSTR("COOL")); + lcd.setCursor(1, 6); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); + lcd.setCursor(1, 7); + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd_put_wchar(' '); + if (t2 >= 10) lcd_put_wchar(' '); + if (t2 >= 100) lcd_put_wchar(' '); + } + else + #endif + lcd_put_u8str(i16tostr3left(t2)); + + lcd_put_wchar(' '); + if (t2 < 10) lcd_put_wchar(' '); + + if (t2) picBits |= ICON_TEMP1; + else picBits &= ~ICON_TEMP1; + } + +#endif // HAS_COOLER + +#if ENABLED(LASER_COOLANT_FLOW_METER) + + FORCE_INLINE void _draw_flowmeter_status() { + lcd.setCursor(5, 5); lcd_put_u8str_P(PSTR("FLOW")); + lcd.setCursor(7, 6); lcd_put_wchar('L'); + lcd.setCursor(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate)); + + if (cooler.flowrate) picBits |= ICON_FAN; + else picBits &= ~ICON_FAN; + } + +#endif + +#if ENABLED(I2C_AMMETER) + + FORCE_INLINE void _draw_ammeter_status() { + lcd.setCursor(10, 5); lcd_put_u8str_P(PSTR("ILAZ")); + ammeter.read(); + lcd.setCursor(11, 6); + if (ammeter.current <= 0.999f) + { + lcd_put_u8str("mA"); + lcd.setCursor(10, 7); + lcd_put_wchar(' '); lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); + } + else { + lcd_put_u8str(" A"); + lcd.setCursor(10, 7); + lcd_put_u8str(ftostr12ns(ammeter.current)); + } + + if (ammeter.current) picBits |= ICON_BED; + else picBits &= ~ICON_BED; + } + +#endif // I2C_AMMETER + +#if HAS_CUTTER + + FORCE_INLINE void _draw_cutter_status() { + lcd.setCursor(15, 5); lcd_put_u8str_P(PSTR("CUTT")); + #if CUTTER_UNIT_IS(RPM) + lcd.setCursor(16, 6); lcd_put_u8str_P(PSTR("RPM")); + lcd.setCursor(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000)); + lcd_put_wchar('K'); + #elif CUTTER_UNIT_IS(PERCENT) + lcd.setCursor(17, 6); lcd_put_wchar('%'); + lcd.setCursor(18, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + #else + lcd.setCursor(17, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower)); + #endif + + if (cutter.unitPower) picBits |= ICON_HOT; + else picBits &= ~ICON_HOT; + } + +#endif // HAS_CUTTER #if HAS_PRINT_PROGRESS @@ -533,7 +637,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *p } } -#endif +#endif // LCD_PROGRESS_BAR void MarlinUI::draw_status_message(const bool blink) { if (!PanelDetected) return; @@ -648,6 +752,19 @@ or or +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|COOL FLOW ILAZ CUTT | +| ttc L mA RPM | +| tts f.f aaa rr.rK| +| ICO ICO ICO ICO | +| ICO ICO ICO ICO | + +or + Equal to 24x10 text LCD |X 000 Y 000 Z 000.00 | @@ -745,50 +862,61 @@ void MarlinUI::draw_status_screen() { #endif // - // Line 6..8 Temperatures, FAN + // Line 6..8 Temperatures, FAN for printer or Cooler, Flowmetter, Ampermeter, Cutter for laser/spindle // - #if HOTENDS < 2 - _draw_heater_status(H_E0, "HE", blink); // Hotend Temperature - #else - _draw_heater_status(H_E0, "HE1", blink); // Hotend 1 Temperature - _draw_heater_status(H_E1, "HE2", blink); // Hotend 2 Temperature - #if HOTENDS > 2 - _draw_heater_status(H_E2, "HE3", blink); // Hotend 3 Temperature - #endif - #endif - - #if HAS_HEATED_BED - #if HAS_LEVELING - _draw_heater_status(H_BED, (planner.leveling_active && blink ? "___" : "BED"), blink); - #else - _draw_heater_status(H_BED, "BED", blink); - #endif - #endif - - #if HAS_FAN - uint16_t spd = thermalManager.fan_speed[0]; - #if ENABLED(ADAPTIVE_FAN_SLOWING) - if (!blink) spd = thermalManager.scaledFanSpeed(0, spd); - #endif - uint16_t per = thermalManager.pwmToPercent(spd); + #if HAS_HOTEND #if HOTENDS < 2 - #define FANX 11 + _draw_heater_status(H_E0, "HE", blink); // Hotend Temperature #else - #define FANX 17 + _draw_heater_status(H_E0, "HE1", blink); // Hotend 1 Temperature + _draw_heater_status(H_E1, "HE2", blink); // Hotend 2 Temperature + #if HOTENDS > 2 + _draw_heater_status(H_E2, "HE3", blink); // Hotend 3 Temperature + #endif #endif - lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); - lcd.setCursor(FANX + 1, 6); lcd.write('%'); - lcd.setCursor(FANX, 7); - lcd.print(i16tostr3rj(per)); - if (TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2])) - picBits |= ICON_FAN; - else - picBits &= ~ICON_FAN; + #if HAS_HEATED_BED + #if HAS_LEVELING + _draw_heater_status(H_BED, (planner.leveling_active && blink ? "___" : "BED"), blink); + #else + _draw_heater_status(H_BED, "BED", blink); + #endif + #endif - #endif // HAS_FAN + #if HAS_FAN + uint16_t spd = thermalManager.fan_speed[0]; + #if ENABLED(ADAPTIVE_FAN_SLOWING) + if (!blink) spd = thermalManager.scaledFanSpeed(0, spd); + #endif + uint16_t per = thermalManager.pwmToPercent(spd); + + #if HOTENDS < 2 + #define FANX 11 + #else + #define FANX 17 + #endif + lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); + lcd.setCursor(FANX + 1, 6); lcd.write('%'); + lcd.setCursor(FANX, 7); + lcd.print(i16tostr3rj(per)); + + if (TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2])) + picBits |= ICON_FAN; + else + picBits &= ~ICON_FAN; + + #endif // HAS_FAN + + #else + + TERN_(HAS_COOLER, _draw_cooler_status(blink)); + TERN_(LASER_COOLANT_FLOW_METER, _draw_flowmeter_status()); + TERN_(I2C_AMMETER, _draw_ammeter_status()); + TERN_(HAS_CUTTER, _draw_cutter_status()); + + #endif // // Line 9, 10 - icons From 154decfc66c30808cfe7320e542fcf90427d7176 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 19 Jul 2021 18:59:06 -0600 Subject: [PATCH 0425/2168] Update vector_3.cpp Fix the regression for G29 J in UBL --- Marlin/src/libs/vector_3.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index b8202217dd..4db8fb5f2e 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -104,9 +104,9 @@ matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &r //row_1.debug(PSTR("row_1")); //row_2.debug(PSTR("row_2")); matrix_3x3 new_matrix; - new_matrix.vectors[0].x = row_0.x; new_matrix.vectors[1].y = row_0.y; new_matrix.vectors[2].z = row_0.z; - new_matrix.vectors[3].x = row_1.x; new_matrix.vectors[4].y = row_1.y; new_matrix.vectors[5].z = row_1.z; - new_matrix.vectors[6].x = row_2.x; new_matrix.vectors[7].y = row_2.y; new_matrix.vectors[8].z = row_2.z; + new_matrix.vectors[0] = row_0; + new_matrix.vectors[1] = row_1; + new_matrix.vectors[2] = row_2; //new_matrix.debug(PSTR("new_matrix")); return new_matrix; } From 3fdf40fd29099025bd6aa81413222aaef0058439 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 20 Jul 2021 01:04:54 +0000 Subject: [PATCH 0426/2168] [cron] Bump distribution date (2021-07-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ea80f51d28..d559910437 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-19" +//#define STRING_DISTRIBUTION_DATE "2021-07-20" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 29249b0b9b..ea126d2855 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 "2021-07-19" + #define STRING_DISTRIBUTION_DATE "2021-07-20" #endif /** From da0450605a31626f423808c4842256671152c489 Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Tue, 20 Jul 2021 12:20:28 -0700 Subject: [PATCH 0427/2168] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20STM32?= =?UTF-8?q?=20ini=20files=20(#22377)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../boards/marlin_STEVAL_STM32F401VE.json | 2 +- .../boards/marlin_blackSTM32F407VET6.json | 2 +- ini/stm32-common.ini | 41 ++ ini/stm32f0.ini | 10 +- ini/stm32f1.ini | 392 ++++++++---------- ini/stm32f4.ini | 318 +++++++------- ini/stm32f7.ini | 26 -- ini/stm32h7.ini | 41 ++ platformio.ini | 2 + 9 files changed, 411 insertions(+), 423 deletions(-) create mode 100644 ini/stm32-common.ini create mode 100644 ini/stm32h7.ini diff --git a/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json b/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json index e89ca0af73..e260950f25 100644 --- a/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json +++ b/buildroot/share/PlatformIO/boards/marlin_STEVAL_STM32F401VE.json @@ -2,7 +2,7 @@ "build": { "core": "stm32", "cpu": "cortex-m4", - "extra_flags": "-DSTM32F401xx", + "extra_flags": "-DSTM32F401xx -DARDUINO_STEVAL", "f_cpu": "84000000L", "hwids": [ [ diff --git a/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json index a3f130c6b1..b0fd9db939 100644 --- a/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json +++ b/buildroot/share/PlatformIO/boards/marlin_blackSTM32F407VET6.json @@ -2,7 +2,7 @@ "build": { "core": "stm32", "cpu": "cortex-m4", - "extra_flags": "-DSTM32F407xx", + "extra_flags": "-DSTM32F407xx -DARDUINO_BLACK_F407VE", "f_cpu": "168000000L", "hwids": [ [ diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini new file mode 100644 index 0000000000..4ae068939e --- /dev/null +++ b/ini/stm32-common.ini @@ -0,0 +1,41 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +#################################### +# +# HAL/STM32 Common Environments +# +#################################### + +[common_stm32] +platform = ststm32@~12.1 +board_build.core = stm32 +build_flags = ${common.build_flags} + -std=gnu++14 + -DUSBCON -DUSBD_USE_CDC + -DTIM_IRQ_PRIO=13 + -DADC_RESOLUTION=12 +build_unflags = -std=gnu++11 +src_filter = ${common.default_src_filter} + + +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py + +# +# STM32 board based on a variant. +# +[stm32_variant] +extends = common_stm32 +extra_scripts = ${common_stm32.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/offset_and_rename.py + +# +# USB Flash Drive mix-ins for STM32 +# +[stm_flash_drive] +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED + -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index 64568e4b4c..6aebd88298 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -27,8 +27,8 @@ platform = ${common_stm32.platform} extends = common_stm32 board = marlin_malyanM200v2 build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED - -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing - -DCUSTOM_STARTUP_FILE + -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants + -fno-strict-aliasing -DCUSTOM_STARTUP_FILE # # Malyan M200 v2 (STM32F070CB) @@ -38,7 +38,8 @@ platform = ${common_stm32.platform} extends = common_stm32 board = malyanm200_f070cb build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -DCUSTOM_STARTUP_FILE + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED -DCUSTOM_STARTUP_FILE # # Malyan M300 (STM32F070CB) @@ -48,5 +49,6 @@ platform = ${common_stm32.platform} extends = common_stm32 board = malyanm300_f070cb build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index f487dc62fc..0f1d308660 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -10,70 +10,48 @@ # Naming Example: STM32F103RCT6 # # F : Foundation (sometimes High Performance F2/F4) -# 1 : Cortex M1 core +# 1 : Cortex M3 core # 03 : Line/Features -# R : 64 or 66 pins (V:100, Z:144, I:176) -# C : 256KB Flash-memory (D:384KB, E:512KB, G:1024KB) +# R : 64 or 66 pins (T:36, C:48, V:100, Z:144, I:176) +# C : 256KB Flash-memory (B: 128KB, D:384KB, E:512KB, G:1024KB) # T : LQFP package # 6 : -40...85°C (7: ...105°C) # ################################# -# -# HAL/STM32 Base Environment values -# -[common_stm32] -platform = ststm32@~12.1 -build_flags = ${common.build_flags} - -std=gnu++14 - -DUSBCON -DUSBD_USE_CDC - -DTIM_IRQ_PRIO=13 - -DADC_RESOLUTION=12 -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + + -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py - -[stm32f1_variant] -extra_scripts = ${common_stm32.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py - buildroot/share/PlatformIO/scripts/offset_and_rename.py - -[common_STM32F103RC] -platform = ${common_stm32.platform} -extends = common_stm32 +[common_STM32F103RC_variant] +extends = stm32_variant board = genericSTM32F103RC -monitor_speed = 115200 -board_build.core = stm32 board_build.variant = MARLIN_F103Rx -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} -DDEBUG_LEVEL=0 +monitor_speed = 115200 # # STM32F103RE # [env:STM32F103RE] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103RE -monitor_speed = 115200 +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103RE +monitor_speed = 115200 # # STM32F103VE # [env:STM32F103VE] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103VE -monitor_speed = 115200 +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +monitor_speed = 115200 # # STM32F103ZE # [env:STM32F103ZE] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103ZE -monitor_speed = 115200 +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +monitor_speed = 115200 # # BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) @@ -82,23 +60,23 @@ monitor_speed = 115200 # STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) # [env:STM32F103RC_btt] -platform = ${common_stm32.platform} -extends = common_STM32F103RC -build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 -board_build.offset = 0x7000 +platform = ${common_stm32.platform} +extends = common_STM32F103RC_variant +build_flags = ${common_STM32F103RC_variant.build_flags} + -DTIMER_SERVO=TIM5 +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 [env:STM32F103RC_btt_USB] -extends = env:STM32F103RC_btt platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip +extends = env:STM32F103RC_btt +platform_packages = ${stm_flash_drive.platform_packages} +build_flags = ${env:STM32F103RC_btt.build_flags} + -DUSE_USB_FS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSBD_USE_CDC_MSC build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC -build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.build_flags} - -DUSBCON - -DUSE_USB_FS - -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 - -DUSBD_USE_CDC_MSC # # MKS Robin (STM32F103ZET6) @@ -106,52 +84,53 @@ build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.b # [env:mks_robin] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = genericSTM32F103ZE -board_build.core = stm32 board_build.variant = MARLIN_F103Zx -board_build.offset = 0x7000 board_build.encrypt = Robin.bin -build_flags = ${common_stm32.build_flags} - -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 -build_unflags = ${common_stm32.build_unflags} - -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32f1_variant.extra_scripts} -lib_deps = +board_build.offset = 0x7000 +build_flags = ${stm32_variant.build_flags} + -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC # # MKS Robin E3/E3D (STM32F103RCT6) with TMC2209 # [env:mks_robin_e3] platform = ${common_stm32.platform} -extends = common_STM32F103RC -build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 -DDEFAULT_SPI=3 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -monitor_speed = 115200 -board_build.offset = 0x5000 +extends = common_STM32F103RC_variant board_build.encrypt = Robin_e3.bin +board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 +build_flags = ${common_STM32F103RC_variant.build_flags} + -DTIMER_SERVO=TIM5 -DDEFAULT_SPI=3 +build_unflags = ${common_STM32F103RC_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC +monitor_speed = 115200 debug_tool = stlink -extra_scripts = ${common_STM32F103RC.extra_scripts} # # Creality (STM32F103RET6) # [env:STM32F103RET6_creality] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 -board = genericSTM32F103RE -monitor_speed = 115200 -board_build.core = stm32 -board_build.variant = MARLIN_F103Rx -board_build.offset = 0x7000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103RE +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32f1_variant.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py -debug_tool = jlink -upload_protocol = jlink +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED + -DSS_TIMER=4 -DTIMER_SERVO=TIM5 + -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${stm32_variant.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py +monitor_speed = 115200 +debug_tool = jlink +upload_protocol = jlink # # BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) @@ -160,80 +139,79 @@ upload_protocol = jlink # STM32F103RE_btt_USB ......... RET6 (USB mass storage) # [env:STM32F103RE_btt] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 -board = genericSTM32F103RE -monitor_speed = 115200 -board_build.core = stm32 -board_build.variant = MARLIN_F103Rx -board_build.offset = 0x7000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103RE +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -build_unflags = ${common_stm32.build_unflags} -extra_scripts = ${stm32f1_variant.extra_scripts} -debug_tool = jlink -upload_protocol = jlink +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED + -DSS_TIMER=4 -DTIMER_SERVO=TIM5 + -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +monitor_speed = 115200 +debug_tool = jlink +upload_protocol = jlink [env:STM32F103RE_btt_USB] -extends = env:STM32F103RE_btt platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip -build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC -build_flags = ${env:STM32F103RE_btt.build_flags} ${env:stm32_flash_drive.build_flags} - -DUSBCON - -DUSE_USB_FS - -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 - -DUSBD_USE_CDC_MSC +extends = env:STM32F103RE_btt +platform_packages = ${stm_flash_drive.platform_packages} +build_flags = ${env:STM32F103RE_btt.build_flags} + -DUSE_USB_FS -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 -DUSBD_USE_CDC_MSC +build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC # # FLSUN QQS Pro (STM32F103VET6) # board Hispeedv1 # [env:flsun_hispeedv1] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 -board = genericSTM32F103VE -board_build.core = stm32 -board_build.variant = MARLIN_F103Vx -board_build.offset = 0x7000 -board_build.encrypt = Robin_mini.bin +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +board_build.encrypt = Robin_mini.bin +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 + -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC # # MKS Robin Nano V1.2 and V2 # [env:mks_robin_nano35] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 -board = genericSTM32F103VE -board_build.core = stm32 -board_build.variant = MARLIN_F103Vx -board_build.offset = 0x7000 -board_build.encrypt = Robin_nano35.bin +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +board_build.encrypt = Robin_nano35.bin +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -debug_tool = jlink -upload_protocol = jlink -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 + -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC +debug_tool = jlink +upload_protocol = jlink # # Mingda MPX_ARM_MINI # [env:mingda_mpx_arm_mini] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = genericSTM32F103ZE -board_build.core = stm32 board_build.variant = MARLIN_F103Zx board_build.offset = 0x10000 -build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC # # Malyan M200 (STM32F103CB) @@ -243,67 +221,55 @@ platform = ${common_stm32.platform} extends = common_stm32 board = malyanm200_f103cb build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + # # FLYmaker FLY Mini (STM32F103RCT6) # [env:FLY_MINI] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DSS_TIMER=4 -board = genericSTM32F103RC -board_build.core = stm32 -board_build.variant = MARLIN_F103Rx -board_build.offset = 0x5000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103RC +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} -DSS_TIMER=4 # # MKS Robin Mini (STM32F103VET6) # [env:mks_robin_mini] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103VE -board_build.core = stm32 -board_build.variant = MARLIN_F103Vx -board_build.offset = 0x7000 -board_build.encrypt = Robin_mini.bin -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +board_build.encrypt = Robin_mini.bin +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -extra_scripts = ${stm32f1_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103VE -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 # # MKS Robin Lite/Lite2 (STM32F103RCT6) # [env:mks_robin_lite] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103RC -board_build.core = stm32 -board_build.variant = MARLIN_F103Rx -board_build.offset = 0x5000 -board_build.encrypt = mksLite.bin -build_flags = ${common_stm32.build_flags} +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103RC +board_build.variant = MARLIN_F103Rx +board_build.encrypt = mksLite.bin +board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 -extra_scripts = ${stm32f1_variant.extra_scripts} # # MKS ROBIN LITE3 (STM32F103RCT6) # [env:mks_robin_lite3] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103RC -board_build.core = stm32 -board_build.variant = MARLIN_F103Rx -board_build.offset = 0x5000 -board_build.encrypt = mksLite3.bin -build_flags = ${common_stm32.build_flags} -board_upload.offset_address = 0x08005000 -extra_scripts = ${stm32f1_variant.extra_scripts} +platform = ${common_stm32.platform} +extends = env:mks_robin_lite +board_build.encrypt = mksLite3.bin # # MKS Robin Pro (STM32F103ZET6) @@ -318,44 +284,43 @@ board_build.encrypt = Robin_pro.bin # - LVGL UI # [env:mks_robin_e3p] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103VE -board_build.core = stm32 -board_build.variant = MARLIN_F103Vx -board_build.offset = 0x7000 -board_build.encrypt = Robin_e3p.bin -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +board_build.encrypt = Robin_e3p.bin +board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 -extra_scripts = ${stm32f1_variant.extra_scripts} -debug_tool = jlink -upload_protocol = jlink +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 + -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 +debug_tool = jlink +upload_protocol = jlink # # JGAurora A5S A1 (STM32F103ZET6) # [env:jgaurora_a5s_a1] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103ZE -board_build.core = stm32 -board_build.variant = MARLIN_F103Zx -board_build.offset = 0xA000 -board_build.rename = firmware_for_sd_upload.bin -build_flags = ${common_stm32.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY -board_build.address = 0x0800A000 -extra_scripts = ${stm32f1_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103ZE +board_build.variant = MARLIN_F103Zx +board_build.offset = 0xA000 +board_build.rename = firmware_for_sd_upload.bin +board_upload.offset_address = 0x0800A000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py # # FYSETC STM32F103RC # [env:STM32F103RC_fysetc] platform = ${common_stm32.platform} -extends = common_STM32F103RC -extra_scripts = ${stm32f1_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 +extends = common_STM32F103RC_variant +extra_scripts = ${common_STM32F103RC_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py lib_ldf_mode = chain debug_tool = stlink upload_protocol = serial @@ -364,20 +329,20 @@ upload_protocol = serial # Longer 3D board in Alfawise U20 (STM32F103VET6) # [env:STM32F103VE_longer] -platform = ${common_stm32.platform} -extends = common_stm32 -board = genericSTM32F103VE -board_build.core = stm32 -board_build.variant = MARLIN_F103Vx -board_build.offset = 0x10000 -board_build.address = 0x08010000 -build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 - -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA -UPIN_WIRE_SCL -DPIN_WIRE_SDA=PB11 -DPIN_WIRE_SCL=PB10 - -DHAL_DAC_MODULE_DISABLED -DHAL_I2S_MODULE_DISABLED -build_unflags = ${common_stm32.build_unflags} - -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED -extra_scripts = ${stm32f1_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F103VE -DU20 -DTS_V12 -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA + -UPIN_WIRE_SCL -DPIN_WIRE_SDA=PB11 -DPIN_WIRE_SCL=PB10 + -DHAL_DAC_MODULE_DISABLED -DHAL_I2S_MODULE_DISABLED +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py # # TRIGORILLA PRO (STM32F103ZET6) @@ -392,15 +357,16 @@ extra_scripts = ${common_stm32.extra_scripts} # [env:chitu_f103] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = genericSTM32F103ZE -board_build.core = stm32 board_build.variant = MARLIN_F103Zx -extra_scripts = ${stm32f1_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/chitu_crypt.py -build_flags = ${common_stm32.build_flags} -DSTM32_XL_DENSITY -build_unflags = ${common_stm32.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +build_flags = ${stm32_variant.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY +build_unflags = ${stm32_variant.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= + -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/chitu_crypt.py # # Some Chitu V5 boards have a problem with GPIO init. diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index ada6605e07..f9c16cf455 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -12,8 +12,8 @@ # F : Foundation (sometimes High Performance F2/F4) # 4 : Cortex M4 core # 01 : Line/Features -# R : 64 or 66 pins (V:100, Z:144, I:176) -# G : 1024KB Flash-memory (C:256KB, D:384KB, E:512KB) +# R : 64 or 66 pins (T:36, C:48 or 49, M:81, V:100, Z:144, I:176) +# G : 1024KB Flash-memory (B:128KB, C:256KB, D:384KB, E:512KB) # T : LQFP package # 6 : -40...85°C (7: ...105°C) # @@ -27,12 +27,7 @@ platform = ${common_stm32.platform} extends = common_stm32 board = armed_v1 build_flags = ${common_stm32.build_flags} - -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing - -[stm32f4_variant] -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py - buildroot/share/PlatformIO/scripts/offset_and_rename.py + -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing # # STM32F401VE @@ -40,49 +35,46 @@ extra_scripts = ${common.extra_scripts} # [env:STM32F401VE_STEVAL] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = marlin_STEVAL_STM32F401VE -build_flags = ${common_stm32.build_flags} - -DARDUINO_STEVAL -DSTM32F401xE - -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS -extra_scripts = ${stm32f4_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DSTM32F401xE -DDISABLE_GENERIC_SERIALUSB + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS # # STM32F401RC # [env:FYSETC_CHEETAH_V20] -platform = ${common_stm32.platform} -extends = common_stm32 -board = marlin_FYSETC_CHEETAH_V20 -build_flags = ${common_stm32.build_flags} -DSTM32F401xC -DVECT_TAB_OFFSET=0xC000 -extra_scripts = ${stm32f4_variant.extra_scripts} +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_FYSETC_CHEETAH_V20 +board_build.offset = 0xC000 +build_flags = ${stm32_variant.build_flags} -DSTM32F401xC # # FLYF407ZG # [env:FLYF407ZG] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_FLY_F407ZG +board_build.offset = 0x8000 upload_protocol = dfu -build_flags = ${common_stm32.build_flags} - -DVECT_TAB_OFFSET=0x8000 -extra_scripts = ${stm32f4_variant.extra_scripts} # # FYSETC S6 (STM32F446RET6 ARM Cortex-M4) # [env:FYSETC_S6] -platform = ${common_stm32.platform} -extends = common_stm32 -platform_packages = tool-stm32duino -board = marlin_fysetc_s6 -build_flags = ${common_stm32.build_flags} -DVECT_TAB_OFFSET=0x10000 -DHAL_PCD_MODULE_ENABLED -extra_scripts = ${stm32f4_variant.extra_scripts} -debug_tool = stlink -upload_protocol = dfu -upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_fysetc_s6 +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 +build_flags = ${stm32_variant.build_flags} -DHAL_PCD_MODULE_ENABLED +debug_tool = stlink +upload_protocol = dfu +upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" # # FYSETC S6 new bootloader @@ -93,8 +85,6 @@ extends = env:FYSETC_S6 board = marlin_fysetc_s6_8000 board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 -build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -extra_scripts = ${stm32f4_variant.extra_scripts} upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" # @@ -104,12 +94,10 @@ upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" # [env:STM32F407VE_black] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = marlin_blackSTM32F407VET6 -build_flags = ${common_stm32.build_flags} - -DARDUINO_BLACK_F407VE - -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS -extra_scripts = ${stm32f4_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS # # Anet ET4-MB_V1.x/ET4P-MB_V1.x (STM32F407VGT6 ARM Cortex-M4) @@ -117,120 +105,108 @@ extra_scripts = ${stm32f4_variant.extra_scripts} # Comment out board_build.offset = 0x10000 if you don't plan to use OpenBLT/flashing directly to 0x08000000. # [env:Anet_ET4_OpenBLT] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} -DHAL_SD_MODULE_ENABLED -DHAL_SRAM_MODULE_ENABLED -board = marlin_STM32F407VGT6_CCM -board_build.core = stm32 -board_build.variant = MARLIN_F4x7Vx -board_build.encrypt = firmware.srec -board_build.offset = 0x10000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_STM32F407VGT6_CCM +board_build.variant = MARLIN_F4x7Vx +board_build.encrypt = firmware.srec +board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -debug_tool = jlink -upload_protocol = jlink -extra_scripts = ${stm32f4_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/openblt.py +build_flags = ${stm32_variant.build_flags} + -DHAL_SD_MODULE_ENABLED -DHAL_SRAM_MODULE_ENABLED +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/openblt.py +debug_tool = jlink +upload_protocol = jlink # # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) # [env:BIGTREE_SKR_PRO] -platform = ${common_stm32.platform} -extends = common_stm32 -board = marlin_BigTree_SKR_Pro -build_flags = ${common_stm32.build_flags} - -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 -extra_scripts = ${stm32f4_variant.extra_scripts} -#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 -debug_init_break = - -# -# USB Flash Drive mix-ins for STM32 -# -[stm_flash_drive] -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip -build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED - -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_BigTree_SKR_Pro +board_build.offset = 0x8000 +build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX +debug_tool = stlink +upload_protocol = stlink # # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_PRO_usb_flash_drive] +platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_PRO platform_packages = ${stm_flash_drive.platform_packages} -build_unflags = -DUSBCON -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} - -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 +build_flags = ${stm_flash_drive.build_flags} -DSTM32F407_5ZX +build_unflags = ${env:BIGTREE_SKR_PRO.build_unflags} -DUSBCON -DUSBD_USE_CDC # # BigTreeTech E3 RRF (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_E3_RRF] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_BIGTREE_E3_RRF -build_flags = ${common_stm32.build_flags} - -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 - -DSERIAL_RX_BUFFER_SIZE=255 -DSERIAL_TX_BUFFER_SIZE=255 -extra_scripts = ${stm32f4_variant.extra_scripts} +board_build.offset = 0x8000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F407_5VX + -DSERIAL_RX_BUFFER_SIZE=255 + -DSERIAL_TX_BUFFER_SIZE=255 # # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) # [env:BIGTREE_GTR_V1_0] -platform = ${common_stm32.platform} -extends = common_stm32 -board = marlin_BigTree_GTR_v1 -extra_scripts = ${stm32f4_variant.extra_scripts} -build_flags = ${common_stm32.build_flags} - -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_BigTree_GTR_v1 +board_build.offset = 0x8000 +build_flags = ${stm32_variant.build_flags} -DSTM32F407IX # # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_GTR_V1_0_usb_flash_drive] +platform = ${common_stm32.platform} extends = env:BIGTREE_GTR_V1_0 platform_packages = ${stm_flash_drive.platform_packages} -build_unflags = -DUSBCON -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} - -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 +build_flags = ${stm_flash_drive.build_flags} -DSTM32F407IX +build_unflags = ${env:BIGTREE_GTR_V1_0.build_unflags} -DUSBCON -DUSBD_USE_CDC # # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_BTT002] -platform = ${common_stm32.platform} -extends = common_stm32 -board = marlin_BigTree_BTT002 -build_flags = ${common_stm32.build_flags} - -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 - -DHAVE_HWSERIAL2 - -DHAVE_HWSERIAL3 - -DPIN_SERIAL2_RX=PD_6 - -DPIN_SERIAL2_TX=PD_5 -extra_scripts = ${stm32f4_variant.extra_scripts} +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_BigTree_BTT002 +board_build.offset = 0x8000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F407_5VX + -DHAVE_HWSERIAL2 + -DHAVE_HWSERIAL3 + -DPIN_SERIAL2_RX=PD_6 + -DPIN_SERIAL2_TX=PD_5 # # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_2] -platform = ${common_stm32.platform} -platform_packages = ${stm_flash_drive.platform_packages} -extends = common_stm32 -board = marlin_STM32F407VGT6_CCM -board_build.core = stm32 -board_build.variant = MARLIN_F4x7Vx -board_build.offset = 0x8000 +platform = ${common_stm32.platform} +extends = stm32_variant +platform_packages = ${stm_flash_drive.platform_packages} +board = marlin_STM32F407VGT6_CCM +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 -extra_scripts = ${stm32f4_variant.extra_scripts} -build_flags = ${stm_flash_drive.build_flags} - -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 - -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED +build_flags = ${stm_flash_drive.build_flags} + -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS + -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 + -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED # # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Media Share Support @@ -238,49 +214,50 @@ build_flags = ${stm_flash_drive.build_flags} [env:BIGTREE_SKR_2_USB] platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_2 -platform_packages = ${stm_flash_drive.platform_packages} -build_unflags = -DUSBD_USE_CDC build_flags = ${env:BIGTREE_SKR_2.build_flags} -DUSBD_USE_CDC_MSC +build_unflags = ${env:BIGTREE_SKR_2.build_unflags} -DUSBD_USE_CDC # # BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) # [env:BIGTREE_OCTOPUS_V1] -platform = ${common_stm32.platform} -extends = common_stm32 -board = marlin_BigTree_Octopus_v1 -extra_scripts = ${stm32f4_variant.extra_scripts} -build_flags = ${common_stm32.build_flags} - -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 -DUSE_USB_HS_IN_FS +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_BigTree_Octopus_v1 +board_build.offset = 0x8000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F446_5VX -DUSE_USB_HS_IN_FS # # BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_OCTOPUS_V1_USB] +platform = ${common_stm32.platform} extends = env:BIGTREE_OCTOPUS_V1 platform_packages = ${stm_flash_drive.platform_packages} -#build_unflags = -DUSBCON -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} - -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 - -DUSBCON -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DUSE_USB_HS_IN_FS -DUSBD_USE_CDC_MSC + -DSTM32F446_5VX -DUSE_USB_HS_IN_FS + -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSBD_USE_CDC_MSC # # Lerdge base # [lerdge_common] platform = ${common_stm32.platform} -extends = common_stm32 +extends = stm32_variant board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_LERDGE -board_build.offset = 0x10000 board_build.encrypt = firmware.bin -extra_scripts = ${stm32f4_variant.extra_scripts} +board_build.offset = 0x10000 +build_flags = ${stm32_variant.build_flags} + -DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4 + -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DARDUINO_LERDGE + -DHAL_SRAM_MODULE_ENABLED +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 +extra_scripts = ${stm32_variant.extra_scripts} buildroot/share/PlatformIO/scripts/lerdge.py -build_flags = ${common_stm32.build_flags} - -DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4 - -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DARDUINO_LERDGE - -DHAL_SRAM_MODULE_ENABLED -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 # # Lerdge X @@ -339,38 +316,33 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # [env:rumba32] platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} - -Os - -DHAL_PCD_MODULE_ENABLED - -DDISABLE_GENERIC_SERIALUSB - -DHAL_UART_MODULE_ENABLED - -DTIMER_SERIAL=TIM9 +extends = stm32_variant board = rumba32_f446ve -upload_protocol = dfu -monitor_speed = 500000 -board_build.core = stm32 board_build.variant = MARLIN_F446VE board_build.offset = 0x0000 -extra_scripts = ${stm32f4_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} + -Os -DHAL_PCD_MODULE_ENABLED + -DDISABLE_GENERIC_SERIALUSB + -DHAL_UART_MODULE_ENABLED + -DTIMER_SERIAL=TIM9 +monitor_speed = 500000 +upload_protocol = dfu # # MKS Robin Pro V2 # [env:mks_robin_pro2] -platform = ${common_stm32.platform} -platform_packages = ${stm_flash_drive.platform_packages} -extends = common_stm32 -build_flags = ${stm_flash_drive.build_flags} -board = genericSTM32F407VET6 -board_build.core = stm32 -board_build.variant = MARLIN_F4x7Vx -board_build.offset = 0x0000 +platform = ${common_stm32.platform} +extends = stm32_variant +platform_packages = ${stm_flash_drive.platform_packages} +board = genericSTM32F407VET6 +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 -build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -debug_tool = jlink -upload_protocol = jlink -extra_scripts = ${stm32f4_variant.extra_scripts} +build_flags = ${stm_flash_drive.build_flags} +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC +debug_tool = jlink +upload_protocol = jlink # # This SPI is used by Robin Nano V3 @@ -382,34 +354,31 @@ build_flags = -DPIN_WIRE_SCL=PB6 -DPIN_WIRE_SDA=PB7 # MKS Robin Nano V3 # [env:mks_robin_nano_v3] -platform = ${common_stm32.platform} -extends = common_stm32 -build_flags = ${common_stm32.build_flags} ${stm32f4_I2C1.build_flags} -DHAL_PCD_MODULE_ENABLED -DUSBCON -DUSBD_USE_CDC -board = marlin_STM32F407VGT6_CCM -board_build.core = stm32 -board_build.variant = MARLIN_F4x7Vx -board_build.rename = Robin_nano_v3.bin -board_build.offset = 0xC000 +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_STM32F407VGT6_CCM +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0xC000 +board_build.rename = Robin_nano_v3.bin board_upload.offset_address = 0x0800C000 -build_unflags = ${common_stm32.build_unflags} -debug_tool = jlink -upload_protocol = jlink -extra_scripts = ${stm32f4_variant.extra_scripts} +build_flags = ${stm32_variant.build_flags} ${stm32f4_I2C1.build_flags} + -DHAL_PCD_MODULE_ENABLED +debug_tool = jlink +upload_protocol = jlink # # MKS Robin Nano V3 with USB Flash Drive Support # Currently, using a STM32duino fork, until USB Host get merged # [env:mks_robin_nano_v3_usb_flash_drive] +platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3 platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} - -DUSBCON - -DUSE_USBHOST_HS - -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 - -DUSE_USB_HS_IN_FS - -DUSBD_USE_CDC + -DUSE_USBHOST_HS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSE_USB_HS_IN_FS # # MKS Robin Nano V3 with USB Flash Drive Support and Shared Media @@ -417,13 +386,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} # [env:mks_robin_nano_v3_usb_flash_drive_msc] platform = ${common_stm32.platform} -extends = env:mks_robin_nano_v3 -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip -build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} - -DUSBCON - -DUSE_USBHOST_HS - -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 - -DUSE_USB_HS_IN_FS - -DUSBD_USE_CDC_MSC +extends = env:mks_robin_nano_v3_usb_flash_drive +build_flags = ${env:mks_robin_nano_v3_usb_flash_drive} + -DUSBD_USE_CDC_MSC diff --git a/ini/stm32f7.ini b/ini/stm32f7.ini index 76d039533c..984b25162e 100644 --- a/ini/stm32f7.ini +++ b/ini/stm32f7.ini @@ -37,29 +37,3 @@ build_flags = ${common_stm32.build_flags} -DTIMER_SERIAL=TIM9 platform = ${common_stm32.platform} extends = common_stm32 board = remram_v1 -build_flags = ${common_stm32.build_flags} - -# -# BigTreeTech SKR SE BX (STM32H743IIT6 ARM Cortex-M7) -# -[env:BTT_SKR_SE_BX] -platform = ${common_stm32.platform} -platform_packages = ${stm_flash_drive.platform_packages} -extends = common_stm32 -board = marlin_BTT_SKR_SE_BX -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -build_flags = ${common_stm32.build_flags} - ${stm_flash_drive.build_flags} - -DUSE_USBHOST_HS - -DUSE_USB_HS_IN_FS - #-DUSBD_USE_CDC_MSC - -DVECT_TAB_OFFSET=0x20000 - -DHAL_DMA2D_MODULE_ENABLED - -DHAL_LTDC_MODULE_ENABLED - -DHAL_SDRAM_MODULE_ENABLED - -DHAL_QSPI_MODULE_ENABLED - -DHAL_MDMA_MODULE_ENABLED - -DHAL_SD_MODULE_ENABLED -upload_protocol = cmsis-dap -debug_tool = cmsis-dap diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini new file mode 100644 index 0000000000..3d0753a235 --- /dev/null +++ b/ini/stm32h7.ini @@ -0,0 +1,41 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +################################# +# +# STM32H7 Architecture +# +# Naming Example: STM32H743IIT6 +# +# H : High Performance +# 7 : Cortex M7 core +# 43 : Line/Features +# I : 176 pins +# I : 2048KB Flash-memory +# T : LQFP package +# 6 : -40...85°C (7: ...105°C) +# +################################# + +# +# BigTreeTech SKR SE BX (STM32H743IIT6 ARM Cortex-M7) +# +[env:BTT_SKR_SE_BX] +platform = ${common_stm32.platform} +extends = stm32_variant +platform_packages = ${stm_flash_drive.platform_packages} +board = marlin_BTT_SKR_SE_BX +board_build.offset = 0x20000 +build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} + -DUSE_USBHOST_HS + -DUSE_USB_HS_IN_FS + -DHAL_DMA2D_MODULE_ENABLED + -DHAL_LTDC_MODULE_ENABLED + -DHAL_SDRAM_MODULE_ENABLED + -DHAL_QSPI_MODULE_ENABLED + -DHAL_MDMA_MODULE_ENABLED + -DHAL_SD_MODULE_ENABLED +upload_protocol = cmsis-dap +debug_tool = cmsis-dap diff --git a/platformio.ini b/platformio.ini index afdd823f9e..1fb9ba55e6 100644 --- a/platformio.ini +++ b/platformio.ini @@ -23,11 +23,13 @@ extra_configs = ini/lpc176x.ini ini/native.ini ini/samd51.ini + ini/stm32-common.ini ini/stm32f0.ini ini/stm32f1-maple.ini ini/stm32f1.ini ini/stm32f4.ini ini/stm32f7.ini + ini/stm32h7.ini ini/teensy.ini # From 178f9a77a88b333470725e0e19d033859721656b Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 21 Jul 2021 07:44:15 +1200 Subject: [PATCH 0428/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STATUS=5FCOMBINE?= =?UTF-8?q?=5FHEATERS=20compile=20(#22405)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 42 ++++++++++++---------- 1 file changed, 23 insertions(+), 19 deletions(-) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index a66aca6d19..5fe8b61bf4 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -264,29 +264,33 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #define HOTEND_BITMAP(N,S) status_hotend_a_bmp #endif - if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { + #if DISABLED(STATUS_COMBINE_HEATERS) - #define BAR_TALL (STATUS_HEATERS_HEIGHT - 2) + if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { - const float prop = target - 20, - perc = prop > 0 && temp >= 20 ? (temp - 20) / prop : 0; - uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); - NOMORE(tall, BAR_TALL); + #define BAR_TALL (STATUS_HEATERS_HEIGHT - 2) - // Draw hotend bitmap, either whole or split by the heating percent - const uint8_t hx = STATUS_HOTEND_X(heater_id), - bw = STATUS_HOTEND_BYTEWIDTH(heater_id); - #if ENABLED(STATUS_HEAT_PERCENT) - if (isHeat && tall <= BAR_TALL) { - const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); - } - else - #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); + const float prop = target - 20, + perc = prop > 0 && temp >= 20 ? (temp - 20) / prop : 0; + uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); + NOMORE(tall, BAR_TALL); - } // PAGE_CONTAINS + // Draw hotend bitmap, either whole or split by the heating percent + const uint8_t hx = STATUS_HOTEND_X(heater_id), + bw = STATUS_HOTEND_BYTEWIDTH(heater_id); + #if ENABLED(STATUS_HEAT_PERCENT) + if (isHeat && tall <= BAR_TALL) { + const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); + } + else + #endif + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); + + } // PAGE_CONTAINS + + #endif // !STATUS_COMBINE_HEATERS if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER From 497541e1995db4e9890abc0951e0a77104bc62ef Mon Sep 17 00:00:00 2001 From: Yash <76577754+yash-fn@users.noreply.github.com> Date: Tue, 20 Jul 2021 14:51:41 -0500 Subject: [PATCH 0429/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20G2/G3=20angular?= =?UTF-8?q?=20motion=20calculation=20(#22407)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/motion/G2_G3.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 170789d827..094afdb70e 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -83,12 +83,13 @@ void plan_arc( #endif // Angle of rotation between position and target from the circle center. - float angular_travel; + float angular_travel, abs_angular_travel; // Do a full circle if starting and ending positions are "identical" if (NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { // Preserve direction for circles angular_travel = clockwise ? -RADIANS(360) : RADIANS(360); + abs_angular_travel = RADIANS(360); } else { // Calculate the angle @@ -103,8 +104,10 @@ void plan_arc( case 2: angular_travel += RADIANS(360); break; // Negative but CCW? Reverse direction. } + abs_angular_travel = ABS(angular_travel); + #ifdef MIN_ARC_SEGMENTS - min_segments = CEIL(min_segments * ABS(angular_travel) / RADIANS(360)); + min_segments = CEIL(min_segments * abs_angular_travel / RADIANS(360)); NOLESS(min_segments, 1U); #endif } @@ -117,8 +120,8 @@ void plan_arc( #endif // If circling around... - if (ENABLED(ARC_P_CIRCLES) && circles) { - const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder + if (TERN0(ARC_P_CIRCLES, circles)) { + const float total_angular = abs_angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total #if HAS_Z_AXIS @@ -138,8 +141,8 @@ void plan_arc( TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e); } - const float flat_mm = radius * angular_travel, - mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) ABS(flat_mm); + const float flat_mm = radius * abs_angular_travel, + mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) flat_mm; if (mm_of_travel < 0.001f) return; const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); From 2d4be74db98c8ab74b5c636cd1899bcaabd760e2 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 20 Jul 2021 12:54:02 -0700 Subject: [PATCH 0430/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20unused=20lambda?= =?UTF-8?q?=20warning=20(#22399)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/probe.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 6831d151f9..d585afb8b2 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -865,9 +865,11 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #if HAS_CURRENT_HOME(Z) static int16_t saved_current_Z; #endif - auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { - if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); } - }; + #if ((ENABLED(DELTA) && (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y))) || HAS_CURRENT_HOME(Z)) + auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); } + }; + #endif if (onoff) { #if ENABLED(DELTA) #if HAS_CURRENT_HOME(X) From a90968b0cef30f166f2f96aea526caf532a84949 Mon Sep 17 00:00:00 2001 From: Malderin <52313714+Malderin@users.noreply.github.com> Date: Tue, 20 Jul 2021 23:07:32 +0300 Subject: [PATCH 0431/2168] =?UTF-8?q?=F0=9F=8E=A8=20MKS=20hardware=20test?= =?UTF-8?q?=20followup=20(#22395)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 134 +++++++++--------- Marlin/src/lcd/extui/mks_ui/mks_hardware.h | 9 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 2 +- 3 files changed, 73 insertions(+), 72 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index cf9790ea9d..3c7eb55532 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -127,77 +127,81 @@ delay(100); } - void mks_gpio_test() { - init_test_gpio(); + #if ENABLED(SDSUPPORT) - test_gpio_readlevel_L(); - test_gpio_readlevel_H(); - test_gpio_readlevel_L(); - if (pw_det_sta && pw_off_sta && mt_det_sta - #if PIN_EXISTS(MT_DET_2) - && mt_det2_sta - #endif - #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) - && (READ(PA1) == LOW) - && (READ(PA3) == LOW) - && (READ(PC2) == LOW) - && (READ(PD8) == LOW) - && (READ(PE5) == LOW) - && (READ(PE6) == LOW) - && (READ(PE7) == LOW) - #endif - ) - disp_det_ok(); - else - disp_det_error(); + void mks_gpio_test() { + init_test_gpio(); - if (endstopx1_sta && endstopy1_sta && endstopz1_sta && endstopz2_sta) - disp_Limit_ok(); - else - disp_Limit_error(); - } + test_gpio_readlevel_L(); + test_gpio_readlevel_H(); + test_gpio_readlevel_L(); + if (pw_det_sta && pw_off_sta && mt_det_sta + #if PIN_EXISTS(MT_DET_2) + && mt_det2_sta + #endif + #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) + && (READ(PA1) == LOW) + && (READ(PA3) == LOW) + && (READ(PC2) == LOW) + && (READ(PD8) == LOW) + && (READ(PE5) == LOW) + && (READ(PE6) == LOW) + && (READ(PE7) == LOW) + #endif + ) + disp_det_ok(); + else + disp_det_error(); - void mks_hardware_test() { - if (millis() % 2000 < 1000) { - WRITE(X_DIR_PIN, LOW); - WRITE(Y_DIR_PIN, LOW); - WRITE(Z_DIR_PIN, LOW); - WRITE(E0_DIR_PIN, LOW); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - WRITE(E1_DIR_PIN, LOW); - #endif - thermalManager.fan_speed[0] = 255; - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - WRITE(HEATER_1_PIN, HIGH); // HE1 - #endif - WRITE(HEATER_0_PIN, HIGH); // HE0 - WRITE(HEATER_BED_PIN, HIGH); // HOT-BED - } - else { - WRITE(X_DIR_PIN, HIGH); - WRITE(Y_DIR_PIN, HIGH); - WRITE(Z_DIR_PIN, HIGH); - WRITE(E0_DIR_PIN, HIGH); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - WRITE(E1_DIR_PIN, HIGH); - #endif - thermalManager.fan_speed[0] = 0; - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - WRITE(HEATER_1_PIN, LOW); // HE1 - #endif - WRITE(HEATER_0_PIN, LOW); // HE0 - WRITE(HEATER_BED_PIN, LOW); // HOT-BED + if (endstopx1_sta && endstopy1_sta && endstopz1_sta && endstopz2_sta) + disp_Limit_ok(); + else + disp_Limit_error(); } - if (endstopx1_sta && endstopx2_sta && endstopy1_sta && endstopy2_sta && endstopz1_sta && endstopz2_sta) { - // nothing here - } - else { + void mks_hardware_test() { + if (millis() % 2000 < 1000) { + WRITE(X_DIR_PIN, LOW); + WRITE(Y_DIR_PIN, LOW); + WRITE(Z_DIR_PIN, LOW); + WRITE(E0_DIR_PIN, LOW); + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(E1_DIR_PIN, LOW); + #endif + thermalManager.fan_speed[0] = 255; + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(HEATER_1_PIN, HIGH); // HE1 + #endif + WRITE(HEATER_0_PIN, HIGH); // HE0 + WRITE(HEATER_BED_PIN, HIGH); // HOT-BED + } + else { + WRITE(X_DIR_PIN, HIGH); + WRITE(Y_DIR_PIN, HIGH); + WRITE(Z_DIR_PIN, HIGH); + WRITE(E0_DIR_PIN, HIGH); + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(E1_DIR_PIN, HIGH); + #endif + thermalManager.fan_speed[0] = 0; + #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + WRITE(HEATER_1_PIN, LOW); // HE1 + #endif + WRITE(HEATER_0_PIN, LOW); // HE0 + WRITE(HEATER_BED_PIN, LOW); // HOT-BED + } + + if (endstopx1_sta && endstopx2_sta && endstopy1_sta && endstopy2_sta && endstopz1_sta && endstopz2_sta) { + // nothing here + } + else { + } + + if (disp_state == PRINT_READY_UI) + mks_disp_test(); } - if (disp_state == PRINT_READY_UI) - mks_disp_test(); - } + #endif #endif // MKS_TEST @@ -613,7 +617,7 @@ void disp_assets_update_progress(const char *msg) { disp_string(100, 165, buf, 0xFFFF, 0x0000); } -#if ENABLED(SDSUPPORT) +#if BOTH(MKS_TEST, SDSUPPORT) uint8_t mks_test_flag = 0; const char *MKSTestPath = "MKS_TEST"; void mks_test_get() { diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h index de0c3a738e..f41c4e18ac 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -26,17 +26,14 @@ #include // Functions for MKS_TEST -#if ENABLED(MKS_TEST) - void mks_gpio_test(); +#if BOTH(MKS_TEST, SDSUPPORT) void mks_hardware_test(); void mks_test_get(); + void mks_gpio_test(); + extern uint8_t mks_test_flag; #endif // String display and assets void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); void disp_assets_update(); void disp_assets_update_progress(const char *msg); - -#if ENABLED(SDSUPPORT) - extern uint8_t mks_test_flag; -#endif diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index d8c5fbd6ec..2127b23a15 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -139,7 +139,7 @@ void tft_lvgl_init() { #if ENABLED(SDSUPPORT) UpdateAssets(); watchdog_refresh(); // LVGL init takes time - mks_test_get(); + TERN_(MKS_TEST, mks_test_get()); #endif touch.Init(); From e4ac55089e73577968cb693924bec673bf32c575 Mon Sep 17 00:00:00 2001 From: vyacheslav-shubin Date: Tue, 20 Jul 2021 23:12:08 +0300 Subject: [PATCH 0432/2168] =?UTF-8?q?=F0=9F=A9=B9=20Init=20var=20to=20supp?= =?UTF-8?q?ress=20invalid=20warning=20(#22396)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 21336f0b9a..03f2c58e81 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -70,7 +70,8 @@ void GcodeSuite::G29() { return; } - int8_t ix, iy = 0; + int8_t ix, iy; + ix = iy = 0; switch (state) { case MeshReport: From 86feddb75fc01fb744c9453dc4d1f5d1bfad4c4f Mon Sep 17 00:00:00 2001 From: Katelyn Schiesser Date: Tue, 20 Jul 2021 13:13:25 -0700 Subject: [PATCH 0433/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20BTC=5FSAMPLE=5FR?= =?UTF-8?q?ES=20sanity=20check=20(#22394)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ae4aba14db..9ced6e4e42 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -623,7 +623,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L static_assert(_test_btc_sample_start != 12.3f, "BTC_SAMPLE_START must be a whole number."); #endif #ifdef BTC_SAMPLE_RES - constexpr _btc_sample_res = BTC_SAMPLE_RES; + constexpr auto _btc_sample_res = BTC_SAMPLE_RES; constexpr decltype(_btc_sample_res) _test_btc_sample_res = 12.3f; static_assert(_test_btc_sample_res != 12.3f, "BTC_SAMPLE_RES must be a whole number."); #endif From 909834683a4db5ba4e16b18059dd4ae68f2129ef Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 21 Jul 2021 01:00:14 +0000 Subject: [PATCH 0434/2168] [cron] Bump distribution date (2021-07-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d559910437..bd8473bee3 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-20" +//#define STRING_DISTRIBUTION_DATE "2021-07-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ea126d2855..ef569263f7 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 "2021-07-20" + #define STRING_DISTRIBUTION_DATE "2021-07-21" #endif /** From 50ada44e7e7e42dd8b04668242a63071300aec27 Mon Sep 17 00:00:00 2001 From: VTXtruder <87478332+VTXtruder@users.noreply.github.com> Date: Tue, 20 Jul 2021 23:27:19 -0400 Subject: [PATCH 0435/2168] =?UTF-8?q?=E2=9C=A8=20Chitu3D=20V9=20board=20(#?= =?UTF-8?q?22401)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/core/boards.h | 25 +-- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f1/pins_CHITU3D.h | 7 +- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 146 +-------------- Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h | 150 +-------------- Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h | 36 ++++ Marlin/src/pins/stm32f1/pins_CHITU3D_common.h | 177 ++++++++++++++++++ 7 files changed, 234 insertions(+), 309 deletions(-) create mode 100755 Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h create mode 100644 Marlin/src/pins/stm32f1/pins_CHITU3D_common.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 661a213b4b..b5b33692a0 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -333,18 +333,19 @@ #define BOARD_CCROBOT_MEEB_3DP 4035 // ccrobot-online.com MEEB_3DP (STM32F103RC) #define BOARD_CHITU3D_V5 4036 // Chitu3D TronXY X5SA V5 Board #define BOARD_CHITU3D_V6 4037 // Chitu3D TronXY X5SA V6 Board -#define BOARD_CREALITY_V4 4038 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4039 // Creality v4.2.7 (STM32F103RE) -#define BOARD_CREALITY_V4210 4040 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 -#define BOARD_CREALITY_V431 4041 // Creality v4.3.1 (STM32F103RE) -#define BOARD_CREALITY_V452 4042 // Creality v4.5.2 (STM32F103RE) -#define BOARD_CREALITY_V453 4043 // Creality v4.5.3 (STM32F103RE) -#define BOARD_TRIGORILLA_PRO 4044 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4045 // FLYmaker FLY MINI (STM32F103RCT6) -#define BOARD_FLSUN_HISPEED 4046 // FLSUN HiSpeedV1 (STM32F103VET6) -#define BOARD_BEAST 4047 // STM32F103RET6 Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4048 // STM32F103ZET6 Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4049 // STM32F103VET6 controller +#define BOARD_CHITU3D_V9 4038 // Chitu3D TronXY X5SA V9 Board +#define BOARD_CREALITY_V4 4039 // Creality v4.x (STM32F103RE) +#define BOARD_CREALITY_V427 4040 // Creality v4.2.7 (STM32F103RE) +#define BOARD_CREALITY_V4210 4041 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 +#define BOARD_CREALITY_V431 4042 // Creality v4.3.1 (STM32F103RE) +#define BOARD_CREALITY_V452 4043 // Creality v4.5.2 (STM32F103RE) +#define BOARD_CREALITY_V453 4044 // Creality v4.5.3 (STM32F103RE) +#define BOARD_TRIGORILLA_PRO 4045 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4046 // FLYmaker FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4047 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4048 // STM32F103RET6 Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4049 // STM32F103ZET6 Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4050 // STM32F103VET6 controller // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b5a81c6097..4c773d1e76 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -537,6 +537,8 @@ #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple env:chitu_v5_gpio_init env:chitu_v5_gpio_init_maple #elif MB(CHITU3D_V6) #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple +#elif MB(CHITU3D_V9) + #include "stm32f1/pins_CHITU3D_V9.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple #elif MB(CREALITY_V4) #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index c2025ba8c0..2d33fb9f2c 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -81,12 +81,7 @@ // Heaters / Fans // #define HEATER_0_PIN PD12 // HOT-END -#define HEATER_1_PIN -1 -#define HEATER_2_PIN -1 - #define HEATER_BED_PIN PG11 // HOT-BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN #define FAN_PIN PG14 // MAIN BOARD FAN @@ -97,8 +92,8 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA0 // Analog Input #define TEMP_0_PIN PA1 // Analog Input +#define TEMP_BED_PIN PA0 // Analog Input // // LCD Pins diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index 88dd28a401..afe58df803 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -21,148 +21,8 @@ */ #pragma once -#include "env_validate.h" +#define BOARD_INFO_NAME "Chitu3D V5" -/** - * 2017 Victor Perez Marlin for stm32f1 test - */ +#define Z_STOP_PIN PG9 -#define BOARD_INFO_NAME "Chitu3D V5" -#define DEFAULT_MACHINE_NAME "STM32F103ZET6" - -#define BOARD_NO_NATIVE_USB - -#define DISABLE_JTAG - -// -// EEPROM -// -#define FLASH_EEPROM_EMULATION -#if ENABLED(FLASH_EEPROM_EMULATION) - // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE -#else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM -#endif - -// -// Limit Switches -// -#define X_STOP_PIN PG10 -#define Y_STOP_PIN PA12 -#define Z_STOP_PIN PA14 - -// -// Steppers -// -#define X_ENABLE_PIN PC13 -#define X_STEP_PIN PE5 -#define X_DIR_PIN PE6 - -#define Y_ENABLE_PIN PE4 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 - -#define Z_ENABLE_PIN PE1 -#define Z_STEP_PIN PB9 -#define Z_DIR_PIN PE0 - -#define E0_ENABLE_PIN PB8 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB5 - -#define E1_ENABLE_PIN PG8 -#define E1_STEP_PIN PC7 -#define E1_DIR_PIN PC6 - -// -// Temperature Sensors -// -#define TEMP_0_PIN PA1 // TH1 -#define TEMP_BED_PIN PA0 // TB1 - -// -// Heaters -// -#define HEATER_0_PIN PG12 // HEATER1 -#define HEATER_BED_PIN PG11 // HOT BED - -// -// Fans -// -#define CONTROLLER_FAN_PIN PD6 // BOARD FAN -#define FAN_PIN PG13 // FAN -#define FAN2_PIN PG14 - -// -// Misc -// -#define BEEPER_PIN PB0 -//#define LED_PIN -1 -//#define POWER_LOSS_PIN -1 -#define FIL_RUNOUT_PIN PA15 - -// SPI Flash -#define HAS_SPI_FLASH 1 -#if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x200000 // 2MB -#endif - -// SPI 2 -#define W25QXX_CS_PIN PB12 -#define W25QXX_MOSI_PIN PB15 -#define W25QXX_MISO_PIN PB14 -#define W25QXX_SCK_PIN PB13 - -// -// TFT with FSMC interface -// -#if HAS_FSMC_TFT - #define TOUCH_CS_PIN PB7 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define TFT_RESET_PIN PF11 - #define TFT_BACKLIGHT_PIN PD13 - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 - - #define TFT_CS_PIN FSMC_CS_PIN - #define TFT_RS_PIN FSMC_RS_PIN -#endif - -#if ENABLED(TFT_LVGL_UI) - // LVGL - #define HAS_SPI_FLASH_FONT 1 - #define HAS_GCODE_PREVIEW 1 - #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 - #define HAS_LANG_SELECT_SCREEN 1 - #define HAS_BAK_VIEW_IN_FLASH 0 - #define HAS_LOGO_IN_FLASH 0 -#elif ENABLED(TFT_COLOR_UI) - // Color UI - #define TFT_BUFFER_SIZE 14400 -#endif - -// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available -// Needs to use SPI2 -#define SPI_DEVICE 2 -#define SD_SCK_PIN PB13 -#define SD_MISO_PIN PB14 -#define SD_MOSI_PIN PB15 -#define SD_SS_PIN PB12 - -// -// SD Card -// -#define SDIO_SUPPORT -#define SD_DETECT_PIN -1 // PF0, but it isn't connected -#define SDIO_CLOCK 4500000 -#define SDIO_READ_RETRIES 16 +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index 51bd7294a9..b76ef52c42 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -21,160 +21,14 @@ */ #pragma once -#include "env_validate.h" - -/** - * 2017 Victor Perez Marlin for stm32f1 test - */ - -#define BOARD_INFO_NAME "Chitu3D" -#define DEFAULT_MACHINE_NAME "STM32F103ZET6" - -#define BOARD_NO_NATIVE_USB - -#define DISABLE_JTAG - -// -// EEPROM -// - -#if NO_EEPROM_SELECTED - #define FLASH_EEPROM_EMULATION -#endif - -#if ENABLED(FLASH_EEPROM_EMULATION) - // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) - #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) - #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE -#else - #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM -#endif - -// -// Limit Switches -// -#define X_STOP_PIN PG10 -#define Y_STOP_PIN PA12 -#define Z_STOP_PIN PG9 - -// -// Steppers -// -#define X_ENABLE_PIN PC13 -#define X_STEP_PIN PE5 -#define X_DIR_PIN PE6 - -#define Y_ENABLE_PIN PE4 -#define Y_STEP_PIN PE2 -#define Y_DIR_PIN PE3 - -#define Z_ENABLE_PIN PE1 -#define Z_STEP_PIN PB9 -#define Z_DIR_PIN PE0 +#define BOARD_INFO_NAME "Chitu3D V6" #define Z2_ENABLE_PIN PF3 #define Z2_STEP_PIN PF5 #define Z2_DIR_PIN PF1 -#define E0_ENABLE_PIN PB8 -#define E0_STEP_PIN PB4 -#define E0_DIR_PIN PB5 - -#define E1_ENABLE_PIN PG8 -#define E1_STEP_PIN PC7 -#define E1_DIR_PIN PC6 - -// -// Temperature Sensors -// -#define TEMP_0_PIN PA1 // TH1 -#define TEMP_BED_PIN PA0 // TB1 - -// -// Heaters -// -#define HEATER_0_PIN PG12 // HEATER1 -#define HEATER_BED_PIN PG11 // HOT BED -//#define HEATER_BED_INVERTING true - -// -// Fans -// -#define CONTROLLER_FAN_PIN PD6 // BOARD FAN -#define FAN_PIN PG13 // FAN -#define FAN2_PIN PG14 - -// -// Misc -// -#define BEEPER_PIN PB0 -//#define LED_PIN PD3 -//#define POWER_LOSS_PIN PG2 // PG4 PW_DET - -#ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA15 // MT_DET -#endif #ifndef FIL_RUNOUT2_PIN #define FIL_RUNOUT2_PIN PF13 #endif -// SPI Flash -#define HAS_SPI_FLASH 1 -#if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x200000 // 2MB -#endif - -// SPI 2 -#define W25QXX_CS_PIN PB12 -#define W25QXX_MOSI_PIN PB15 -#define W25QXX_MISO_PIN PB14 -#define W25QXX_SCK_PIN PB13 - -// -// TFT with FSMC interface -// -#if HAS_FSMC_TFT - #define TOUCH_CS_PIN PB7 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define TFT_RESET_PIN PF11 - #define TFT_BACKLIGHT_PIN PD13 - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 -#endif - -#if ENABLED(TFT_LVGL_UI) - // LVGL - #define HAS_SPI_FLASH_FONT 1 - #define HAS_GCODE_PREVIEW 1 - #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 - #define HAS_LANG_SELECT_SCREEN 1 - #define HAS_BAK_VIEW_IN_FLASH 0 - #define HAS_LOGO_IN_FLASH 0 -#elif ENABLED(TFT_COLOR_UI) - // Color UI - #define TFT_BUFFER_SIZE 14400 -#endif - -// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available -// so SPI2 is required. -#define SPI_DEVICE 2 -#define SD_SCK_PIN PB13 -#define SD_MISO_PIN PB14 -#define SD_MOSI_PIN PB15 -#define SD_SS_PIN PB12 - -// -// SD Card -// -#define SDIO_SUPPORT -#define SD_DETECT_PIN -1 // PF0, but it isn't connected -#define SDIO_CLOCK 4500000 -#define SDIO_READ_RETRIES 16 +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h new file mode 100755 index 0000000000..eb7f91deab --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define BOARD_INFO_NAME "Chitu3D V9" + +#define Z_STOP_PIN PA14 + +#define Z2_ENABLE_PIN PF3 +#define Z2_STEP_PIN PF5 +#define Z2_DIR_PIN PF1 + +#ifndef FIL_RUNOUT2_PIN + #define FIL_RUNOUT2_PIN PF13 +#endif + +#include "pins_CHITU3D_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h new file mode 100644 index 0000000000..b638589388 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -0,0 +1,177 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Chitu3D" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "STM32F103ZET6" +#endif + +#define BOARD_NO_NATIVE_USB +#define DISABLE_JTAG + +// +// EEPROM +// + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) + #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) + #define EEPROM_PAGE_SIZE (0x800U) // 2KB, but will use 2x more (4KB) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE +#else + #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#ifndef Z_STOP_PIN + #define Z_STOP_PIN PG9 +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PC13 +#define X_STEP_PIN PE5 +#define X_DIR_PIN PE6 + +#define Y_ENABLE_PIN PE4 +#define Y_STEP_PIN PE2 +#define Y_DIR_PIN PE3 + +#define Z_ENABLE_PIN PE1 +#define Z_STEP_PIN PB9 +#define Z_DIR_PIN PE0 + +#define E0_ENABLE_PIN PB8 +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB5 + +#define E1_ENABLE_PIN PG8 +#define E1_STEP_PIN PC7 +#define E1_DIR_PIN PC6 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA1 // TH1 Analog Input +#define TEMP_BED_PIN PA0 // TB1 Analog Input + +// +// Heaters +// +#define HEATER_0_PIN PG12 // HEATER1 +#define HEATER_BED_PIN PG11 // HOT BED +//#define HEATER_BED_INVERTING true + +// +// Fans +// +#define CONTROLLER_FAN_PIN PD6 // BOARD FAN +#define FAN_PIN PG13 // FAN +#define FAN2_PIN PG14 + +// +// Misc +// +#define BEEPER_PIN PB0 +//#define LED_PIN PD3 +//#define POWER_LOSS_PIN PG2 // PG4 PW_DET + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA15 // MT_DET +#endif + +// SPI Flash +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x200000 // 2MB +#endif + +// SPI 2 +#define W25QXX_CS_PIN PB12 +#define W25QXX_MOSI_PIN PB15 +#define W25QXX_MISO_PIN PB14 +#define W25QXX_SCK_PIN PB13 + +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + #define TOUCH_CS_PIN PB7 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + + #define TFT_RESET_PIN PF11 + #define TFT_BACKLIGHT_PIN PD13 + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN +#endif + +#if ENABLED(TFT_LVGL_UI) + // LVGL + #define HAS_SPI_FLASH_FONT 1 + #define HAS_GCODE_PREVIEW 1 + #define HAS_GCODE_DEFAULT_VIEW_IN_FLASH 0 + #define HAS_LANG_SELECT_SCREEN 1 + #define HAS_BAK_VIEW_IN_FLASH 0 + #define HAS_LOGO_IN_FLASH 0 +#elif ENABLED(TFT_COLOR_UI) + // Color UI + #define TFT_BUFFER_SIZE 14400 +#endif + +// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available +// so SPI2 is required. +#define SPI_DEVICE 2 +#define SD_SCK_PIN PB13 +#define SD_MISO_PIN PB14 +#define SD_MOSI_PIN PB15 +#define SD_SS_PIN PB12 + +// +// SD Card +// +#define SDIO_SUPPORT +#define SD_DETECT_PIN -1 // PF0, but it isn't connected +#define SDIO_CLOCK 4500000 +#define SDIO_READ_RETRIES 16 From eb3ad3e4fe5a914921fb3878ccfaeb1905773d51 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 20 Jul 2021 23:35:56 -0500 Subject: [PATCH 0436/2168] =?UTF-8?q?=F0=9F=8E=A8=20BTT=20SKR=20Pro=20pins?= =?UTF-8?q?=20auto-assign=20(#22411)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: MarkusThur <83773817+MarkusThur@users.noreply.github.com> --- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 68 +++++++++++++++++-- 1 file changed, 61 insertions(+), 7 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index fe6d8740bd..fdc6c6f6e5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -231,27 +231,81 @@ // // Temperature Sensors +// Use ADC pins without pullup for sensors that don't need a pullup. // -#define TEMP_0_PIN PF4 // T1 <-> E0 -#define TEMP_1_PIN PF5 // T2 <-> E1 -#define TEMP_2_PIN PF6 // T3 <-> E2 -#define TEMP_BED_PIN PF3 // T0 <-> Bed +#if TEMP_SENSOR_0_IS_AD8495 || TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 +#else + #define TEMP_0_PIN PF4 // T1 <-> E0 +#endif +#if TEMP_SENSOR_1_IS_AD8495 || TEMP_SENSOR_1 == 20 + #define TEMP_1_PIN PF9 +#else + #define TEMP_1_PIN PF5 // T2 <-> E1 +#endif +#if TEMP_SENSOR_2_IS_AD8495 || TEMP_SENSOR_2 == 20 + #define TEMP_2_PIN PF10 +#else + #define TEMP_2_PIN PF6 // T3 <-> E2 +#endif +#if TEMP_SENSOR_BED_IS_AD8495 || TEMP_SENSOR_BED == 20 + #define TEMP_BED_PIN PF7 +#else + #define TEMP_BED_PIN PF3 // T0 <-> Bed +#endif + +#ifdef TEMP_SENSOR_PROBE && !defined(TEMP_PROBE_PIN) + #if TEMP_SENSOR_PROBE_IS_AD8495 || TEMP_SENSOR_PROBE == 20 + #if HOTENDS == 2 + #define TEMP_PROBE_PIN PF10 + #elif HOTENDS < 2 + #define TEMP_PROBE_PIN PF9 + #endif + #else + #if HOTENDS == 2 + #define TEMP_PROBE_PIN TEMP_2_PIN + #elif HOTENDS < 2 + #define TEMP_PROBE_PIN TEMP_1_PIN + #endif + #endif +#endif + +#if TEMP_SENSOR_CHAMBER && !defined(TEMP_CHAMBER_PIN) + #if TEMP_SENSOR_CHAMBER_IS_AD8495 || TEMP_SENSOR_CHAMBER == 20 + #define TEMP_CHAMBER_PIN PF10 + #else + #define TEMP_CHAMBER_PIN TEMP_2_PIN + #endif +#endif // -// Heaters / Fans +// Heaters // #define HEATER_0_PIN PB1 // Heater0 #define HEATER_1_PIN PD14 // Heater1 -#define HEATER_2_PIN PB0 // Heater1 +#if TEMP_SENSOR_CHAMBER && HOTENDS < 3 + #define HEATER_CHAMBER_PIN PB0 // Heater2 +#else + #define HEATER_2_PIN PB0 // Heater2 +#endif #define HEATER_BED_PIN PD12 // Hotbed + +// +// Fans +// #define FAN_PIN PC8 // Fan0 #define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PE6 // Fan2 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN FAN1_PIN #endif +#if ENABLED(USE_CONTROLLER_FAN) && HOTENDS < 2 + #define CONTROLLER_FAN_PIN PE6 // Fan2 +#else + #define FAN2_PIN PE6 // Fan2 +#endif + // // Misc. Functions // From af4c281af582699bd535a1da4eb2abb2c7775cba Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 21 Jul 2021 00:12:26 -0500 Subject: [PATCH 0437/2168] =?UTF-8?q?=F0=9F=94=A7=20Clean=20up=20PTC=5FPRO?= =?UTF-8?q?BE=5FHEATING=5FOFFSET?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e99e1f7c09..d404d0d19c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2021,9 +2021,9 @@ // calibration. //#define BTC_PROBE_TEMP 30 // (°C) - // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. - //#define PTC_PROBE_HEATING_OFFSET 0.5f + // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. + // Note: the Z=0.0 offset is determined by the probe offset which can be set using M851. + //#define PTC_PROBE_HEATING_OFFSET 0.5 // Height to raise the Z-probe between heating and taking the next measurement. Some probes // may fail to untrigger if they have been triggered for a long time, which can be solved by From eb2f086522c0befd3628693250ba56fe56a1a7a1 Mon Sep 17 00:00:00 2001 From: Luke Harrison Date: Wed, 21 Jul 2021 07:43:33 +0200 Subject: [PATCH 0438/2168] =?UTF-8?q?=F0=9F=94=A7=20Octopus=20SPI=20displa?= =?UTF-8?q?y=20pins,=20fix=20USB=20build=20env=20(#22412)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 18 ++++++++++++++++++ ini/stm32f1.ini | 2 +- ini/stm32f4.ini | 3 ++- 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 2cf1ee1447..25622bc62d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -500,6 +500,24 @@ #endif #endif +#if HAS_SPI_TFT + #define TFT_CS_PIN EXP2_07_PIN + #define TFT_A0_PIN EXP2_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + + #define TOUCH_INT_PIN EXP1_04_PIN + #define TOUCH_MISO_PIN EXP1_05_PIN + #define TOUCH_MOSI_PIN EXP1_08_PIN + #define TOUCH_SCK_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN +#endif + // // WIFI // diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 0f1d308660..175d0e45b0 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -336,7 +336,7 @@ board_build.variant = MARLIN_F103Vx board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 build_flags = ${stm32_variant.build_flags} - -DMCU_STM32F103VE -DU20 -DTS_V12 -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA + -DMCU_STM32F103VE -DU20 -DTS_V12 -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA -UPIN_WIRE_SCL -DPIN_WIRE_SDA=PB11 -DPIN_WIRE_SCL=PB10 -DHAL_DAC_MODULE_DISABLED -DHAL_I2S_MODULE_DISABLED build_unflags = ${stm32_variant.build_unflags} diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index f9c16cf455..901f145113 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -129,7 +129,7 @@ platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_SKR_Pro board_build.offset = 0x8000 -build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX +build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX debug_tool = stlink upload_protocol = stlink @@ -235,6 +235,7 @@ build_flags = ${stm32_variant.build_flags} platform = ${common_stm32.platform} extends = env:BIGTREE_OCTOPUS_V1 platform_packages = ${stm_flash_drive.platform_packages} +build_unflags = -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} -DSTM32F446_5VX -DUSE_USB_HS_IN_FS -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 From d819de46d32d7d6f87664e4b7ecf3afb7a3ed8ce Mon Sep 17 00:00:00 2001 From: ellensp Date: Thu, 22 Jul 2021 09:31:11 +1200 Subject: [PATCH 0439/2168] =?UTF-8?q?=F0=9F=8E=A8=20MKS=20Hardware=20Test?= =?UTF-8?q?=20followup=20(#22414)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../lcd/extui/mks_ui/draw_media_select.cpp | 4 +- .../src/lcd/extui/mks_ui/draw_ready_print.cpp | 12 +- Marlin/src/lcd/extui/mks_ui/draw_tool.cpp | 4 +- .../extui/mks_ui/draw_touch_calibration.cpp | 6 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 188 ++++++++++++++---- Marlin/src/lcd/extui/mks_ui/mks_hardware.h | 2 + .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 6 + buildroot/tests/mks_robin_nano35 | 1 + buildroot/tests/mks_robin_nano35_maple | 1 + 9 files changed, 170 insertions(+), 54 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 0394ed6009..81c82dc02d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -39,7 +39,7 @@ enum { }; #if ENABLED(MKS_TEST) - extern uint8_t curent_disp_ui; + extern uint8_t current_disp_ui; #endif static void event_handler(lv_obj_t *obj, lv_event_t event) { @@ -49,7 +49,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_T_USB_DISK: card.changeMedia(&card.media_driver_usbFlash); break; case ID_T_SD_DISK: card.changeMedia(&card.media_driver_sdcard); break; case ID_T_RETURN: - TERN_(MKS_TEST, curent_disp_ui = 1); + TERN_(MKS_TEST, current_disp_ui = 1); lv_draw_ready_print(); return; } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index 6f24d81b49..d324d8d7be 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -61,7 +61,7 @@ static lv_obj_t *buttonExt1, *labelExt1, *buttonFanstate, *labelFan; #endif #if ENABLED(MKS_TEST) - uint8_t curent_disp_ui = 0; + uint8_t current_disp_ui = 0; #endif enum { ID_TOOL = 1, ID_SET, ID_PRINT, ID_INFO_EXT, ID_INFO_BED, ID_INFO_FAN }; @@ -106,8 +106,10 @@ void disp_det_error() { lv_obj_t *e1, *e2, *e3, *bed; void mks_disp_test() { char buf[30] = {0}; - sprintf_P(buf, PSTR("e1:%d"), thermalManager.wholeDegHotend(0)); - lv_label_set_text(e1, buf); + #if HAS_HOTEND + sprintf_P(buf, PSTR("e1:%d"), thermalManager.wholeDegHotend(0)); + lv_label_set_text(e1, buf); + #endif #if HAS_MULTI_HOTEND sprintf_P(buf, PSTR("e2:%d"), thermalManager.wholeDegHotend(1)); lv_label_set_text(e2, buf); @@ -126,7 +128,7 @@ void lv_draw_ready_print() { ZERO(disp_state_stack._disp_state); scr = lv_screen_create(PRINT_READY_UI, ""); - if (TERN0(SDSUPPORT, mks_test_flag == 0x1E)) { + if (mks_test_flag == 0x1E) { // Create image buttons buttonTool = lv_imgbtn_create(scr, "F:/bmp_tool.bin", event_handler, ID_TOOL); @@ -147,7 +149,7 @@ void lv_draw_ready_print() { #if HAS_MULTI_HOTEND e2 = lv_label_create_empty(scr); lv_obj_set_pos(e2, 20, 45); - sprintf_P(buf, PSTR("e1: %d"), thermalManager.wholeDegHotend(1)); + sprintf_P(buf, PSTR("e2: %d"), thermalManager.wholeDegHotend(1)); lv_label_set_text(e2, buf); #endif #if HAS_HEATED_BED diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp index 16c1448b3c..8b9747972d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -45,7 +45,7 @@ enum { }; #if ENABLED(MKS_TEST) - extern uint8_t curent_disp_ui; + extern uint8_t current_disp_ui; #endif static void event_handler(lv_obj_t *obj, lv_event_t event) { @@ -75,7 +75,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { lv_draw_more(); break; case ID_T_RETURN: - TERN_(MKS_TEST, curent_disp_ui = 1); + TERN_(MKS_TEST, current_disp_ui = 1); lv_draw_ready_print(); break; } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index a4470a4c87..e10a07c6de 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -34,6 +34,10 @@ static lv_obj_t *scr; static lv_obj_t *status_label; +#if ENABLED(MKS_TEST) + extern uint8_t current_disp_ui; +#endif + static void event_handler(lv_obj_t *obj, lv_event_t event); enum { @@ -93,7 +97,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; switch (obj->mks_obj_id) { case ID_TC_RETURN: - TERN_(MKS_TEST, curent_disp_ui = 1); + TERN_(MKS_TEST, current_disp_ui = 1); lv_clear_touch_calibration_screen(); draw_return_ui(); break; diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 3c7eb55532..5cd1a4c525 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -38,12 +38,44 @@ #if ENABLED(MKS_TEST) #include "mks_hardware.h" + #include "../../../module/endstops.h" bool pw_det_sta, pw_off_sta, mt_det_sta; #if PIN_EXISTS(MT_DET_2) bool mt_det2_sta; #endif - bool endstopx1_sta, endstopx2_sta, endstopy1_sta, endstopy2_sta, endstopz1_sta, endstopz2_sta; + #if HAS_X_MIN || HAS_X_MAX + bool endstopx1_sta; + #else + constexpr static bool endstopx1_sta = true; + #endif + #if HAS_X2_MIN || HAS_X2_MAX + bool endstopx2_sta; + #else + constexpr static bool endstopx2_sta = true; + #endif + #if HAS_Y_MIN || HAS_Y_MAX + bool endstopy1_sta; + #else + constexpr static bool endstopy1_sta = true; + #endif + #if HAS_Y2_MIN || HAS_Y2_MAX + bool endstopy2_sta; + #else + constexpr static bool endstopy2_sta = true; + #endif + #if HAS_Z_MIN || HAS_Z_MAX + bool endstopz1_sta; + #else + constexpr static bool endstopz1_sta = true; + #endif + #if HAS_Z2_MIN || HAS_Z2_MAX + bool endstopz2_sta; + #else + constexpr static bool endstopz2_sta = true; + #endif + + #define ESTATE(S) (READ(S##_PIN) != S##_ENDSTOP_INVERTING) void test_gpio_readlevel_L() { WRITE(WIFI_IO0_PIN, HIGH); @@ -54,10 +86,36 @@ #if PIN_EXISTS(MT_DET_2) mt_det2_sta = (READ(MT_DET_2_PIN) == LOW); #endif - endstopx1_sta = (READ(X_MIN_PIN) == LOW); - endstopy1_sta = (READ(Y_MIN_PIN) == LOW); - endstopz1_sta = (READ(Z_MIN_PIN) == LOW); - endstopz2_sta = (READ(Z_MAX_PIN) == LOW); + #if HAS_X_MIN + endstopx1_sta = ESTATE(X_MIN); + #elif HAS_X_MAX + endstopx1_sta = ESTATE(X_MAX); + #endif + #if HAS_X2_MIN + endstopx2_sta = ESTATE(X2_MIN); + #elif HAS_X2_MAX + endstopx2_sta = ESTATE(X2_MAX); + #endif + #if HAS_Y_MIN + endstopy1_sta = ESTATE(Y_MIN); + #elif HAS_Y_MAX + endstopy1_sta = ESTATE(Y_MAX); + #endif + #if HAS_Y2_MIN + endstopy2_sta = ESTATE(Y2_MIN); + #elif HAS_Y2_MAX + endstopy2_sta = ESTATE(Y2_MAX); + #endif + #if HAS_Z_MIN + endstopz1_sta = ESTATE(Z_MIN); + #elif HAS_Z_MAX + endstopz1_sta = ESTATE(Z_MAX); + #endif + #if HAS_Z2_MIN + endstopz2_sta = ESTATE(Z2_MIN); + #elif HAS_Z2_MAX + endstopz2_sta = ESTATE(Z2_MAX); + #endif } void test_gpio_readlevel_H() { @@ -69,44 +127,66 @@ #if PIN_EXISTS(MT_DET_2) mt_det2_sta = (READ(MT_DET_2_PIN) == HIGH); #endif - endstopx1_sta = (READ(X_MIN_PIN) == HIGH); - endstopy1_sta = (READ(Y_MIN_PIN) == HIGH); - endstopz1_sta = (READ(Z_MIN_PIN) == HIGH); - endstopz2_sta = (READ(Z_MAX_PIN) == HIGH); + #if HAS_X_MIN + endstopx1_sta = !ESTATE(X_MIN); + #elif HAS_X_MAX + endstopx1_sta = !ESTATE(X_MAX); + #endif + #if HAS_X2_MIN + endstopx2_sta = !ESTATE(X2_MIN); + #elif HAS_X2_MAX + endstopx2_sta = !ESTATE(X2_MAX); + #endif + #if HAS_Y_MIN + endstopy1_sta = !ESTATE(Y_MIN); + #elif HAS_Y_MAX + endstopy1_sta = !ESTATE(Y_MAX); + #endif + #if HAS_Y2_MIN + endstopy2_sta = !ESTATE(Y2_MIN); + #elif HAS_Y2_MAX + endstopy2_sta = !ESTATE(Y2_MAX); + #endif + #if HAS_Z_MIN + endstopz1_sta = !ESTATE(Z_MIN); + #elif HAS_Z_MAX + endstopz1_sta = !ESTATE(Z_MAX); + #endif + #if HAS_Z2_MIN + endstopz2_sta = !ESTATE(Z2_MIN); + #elif HAS_Z2_MAX + endstopz2_sta = !ESTATE(Z2_MAX); + #endif } void init_test_gpio() { - SET_INPUT_PULLUP(X_MIN_PIN); - SET_INPUT_PULLUP(Y_MIN_PIN); - SET_INPUT_PULLUP(Z_MIN_PIN); - SET_INPUT_PULLUP(Z_MAX_PIN); + endstops.init(); SET_OUTPUT(WIFI_IO0_PIN); - SET_INPUT_PULLUP(MT_DET_1_PIN); + #if PIN_EXISTS(MT_DET_1) + SET_INPUT_PULLUP(MT_DET_1_PIN); + #endif #if PIN_EXISTS(MT_DET_2) SET_INPUT_PULLUP(MT_DET_2_PIN); #endif SET_INPUT_PULLUP(MKS_TEST_POWER_LOSS_PIN); SET_INPUT_PULLUP(MKS_TEST_PS_ON_PIN); - SET_INPUT_PULLUP(SERVO0_PIN); - SET_OUTPUT(X_ENABLE_PIN); - SET_OUTPUT(Y_ENABLE_PIN); - SET_OUTPUT(Z_ENABLE_PIN); - SET_OUTPUT(E0_ENABLE_PIN); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - SET_OUTPUT(E1_ENABLE_PIN); + OUT_WRITE(X_ENABLE_PIN, LOW); + #if HAS_Y_AXIS + OUT_WRITE(Y_ENABLE_PIN, LOW); #endif - - WRITE(X_ENABLE_PIN, LOW); - WRITE(Y_ENABLE_PIN, LOW); - WRITE(Z_ENABLE_PIN, LOW); - WRITE(E0_ENABLE_PIN, LOW); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) - WRITE(E1_ENABLE_PIN, LOW); + #if HAS_Z_AXIS + OUT_WRITE(Z_ENABLE_PIN, LOW); + #endif + #if HAS_EXTRUDERS + OUT_WRITE(E0_ENABLE_PIN, LOW); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + OUT_WRITE(E1_ENABLE_PIN, LOW); #endif #if ENABLED(MKS_HARDWARE_TEST_ONLY_E0) @@ -161,34 +241,54 @@ void mks_hardware_test() { if (millis() % 2000 < 1000) { + thermalManager.fan_speed[0] = 255; WRITE(X_DIR_PIN, LOW); - WRITE(Y_DIR_PIN, LOW); - WRITE(Z_DIR_PIN, LOW); - WRITE(E0_DIR_PIN, LOW); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + #if HAS_Y_AXIS + WRITE(Y_DIR_PIN, LOW); + #endif + #if HAS_Z_AXIS + WRITE(Z_DIR_PIN, LOW); + #endif + #if HAS_EXTRUDERS + WRITE(E0_DIR_PIN, LOW); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(E1_DIR_PIN, LOW); #endif - thermalManager.fan_speed[0] = 255; - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + #if HAS_MULTI_HOTEND && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(HEATER_1_PIN, HIGH); // HE1 #endif - WRITE(HEATER_0_PIN, HIGH); // HE0 - WRITE(HEATER_BED_PIN, HIGH); // HOT-BED + #if HAS_HOTEND + WRITE(HEATER_0_PIN, HIGH); // HE0 + #endif + #if HAS_HEATED_BED + WRITE(HEATER_BED_PIN, HIGH); // HOT-BED + #endif } else { + thermalManager.fan_speed[0] = 0; WRITE(X_DIR_PIN, HIGH); - WRITE(Y_DIR_PIN, HIGH); - WRITE(Z_DIR_PIN, HIGH); - WRITE(E0_DIR_PIN, HIGH); - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + #if HAS_Y_AXIS + WRITE(Y_DIR_PIN, HIGH); + #endif + #if HAS_Y_AXIS + WRITE(Z_DIR_PIN, HIGH); + #endif + #if HAS_EXTRUDERS + WRITE(E0_DIR_PIN, HIGH); + #endif + #if HAS_MULTI_EXTRUDER && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(E1_DIR_PIN, HIGH); #endif - thermalManager.fan_speed[0] = 0; - #if DISABLED(MKS_HARDWARE_TEST_ONLY_E0) + #if HAS_MULTI_HOTEND && DISABLED(MKS_HARDWARE_TEST_ONLY_E0) WRITE(HEATER_1_PIN, LOW); // HE1 #endif - WRITE(HEATER_0_PIN, LOW); // HE0 - WRITE(HEATER_BED_PIN, LOW); // HOT-BED + #if HAS_HOTEND + WRITE(HEATER_0_PIN, LOW); // HE0 + #endif + #if HAS_HEATED_BED + WRITE(HEATER_BED_PIN, LOW); // HOT-BED + #endif } if (endstopx1_sta && endstopx2_sta && endstopy1_sta && endstopy2_sta && endstopz1_sta && endstopz2_sta) { diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h index f41c4e18ac..5313265662 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -31,6 +31,8 @@ void mks_test_get(); void mks_gpio_test(); extern uint8_t mks_test_flag; +#else + #define mks_test_flag 0 #endif // String display and assets diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 178e75ab7f..182506f11e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -220,6 +220,12 @@ #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN #endif +// MKS TEST +#if ENABLED(MKS_TEST) + #define MKS_TEST_POWER_LOSS_PIN PA13 // PW_DET + #define MKS_TEST_PS_ON_PIN PB2 // PW_OFF +#endif + // // Onboard SD card // diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 index 99ff2623bb..bd16fe48e9 100755 --- a/buildroot/tests/mks_robin_nano35 +++ b/buildroot/tests/mks_robin_nano35 @@ -22,6 +22,7 @@ use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC opt_enable TFT_INTERFACE_SPI MKS_WIFI_MODULE +opt_add MKS_TEST exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" # diff --git a/buildroot/tests/mks_robin_nano35_maple b/buildroot/tests/mks_robin_nano35_maple index f1549a8103..ebd5466ce6 100755 --- a/buildroot/tests/mks_robin_nano35_maple +++ b/buildroot/tests/mks_robin_nano35_maple @@ -32,6 +32,7 @@ use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE +opt_add MKS_TEST exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" # From 21011eefa818f73d79746f7555fead94f0d3d20a Mon Sep 17 00:00:00 2001 From: Chris Pepper Date: Thu, 22 Jul 2021 01:01:23 +0100 Subject: [PATCH 0440/2168] =?UTF-8?q?=E2=9C=A8=20Simulator=20HAL=20and=20b?= =?UTF-8?q?uild=20targets=20(#22418)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 6 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 217 ++++++++++++++++++ Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h | 26 +++ Marlin/src/HAL/NATIVE_SIM/fastio.h | 111 +++++++++ .../src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h | 22 ++ .../src/HAL/NATIVE_SIM/inc/Conditionals_adv.h | 31 +++ .../HAL/NATIVE_SIM/inc/Conditionals_post.h | 22 ++ Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h | 43 ++++ Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 59 +++++ Marlin/src/HAL/NATIVE_SIM/servo_private.h | 80 +++++++ Marlin/src/HAL/NATIVE_SIM/spi_pins.h | 55 +++++ Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h | 64 ++++++ Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h | 80 +++++++ Marlin/src/HAL/NATIVE_SIM/timers.h | 91 ++++++++ .../HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp | 52 +++++ .../src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h | 37 +++ Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h | 44 ++++ Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h | 43 ++++ .../HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp | 52 +++++ .../src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h | 46 ++++ .../NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp | 171 ++++++++++++++ .../src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp | 215 +++++++++++++++++ Marlin/src/HAL/NATIVE_SIM/watchdog.h | 27 +++ Marlin/src/HAL/platforms.h | 2 + Marlin/src/HAL/shared/Delay.h | 2 +- Marlin/src/core/serial.h | 3 + Marlin/src/lcd/dogm/HAL_LCD_com_defines.h | 5 + .../src/lcd/extui/mks_ui/draw_print_file.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 8 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 8 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 62 ++++- Marlin/src/pins/pins.h | 2 +- Marlin/src/sd/SdFatUtil.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 2 +- .../PlatformIO/scripts/common-dependencies.py | 10 +- .../share/PlatformIO/scripts/simulator.py | 52 +++++ ini/native.ini | 107 +++++++++ 37 files changed, 1847 insertions(+), 16 deletions(-) create mode 100644 Marlin/src/HAL/NATIVE_SIM/HAL.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/fastio.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/pinsDebug.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/servo_private.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/spi_pins.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/timers.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp create mode 100644 Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp create mode 100644 Marlin/src/HAL/NATIVE_SIM/watchdog.h create mode 100644 buildroot/share/PlatformIO/scripts/simulator.py diff --git a/.gitignore b/.gitignore index ac2c9b5591..bc603ba38b 100755 --- a/.gitignore +++ b/.gitignore @@ -143,7 +143,11 @@ vc-fileutils.settings .vscode/launch.json .vscode/*.db -# cmake +#Simulation +imgui.ini +eeprom.dat + +#cmake CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h new file mode 100644 index 0000000000..d5c5782c36 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -0,0 +1,217 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 + +#define CPU_32_BIT +#define HAL_IDLETASK +void HAL_idletask(); + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU +#include +#include + +#undef min +#undef max + +#include +#include "pinmapping.h" + +void _printf (const char *format, ...); +void _putc(uint8_t c); +uint8_t _getc(); + +//extern "C" volatile uint32_t _millis; + +//arduino: Print.h +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 +//arduino: binary.h (weird defines) +#define B01 1 +#define B10 2 + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +#define SHARED_SERVOS HAS_SERVOS + +extern MSerialT serial_stream_0; +extern MSerialT serial_stream_1; +extern MSerialT serial_stream_2; +extern MSerialT serial_stream_3; + +#define _MSERIAL(X) serial_stream_##X +#define MSERIAL(X) _MSERIAL(X) + +#if WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#else + #error "SERIAL_PORT must be from 0 to 3. Please update your configuration." +#endif + +#ifdef SERIAL_PORT_2 + #if WITHIN(SERIAL_PORT_2, 0, 3) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #else + #error "SERIAL_PORT_2 must be from 0 to 3. Please update your configuration." + #endif +#endif + +#ifdef MMU2_SERIAL_PORT + #if WITHIN(MMU2_SERIAL_PORT, 0, 3) + #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) + #else + #error "MMU2_SERIAL_PORT must be from 0 to 3. Please update your configuration." + #endif +#endif + +#ifdef LCD_SERIAL_PORT + #if WITHIN(LCD_SERIAL_PORT, 0, 3) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #else + #error "LCD_SERIAL_PORT must be from 0 to 3. Please update your configuration." + #endif +#endif + + +#define ST7920_DELAY_1 DELAY_NS(600) +#define ST7920_DELAY_2 DELAY_NS(750) +#define ST7920_DELAY_3 DELAY_NS(750) + +// +// Interrupts +// +#define CRITICAL_SECTION_START() +#define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() + +inline void HAL_init() {} + +// Utility functions +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +int freeMemory(); +#pragma GCC diagnostic pop + +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true + +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + +/* ---------------- Delay in cycles */ + +#define DELAY_CYCLES(x) Kernel::delayCycles(x) +#define SYSTEM_YIELD() Kernel::yield() + +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +extern volatile uint32_t systick_uptime_millis; + +// Marlin uses strstr in constexpr context, this is not supported, workaround by defining constexpr versions of the required functions. +#define strstr(a, b) strstr_constexpr((a), (b)) + +constexpr inline std::size_t strlen_constexpr(const char* str) { + // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 + if (str != nullptr) { + std::size_t i = 0; + while (str[i] != '\0') { + ++i; + } + + return i; + } + + return 0; +} + +constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { + // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 + if (lhs == nullptr || rhs == nullptr) { + return rhs != nullptr ? -1 : 1; + } + + for (std::size_t i = 0; i < count; ++i) { + if (lhs[i] != rhs[i]) { + return lhs[i] < rhs[i] ? -1 : 1; + } else if (lhs[i] == '\0') { + return 0; + } + } + + return 0; +} + +constexpr inline const char* strstr_constexpr(const char* str, const char* target) { + // https://github.com/freebsd/freebsd/blob/master/sys/libkern/strstr.c + if (char c = target != nullptr ? *target++ : '\0'; c != '\0' && str != nullptr) { + std::size_t len = strlen_constexpr(target); + do { + char sc = {}; + do { + if ((sc = *str++) == '\0') { + return nullptr; + } + } while (sc != c); + } while (strncmp_constexpr(str, target, len) != 0); + --str; + } + + return str; +} + +constexpr inline char* strstr_constexpr(char* str, const char* target) { + // https://github.com/freebsd/freebsd/blob/master/sys/libkern/strstr.c + if (char c = target != nullptr ? *target++ : '\0'; c != '\0' && str != nullptr) { + std::size_t len = strlen_constexpr(target); + do { + char sc = {}; + do { + if ((sc = *str++) == '\0') { + return nullptr; + } + } while (sc != c); + } while (strncmp_constexpr(str, target, len) != 0); + --str; + } + return str; +} diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h new file mode 100644 index 0000000000..b5cc6f02a4 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/NATIVE_SIM/fastio.h b/Marlin/src/HAL/NATIVE_SIM/fastio.h new file mode 100644 index 0000000000..de8013b1e5 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/fastio.h @@ -0,0 +1,111 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Fast I/O Routines for X86_64 + */ + +#include "../shared/Marduino.h" +#include + +#define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1) +#define SET_DIR_OUTPUT(IO) Gpio::setDir(IO, 0) + +#define SET_MODE(IO, mode) Gpio::setMode(IO, mode) + +#define WRITE_PIN_SET(IO) Gpio::set(IO) +#define WRITE_PIN_CLR(IO) Gpio::clear(IO) + +#define READ_PIN(IO) Gpio::get(IO) +#define WRITE_PIN(IO,V) Gpio::set(IO, V) + +/** + * Magic I/O routines + * + * Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW); + * + * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html + */ + +/// Read a pin +#define _READ(IO) READ_PIN(IO) + +/// Write to a pin +#define _WRITE(IO,V) WRITE_PIN(IO,V) + +/// toggle a pin +#define _TOGGLE(IO) _WRITE(IO, !READ(IO)) + +/// set pin as input +#define _SET_INPUT(IO) SET_DIR_INPUT(IO) + +/// set pin as output +#define _SET_OUTPUT(IO) SET_DIR_OUTPUT(IO) + +/// set pin as input with pullup mode +#define _PULLUP(IO,V) pinMode(IO, (V) ? INPUT_PULLUP : INPUT) + +/// set pin as input with pulldown mode +#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT) + +// hg42: all pins can be input or output (I hope) +// hg42: undefined pins create compile error (IO, is no pin) +// hg42: currently not used, but was used by pinsDebug + +/// check if pin is an input +#define _IS_INPUT(IO) (IO >= 0) + +/// check if pin is an output +#define _IS_OUTPUT(IO) (IO >= 0) + +/// Read a pin wrapper +#define READ(IO) _READ(IO) + +/// Write to a pin wrapper +#define WRITE(IO,V) _WRITE(IO,V) + +/// toggle a pin wrapper +#define TOGGLE(IO) _TOGGLE(IO) + +/// set pin as input wrapper +#define SET_INPUT(IO) _SET_INPUT(IO) +/// set pin as input with pullup wrapper +#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0) +/// set pin as input with pulldown wrapper +#define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0) +/// set pin as output wrapper - reads the pin and sets the output to that value +#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) +// set pin as PWM +#define SET_PWM(IO) SET_OUTPUT(IO) + +/// check if pin is an input wrapper +#define IS_INPUT(IO) _IS_INPUT(IO) +/// check if pin is an output wrapper +#define IS_OUTPUT(IO) _IS_OUTPUT(IO) + +// Shorthand +#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0) + +// digitalRead/Write wrappers +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO,V) digitalWrite(IO,V) diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..1ac02f1182 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_LCD.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h new file mode 100644 index 0000000000..69b6b4848f --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_adv.h @@ -0,0 +1,31 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +// Add strcmp_P if missing +#ifndef strcmp_P + #define strcmp_P(a, b) strcmp((a), (b)) +#endif + +#ifndef strcat_P + #define strcat_P(dest, src) strcat((dest), (src)) +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h new file mode 100644 index 0000000000..1ac02f1182 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/Conditionals_post.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h new file mode 100644 index 0000000000..104af9af5b --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Test X86_64-specific configuration values for errors at compile-time. + */ + +// Emulating RAMPS +#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 ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on LINUX." +#endif + +#if HAS_TMC_SW_SERIAL + #error "TMC220x Software Serial is not supported on LINUX." +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) + #error "POSTMORTEM_DEBUGGING is not yet supported on LINUX." +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h new file mode 100644 index 0000000000..2aeeb52e92 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -0,0 +1,59 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 . + * + */ + +/** + * Support routines for X86_64 + */ + +/** + * Translation of routines & variables used by pinsDebug.h + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS +#define pwm_details(pin) pin = pin // do nothing // print PWM details +#define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin. +#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) +#define digitalRead_mod(p) digitalRead(p) +#define PRINT_PORT(p) +#define GET_ARRAY_PIN(p) pin_array[p].pin +#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin + +// active ADC function/mode/code values for PINSEL registers +constexpr int8_t ADC_pin_mode(pin_t pin) { + return (-1); +} + +int8_t get_pin_mode(pin_t pin) { + if (!VALID_PIN(pin)) return -1; + return 0; +} + +bool GET_PINMODE(pin_t pin) { + int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin + return false; + + return (Gpio::getMode(pin) != 0); //input/output state +} + +bool GET_ARRAY_IS_DIGITAL(pin_t pin) { + return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); +} diff --git a/Marlin/src/HAL/NATIVE_SIM/servo_private.h b/Marlin/src/HAL/NATIVE_SIM/servo_private.h new file mode 100644 index 0000000000..06be1893f6 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/servo_private.h @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 + * Copyright (c) 2009 Michael Margolis. All right reserved. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library 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 + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +/** + * Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers - + * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. + * + * The only modification was to update/delete macros to match the LPC176x. + * + */ + +#include + +// Macros +//values in microseconds +#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo +#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo +#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached +#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds + +#define MAX_SERVOS 4 + +#define INVALID_SERVO 255 // flag indicating an invalid servo index + + +// Types + +typedef struct { + uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin) + uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false +} ServoPin_t; + +typedef struct { + ServoPin_t Pin; + unsigned int pulse_width; // pulse width in microseconds +} ServoInfo_t; + +// Global variables + +extern uint8_t ServoCount; +extern ServoInfo_t servo_info[MAX_SERVOS]; diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h new file mode 100644 index 0000000000..a5138e0ccb --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../../core/macros.h" +#include "../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) + #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently + // needed due to the speed and mode required for communicating with each device being different. + // This requirement can be removed if the SPI access to these devices is updated to use + // spiBeginTransaction. +#endif + +// Onboard SD +//#define SD_SCK_PIN P0_07 +//#define SD_MISO_PIN P0_08 +//#define SD_MOSI_PIN P0_09 +//#define SD_SS_PIN P0_06 + +// External SD +#ifndef SD_SCK_PIN + #define SD_SCK_PIN 50 +#endif +#ifndef SD_MISO_PIN + #define SD_MISO_PIN 51 +#endif +#ifndef SD_MOSI_PIN + #define SD_MOSI_PIN 52 +#endif +#ifndef SD_SS_PIN + #define SD_SS_PIN 53 +#endif +#ifndef SDSS + #define SDSS SD_SS_PIN +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h new file mode 100644 index 0000000000..b3e622f19a --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -0,0 +1,64 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../../../inc/MarlinConfig.h" + +#ifndef LCD_READ_ID + #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) +#endif +#ifndef LCD_READ_ID4 + #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) +#endif + +#define DATASIZE_8BIT 8 +#define DATASIZE_16BIT 16 +#define TFT_IO_DRIVER TFT_SPI + +#define DMA_MINC_ENABLE 1 +#define DMA_MINC_DISABLE 0 + +class TFT_SPI { +private: + static uint32_t ReadID(uint16_t Reg); + static void Transmit(uint16_t Data); + static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + +public: + // static SPIClass SPIx; + + static void Init(); + static uint32_t GetID(); + static bool isBusy(); + static void Abort(); + + static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); + static void DataTransferEnd(); + static void DataTransferAbort(); + + static void WriteData(uint16_t Data); + static void WriteReg(uint16_t Reg); + + static void WriteSequence(uint16_t *Data, uint16_t Count); + // static void WriteMultiple(uint16_t Color, uint16_t Count); + static void WriteMultiple(uint16_t Color, uint32_t Count); +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h new file mode 100644 index 0000000000..9ef1816c7b --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -0,0 +1,80 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(TOUCH_BUTTONS_HW_SPI) + #include +#endif + +#ifndef TOUCH_MISO_PIN + #define TOUCH_MISO_PIN SD_MISO_PIN +#endif +#ifndef TOUCH_MOSI_PIN + #define TOUCH_MOSI_PIN SD_MOSI_PIN +#endif +#ifndef TOUCH_SCK_PIN + #define TOUCH_SCK_PIN SD_SCK_PIN +#endif +#ifndef TOUCH_CS_PIN + #define TOUCH_CS_PIN SD_SS_PIN +#endif +#ifndef TOUCH_INT_PIN + #define TOUCH_INT_PIN -1 +#endif + +#define XPT2046_DFR_MODE 0x00 +#define XPT2046_SER_MODE 0x04 +#define XPT2046_CONTROL 0x80 + +enum XPTCoordinate : uint8_t { + XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE, + XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, +}; + +#if !defined(XPT2046_Z1_THRESHOLD) + #define XPT2046_Z1_THRESHOLD 10 +#endif + +class XPT2046 { +private: + static bool isBusy() { return false; } + + static uint16_t getRawData(const XPTCoordinate coordinate); + static bool isTouched(); + + static inline void DataTransferBegin(); + static inline void DataTransferEnd(); + #if ENABLED(TOUCH_BUTTONS_HW_SPI) + static uint16_t HardwareIO(uint16_t data); + #endif + static uint16_t SoftwareIO(uint16_t data); + static uint16_t IO(uint16_t data = 0); + +public: + #if ENABLED(TOUCH_BUTTONS_HW_SPI) + static SPIClass SPIx; + #endif + + static void Init(); + static bool getRawPoint(int16_t *x, int16_t *y); +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h new file mode 100644 index 0000000000..c61eb29e76 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -0,0 +1,91 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 timers for Linux X86_64 + */ + +#include + +// ------------------------ +// Defines +// ------------------------ + +#define FORCE_INLINE __attribute__((always_inline)) inline + +typedef uint64_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF + +#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals + +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif +#ifndef SYSTICK_TIMER_NUM + #define SYSTICK_TIMER_NUM 2 // Timer Index for Systick +#endif +#define SYSTICK_TIMER_FREQUENCY 1000 + +#define TEMP_TIMER_RATE 1000000 +#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency + +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void TIMER1_IRQHandler() +#endif + +void HAL_timer_init(); +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); + +void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare); +hal_timer_t HAL_timer_get_compare(const uint8_t timer_num); +hal_timer_t HAL_timer_get_count(const uint8_t timer_num); + +void HAL_timer_enable_interrupt(const uint8_t timer_num); +void HAL_timer_disable_interrupt(const uint8_t timer_num); +bool HAL_timer_interrupt_enabled(const uint8_t timer_num); + +#define HAL_timer_isr_prologue(TIMER_NUM) +#define HAL_timer_isr_epilogue(TIMER_NUM) diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp new file mode 100644 index 0000000000..745454394a --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.cpp @@ -0,0 +1,52 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +// adapted from I2C/master/master.c example +// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html + +#ifdef __PLAT_NATIVE_SIM__ + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +uint8_t u8g_i2c_start(const uint8_t sla) { + return 1; +} + +void u8g_i2c_init(const uint8_t clock_option) { +} + +uint8_t u8g_i2c_send_byte(uint8_t data) { + return 1; +} + +void u8g_i2c_stop() { +} + +#ifdef __cplusplus + } +#endif + +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h new file mode 100644 index 0000000000..6d5f91d3ba --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_I2C_routines.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#ifdef __cplusplus + extern "C" { +#endif + +void u8g_i2c_init(const uint8_t clock_options); +//uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos); +uint8_t u8g_i2c_start(uint8_t sla); +uint8_t u8g_i2c_send_byte(uint8_t data); +void u8g_i2c_stop(); + +#ifdef __cplusplus + } +#endif + diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h new file mode 100644 index 0000000000..44ffbfeb90 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +void usleep(uint64_t microsec); +// The following are optional depending on the platform. + +// definitions of HAL specific com and device drivers. +uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); +uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + +// connect U8g com generic com names to the desired driver +#define U8G_COM_SW_SPI u8g_com_sw_spi_fn +#define U8G_COM_ST7920_SW_SPI u8g_com_ST7920_sw_spi_fn + +// let these default for now +#define U8G_COM_HW_SPI u8g_com_null_fn +#define U8G_COM_ST7920_HW_SPI u8g_com_null_fn +#define U8G_COM_SSD_I2C u8g_com_null_fn +#define U8G_COM_PARALLEL u8g_com_null_fn +#define U8G_COM_T6963 u8g_com_null_fn +#define U8G_COM_FAST_PARALLEL u8g_com_null_fn +#define U8G_COM_UC_I2C u8g_com_null_fn + + diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h new file mode 100644 index 0000000000..297361cd44 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_delay.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * LCD delay routines - used by all the drivers. + * + * These are based on the LPC1768 routines. + * + * Couldn't just call exact copies because the overhead + * results in a one microsecond delay taking about 4µS. + */ + +#ifdef __cplusplus + extern "C" { +#endif + +void U8g_delay(int msec); +void u8g_MicroDelay(); +void u8g_10MicroDelay(); + +#ifdef __cplusplus + } +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp new file mode 100644 index 0000000000..3b5acc1656 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.cpp @@ -0,0 +1,52 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about about 25% of the CPU's time. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../fastio.h" +#include "LCD_pin_routines.h" + +#ifdef __cplusplus + extern "C" { +#endif +void u8g_SetPinOutput(uint8_t internal_pin_number){SET_DIR_OUTPUT(internal_pin_number);} +void u8g_SetPinInput(uint8_t internal_pin_number){SET_DIR_INPUT(internal_pin_number);} +void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status){WRITE_PIN(pin, pin_status);} +uint8_t u8g_GetPinLevel(uint8_t pin){return READ_PIN(pin);} +void usleep(uint64_t microsec){ +assert(false); // why we here? +} +#ifdef __cplusplus + } +#endif + +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h new file mode 100644 index 0000000000..c27c84e8c3 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h @@ -0,0 +1,46 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Low level pin manipulation routines - used by all the drivers. + * + * These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines. + * + * Couldn't just call exact copies because the overhead killed the LCD update speed + * With an intermediate level the softspi was running in the 10-20kHz range which + * resulted in using about about 25% of the CPU's time. + */ + + +#ifdef __cplusplus + extern "C" { +#endif + +void u8g_SetPinOutput(uint8_t internal_pin_number); +void u8g_SetPinInput(uint8_t internal_pin_number); +void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status); +uint8_t u8g_GetPinLevel(uint8_t pin); + +#ifdef __cplusplus + } +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp new file mode 100644 index 0000000000..e95c6ebfbd --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -0,0 +1,171 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Based on u8g_com_st7920_hw_spi.c + * + * Universal 8bit Graphics Library + * + * Copyright (c) 2011, olikraus@gmail.com + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(U8GLIB_ST7920) + +#include +#include "../../shared/Delay.h" + +#undef SPI_SPEED +#define SPI_SPEED 6 +#define SPI_DELAY_CYCLES (1 + SPI_SPEED * 10) + +static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL; +static uint8_t SPI_speed = 0; + +static uint8_t swSpiTransfer(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++) { + WRITE_PIN(mosi_pin, !!(b & 0x80)); + DELAY_CYCLES(SPI_SPEED); + WRITE_PIN(sck_pin, HIGH); + DELAY_CYCLES(SPI_SPEED); + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + WRITE_PIN(sck_pin, LOW); + DELAY_CYCLES(SPI_SPEED); + } + return b; +} + +static uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) { + WRITE_PIN(mosi_pin, HIGH); + WRITE_PIN(sck_pin, LOW); + return spiRate; +} + +static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) { + static uint8_t rs_last_state = 255; + if (rs != rs_last_state) { + // Transfer Data (FA) or Command (F8) + swSpiTransfer(rs ? 0x0FA : 0x0F8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); + rs_last_state = rs; + DELAY_US(40); // Give the controller time to process the data: 20 is bad, 30 is OK, 40 is safe + } + swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); + swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); +} +#ifdef __cplusplus + extern "C" { +#endif + +uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + SCK_pin_ST7920_HAL = u8g->pin_list[U8G_PI_SCK]; + MOSI_pin_ST7920_HAL_HAL = u8g->pin_list[U8G_PI_MOSI]; + + u8g_SetPIOutput(u8g, U8G_PI_CS); + u8g_SetPIOutput(u8g, U8G_PI_SCK); + u8g_SetPIOutput(u8g, U8G_PI_MOSI); + u8g_Delay(5); + + SPI_speed = swSpiInit(SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL); + + u8g_SetPILevel(u8g, U8G_PI_CS, 0); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); + u8g_SetPILevel(u8g, U8G_PI_MOSI, 0); + + u8g->pin_list[U8G_PI_A0_STATE] = 0; /* initial RS state: command mode */ + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g->pin_list[U8G_PI_A0_STATE] = arg_val; + break; + + case U8G_COM_MSG_CHIP_SELECT: + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS]) u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t*) arg_ptr; + while (arg_val > 0) { + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++); + arg_val--; + } + } + break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t*) arg_ptr; + while (arg_val > 0) { + u8g_com_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++); + arg_val--; + } + } + break; + } + return 1; +} +#ifdef __cplusplus + } +#endif + +#endif // U8GLIB_ST7920 +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp new file mode 100644 index 0000000000..8e0ac9c7df --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -0,0 +1,215 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Based on u8g_com_std_sw_spi.c + * + * Universal 8bit Graphics Library + * + * Copyright (c) 2015, olikraus@gmail.com + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) + +#undef SPI_SPEED +#define SPI_SPEED 2 // About 2 MHz + +#include +#include + +#ifdef __cplusplus + extern "C" { +#endif + +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 ) { + LOOP_L_N(i, 8) { + if (spi_speed == 0) { + WRITE_PIN(mosi_pin, !!(b & 0x80)); + WRITE_PIN(sck_pin, HIGH); + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + WRITE_PIN(sck_pin, LOW); + } + else { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + LOOP_L_N(j, spi_speed) + WRITE_PIN(mosi_pin, state); + + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + WRITE_PIN(sck_pin, HIGH); + + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + + LOOP_L_N(j, spi_speed) + WRITE_PIN(sck_pin, LOW); + } + } + + return b; +} + +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 ) { + + LOOP_L_N(i, 8) { + const uint8_t state = (b & 0x80) ? HIGH : LOW; + if (spi_speed == 0) { + WRITE_PIN(sck_pin, LOW); + WRITE_PIN(mosi_pin, state); + WRITE_PIN(mosi_pin, state); // need some setup time + WRITE_PIN(sck_pin, HIGH); + } + else { + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + WRITE_PIN(sck_pin, LOW); + + LOOP_L_N(j, spi_speed) + WRITE_PIN(mosi_pin, state); + + LOOP_L_N(j, spi_speed) + WRITE_PIN(sck_pin, HIGH); + } + b <<= 1; + if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; + } + + return b; +} + +static uint8_t SPI_speed = 0; + +static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const uint8_t mosi_pin) { + return spi_speed; +} + +static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { + #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); + #else + swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); + #endif +} + +uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + switch (msg) { + case U8G_COM_MSG_INIT: + u8g_SetPIOutput(u8g, U8G_PI_SCK); + u8g_SetPIOutput(u8g, U8G_PI_MOSI); + u8g_SetPIOutput(u8g, U8G_PI_CS); + u8g_SetPIOutput(u8g, U8G_PI_A0); + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET); + SPI_speed = swSpiInit(SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); + u8g_SetPILevel(u8g, U8G_PI_MOSI, 0); + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_CHIP_SELECT: + #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + u8g_SetPILevel(u8g, U8G_PI_CS, LOW); + } + else { + u8g_SetPILevel(u8g, U8G_PI_CS, HIGH); + u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive + } + #else + u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val); + #endif + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); + arg_val--; + } + } + break; + + case U8G_COM_MSG_WRITE_SEQ_P: { + uint8_t *ptr = (uint8_t *)arg_ptr; + while (arg_val > 0) { + u8g_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_SetPILevel(u8g, U8G_PI_A0, arg_val); + break; + } + return 1; +} + +#ifdef __cplusplus + } +#endif + +#elif !ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB + #include + uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {return 0;} +#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 +#endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/NATIVE_SIM/watchdog.h b/Marlin/src/HAL/NATIVE_SIM/watchdog.h new file mode 100644 index 0000000000..4e404c3887 --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/watchdog.h @@ -0,0 +1,27 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define WDT_TIMEOUT 4000000 // 4 second timeout + +void watchdog_init(); +void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index e0617bdf7f..0b1b305f6d 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -43,6 +43,8 @@ #define HAL_PATH(PATH, NAME) XSTR(PATH/ESP32/NAME) #elif defined(__PLAT_LINUX__) #define HAL_PATH(PATH, NAME) XSTR(PATH/LINUX/NAME) +#elif defined(__PLAT_NATIVE_SIM__) + #define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME) #elif defined(__SAMD51__) #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) #else diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index 3174968c1b..04df35d88d 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -160,7 +160,7 @@ void calibrate_delay_loop(); // Delay in microseconds #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) -#elif defined(__PLAT_LINUX__) || defined(ESP32) +#elif defined(ESP32) || defined(__PLAT_LINUX__) || defined(__PLAT_NATIVE_SIM__) // DELAY_CYCLES specified inside platform diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index ee6c0e6eae..7ceb70c22c 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -304,6 +304,9 @@ void serial_echopair_PGM(PGM_P const s_P, unsigned int v); void serial_echopair_PGM(PGM_P const s_P, unsigned long v); inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); } inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); } +#if __INTPTR_WIDTH__ != __SIZE_WIDTH__ + inline void serial_echopair_PGM(PGM_P const s_P, size_t v) { serial_echopair_PGM(s_P, (long int)v); } +#endif void serial_echo_start(); void serial_error_start(); diff --git a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h index 98a8f0a98a..a30dd4ca17 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -97,6 +97,11 @@ #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn #define U8G_COM_SSD_I2C_HAL u8g_com_HAL_LPC1768_ssd_hw_i2c_fn +#elif defined(__PLAT_NATIVE_SIM__) + uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); + #define U8G_COM_HAL_SW_SPI_FN u8g_com_sw_spi_fn + #define U8G_COM_ST7920_HAL_SW_SPI u8g_com_ST7920_sw_spi_fn #endif #ifndef U8G_COM_HAL_SW_SPI_FN diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index 6b973241fe..5e1dfae5d1 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -360,7 +360,7 @@ void disp_gcode_icon(uint8_t file_num) { uint32_t lv_open_gcode_file(char *path) { #if ENABLED(SDSUPPORT) uint32_t *ps4; - uint32_t pre_sread_cnt = UINT32_MAX; + uintptr_t pre_sread_cnt = UINTPTR_MAX; char *cur_name; cur_name = strrchr(path, '/'); @@ -370,7 +370,7 @@ uint32_t lv_open_gcode_file(char *path) { ps4 = (uint32_t *)strstr((char *)public_buf, ";simage:"); // Ignore the beginning message of gcode file if (ps4) { - pre_sread_cnt = (uint32_t)ps4 - (uint32_t)((uint32_t *)(&public_buf[0])); + pre_sread_cnt = (uintptr_t)ps4 - (uintptr_t)((uint32_t *)(&public_buf[0])); card.setIndex(pre_sread_cnt); } return pre_sread_cnt; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 1c1e5cc1f5..aae6e62a66 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -560,11 +560,11 @@ char *creat_title_text() { #if HAS_GCODE_PREVIEW - uint32_t gPicturePreviewStart = 0; + uintptr_t gPicturePreviewStart = 0; void preview_gcode_prehandle(char *path) { #if ENABLED(SDSUPPORT) - uint32_t pre_read_cnt = 0; + uintptr_t pre_read_cnt = 0; uint32_t *p1; char *cur_name; @@ -575,7 +575,7 @@ char *creat_title_text() { p1 = (uint32_t *)strstr((char *)public_buf, ";simage:"); if (p1) { - pre_read_cnt = (uint32_t)p1 - (uint32_t)((uint32_t *)(&public_buf[0])); + pre_read_cnt = (uintptr_t)p1 - (uintptr_t)((uint32_t *)(&public_buf[0])); To_pre_view = pre_read_cnt; gcode_preview_over = true; @@ -606,7 +606,7 @@ char *creat_title_text() { uint32_t br = card.read(public_buf, 400); uint32_t *p1 = (uint32_t *)strstr((char *)public_buf, ";gimage:"); if (p1) { - gPicturePreviewStart += (uint32_t)p1 - (uint32_t)((uint32_t *)(&public_buf[0])); + gPicturePreviewStart += (uintptr_t)p1 - (uintptr_t)((uint32_t *)(&public_buf[0])); break; } else { diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 2127b23a15..cfd6db15fd 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -398,7 +398,7 @@ lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_ // find small image size card.read(public_buf, 512); public_buf[511] = '\0'; - char* eol = strpbrk((const char*)public_buf, "\n\r"); + const char* eol = strpbrk((const char*)public_buf, "\n\r"); small_image_size = (uintptr_t)eol - (uintptr_t)((uint32_t *)(&public_buf[0])) + 1; return LV_FS_RES_OK; } @@ -530,4 +530,10 @@ void lv_encoder_pin_init() { #endif // HAS_ENCODER_ACTION +#if __PLAT_NATIVE_SIM__ + #include + typedef void (*lv_log_print_g_cb_t)(lv_log_level_t level, const char *, uint32_t, const char *); + extern "C" void lv_log_register_print_cb(lv_log_print_g_cb_t print_cb) {} +#endif + #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 3930279c94..a0f8c1648c 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -49,6 +49,10 @@ #define BOARD_INFO_NAME "RAMPS 1.4" #endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "SimRap 1.4" +#endif + #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif @@ -208,6 +212,7 @@ // #define SDSS 53 #define LED_PIN 13 +#define NEOPIXEL_PIN 71 #ifndef FILWIDTH_PIN #define FILWIDTH_PIN 5 // Analog Input on AUX2 @@ -215,7 +220,7 @@ // define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN 21 #endif #ifndef PS_ON_PIN @@ -389,7 +394,54 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_WIRED_LCD +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI) + + #define TFT_A0_PIN 43 + #define TFT_CS_PIN 49 + #define TFT_DC_PIN 43 + #define TFT_SCK_PIN SD_SCK_PIN + #define TFT_MOSI_PIN SD_MOSI_PIN + #define TFT_MISO_PIN SD_MISO_PIN + #define LCD_USE_DMA_SPI + + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 + #define BEEPER_PIN 42 + + #define TOUCH_CS_PIN 33 + #define SD_DETECT_PIN 41 + + #define HAS_SPI_FLASH 1 + #if HAS_SPI_FLASH + #define SPI_DEVICE 1 + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define W25QXX_CS_PIN 31 + #define W25QXX_MOSI_PIN SD_MOSI_PIN + #define W25QXX_MISO_PIN SD_MISO_PIN + #define W25QXX_SCK_PIN SD_SCK_PIN + #endif + + #define TFT_BUFFER_SIZE 0xFFFF + #ifndef TFT_DRIVER + #define TFT_DRIVER ST7796 + #endif + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION 63934 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION 63598 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET -1 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET -20 + #endif + + #define BTN_BACK 70 + +#elif HAS_WIRED_LCD // // LCD Display output pins @@ -622,14 +674,18 @@ #define BTN_EN1 37 #define BTN_EN2 35 #define BTN_ENC 31 + #define SD_DETECT_PIN 41 #endif #if ENABLED(G3D_PANEL) #define SD_DETECT_PIN 49 #define KILL_PIN 41 #endif - #endif + + // CUSTOM SIMULATOR INPUTS + #define BTN_BACK 70 + #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 4c773d1e76..a4ef4f080c 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -681,7 +681,7 @@ // #elif MB(LINUX_RAMPS) - #include "linux/pins_RAMPS_LINUX.h" // Linux env:linux_native + #include "linux/pins_RAMPS_LINUX.h" // Native or Simulation lin:linux_native mac:simulator_macos_debug mac:simulator_macos_release win:simulator_windows lin:simulator_linux_debug lin:simulator_linux_release #else diff --git a/Marlin/src/sd/SdFatUtil.cpp b/Marlin/src/sd/SdFatUtil.cpp index 7d9f33dc50..e6f7a9a013 100644 --- a/Marlin/src/sd/SdFatUtil.cpp +++ b/Marlin/src/sd/SdFatUtil.cpp @@ -48,7 +48,7 @@ return &top - reinterpret_cast(sbrk(0)); } -#else +#elif defined(__AVR__) extern char* __brkval; extern char __bss_end; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 90c39feaf8..f3a913ced3 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -939,7 +939,7 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con while (atom_ptr) { // Find next subdirectory delimiter - char * const name_end = strchr(atom_ptr, '/'); + const char * const name_end = strchr(atom_ptr, '/'); // Last atom in the path? Item found. if (name_end <= atom_ptr) break; diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index 01ee89e25e..83dfeca879 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -215,7 +215,13 @@ def search_compiler(): # Find the current platform compiler by searching the $PATH # which will be in a platformio toolchain bin folder path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) - gcc = "g++" + + # See if the environment provides a default compiler + try: + gcc = env.GetProjectOption('custom_deps_gcc') + except: + gcc = "g++" + if env['PLATFORM'] == 'win32': path_separator = ';' path_regex += r'.*\\bin' @@ -241,6 +247,8 @@ def search_compiler(): return filepath filepath = env.get('CXX') + if filepath == 'CC': + filepath = gcc blab("Couldn't find a compiler! Fallback to %s" % filepath) return filepath diff --git a/buildroot/share/PlatformIO/scripts/simulator.py b/buildroot/share/PlatformIO/scripts/simulator.py new file mode 100644 index 0000000000..fb9d93cceb --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/simulator.py @@ -0,0 +1,52 @@ +# +# PlatformIO pre: script for simulator builds +# + +# Get the environment thus far for the build +Import("env") + +#print(env.Dump()) + +# +# Give the binary a distinctive name +# + +env['PROGNAME'] = "MarlinSimulator" + +# +# If Xcode is installed add the path to its Frameworks folder, +# or if Mesa is installed try to use its GL/gl.h. +# + +import sys +if sys.platform == 'darwin': + + # + # Silence half of the ranlib warnings. (No equivalent for 'ARFLAGS') + # + env['RANLIBFLAGS'] += [ "-no_warning_for_no_symbols" ] + + # Default paths for Xcode and a lucky GL/gl.h dropped by Mesa + xcode_path = "/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX.sdk/System/Library/Frameworks" + mesa_path = "/opt/local/include/GL/gl.h" + + import os.path + + if os.path.exists(xcode_path): + + env['BUILD_FLAGS'] += [ "-F" + xcode_path ] + print("Using OpenGL framework headers from Xcode.app") + + elif os.path.exists(mesa_path): + + env['BUILD_FLAGS'] += [ '-D__MESA__' ] + print("Using OpenGL header from", mesa_path) + + else: + + print("\n\nNo OpenGL headers found. Install Xcode for matching headers, or use 'sudo port install mesa' to get a GL/gl.h.\n\n") + + # Break out of the PIO build immediately + sys.exit(1) + +env.AddCustomTarget("upload", "$BUILD_DIR/${PROGNAME}", "$BUILD_DIR/${PROGNAME}") diff --git a/ini/native.ini b/ini/native.ini index dbdfd26f8b..b40ea836da 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -21,3 +21,110 @@ build_unflags = -Wall lib_ldf_mode = off lib_deps = src_filter = ${common.default_src_filter} + + +# +# Native Simulation +# Builds with a small subset of available features +# Required system libraries: SDL2, SDL2-net, OpenGL, GLM +# +# Tested with Linux (Mint 20) : gcc [9.3.0, 10.2.0]: libsdl2-dev[2.0.10], libsdl2-net-dev[2.0.1], libglm-dev[0.9.9.7, 0.9.9.8] +# +# Debugging with gdb in vscode is as easy as adding the launch task as usual, but platformio +# will randomly remove your task when it recreates its tasks from a template. Add your gdb +# launch task to '~/.platformio/penv/lib/python{PYTHON_VERSION}/site-packages/platformio/ide/tpls/vscode/.vscode' +# to avoid this until platformio updates. +# +[simulator_common] +platform = native +framework = +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g +src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align +release_flags = -g0 -O3 -flto +debug_build_flags = -fstack-protector-strong -g -g3 -ggdb +lib_compat_mode = off +src_filter = ${common.default_src_filter} + + +lib_deps = ${common.lib_deps} + MarlinSimUI=https://github.com/p3p/MarlinSimUI.git + Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip + LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/simulator.py + + +[simulator_linux] +extends = simulator_common +build_flags = ${simulator_common.build_flags} -ldl -lpthread -lSDL2 -lSDL2_net -lGL + +[env:simulator_linux_debug] +platform = ${simulator_linux.platform} +extends = simulator_linux +build_type = debug + +[env:simulator_linux_release] +platform = ${simulator_linux.platform} +extends = simulator_linux +build_type = release +build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} + +# +# Simulator for macOS (MacPorts) +# +# sudo port install gcc10 gdb glm libsdl2 freetype +# sudo port install ld64 @3_3 +ld64_xcode +# sudo port uninstall ld64 ld64-latest +# cd /opt/local/bin +# sudo rm -f gcc g++ cc +# sudo ln gcc-mp-10 gcc ; sudo ln g++-mp-10 g++ ; sudo ln g++ cc +# cd - +# +# Use 'sudo port install mesa' to get a if no Xcode is installed. +# If Xcode is installed be sure to run `xcode-select --install` first. +# +# For VSCode debugging paste the block below near the top of launch.json. +# NOTE: The PlatformIO VSCode extension will remove it when regenerating launch.json. +# +# { "name": "Debug Sim", +# "type": "cppdbg", +# "request": "launch", +# "program": "${workspaceFolder}/.pio/build/simulator_macos/MarlinSimulator", +# "miDebuggerPath": "/opt/local/bin/ggdb", +# "MIMode": "gdb", +# "cwd": "${workspaceFolder}/.pio/build/simulator_macos" }, +# +[simulator_macos] +build_unflags = -lGL +custom_verbose = 0 +build_flags = + -I/opt/local/include + -I/opt/local/include/freetype2 + -I/opt/local/include/SDL2/ + -L/opt/local/lib + -Wl,-framework,OpenGl + -Wl,-framework,CoreFoundation + -lSDL2 + +[env:simulator_macos_debug] +platform = ${env:simulator_linux_release.platform} +extends = env:simulator_linux_debug +build_flags = ${env:simulator_linux_debug.build_flags} ${simulator_macos.build_flags} -ggdb -Og -D_THREAD_SAFE +build_unflags = ${simulator_macos.build_unflags} + +[env:simulator_macos_release] +platform = ${env:simulator_linux_release.platform} +extends = env:simulator_linux_release +build_flags = ${env:simulator_linux_release.build_flags} ${simulator_macos.build_flags} +build_unflags = ${simulator_macos.build_unflags} + +# +# Simulator for Windows 10 +# +# MSYS2 mingw-w64-x86_64 with these packages: +# pacman -S --needed base-devel mingw-w64-x86_64-toolchain mingw64/mingw-w64-x86_64-glm mingw64/mingw-w64-x86_64-SDL2 mingw64/mingw-w64-x86_64-SDL2_net +# +[env:simulator_windows] +platform = ${simulator_common.platform} +extends = simulator_common +src_build_flags = ${simulator_common.src_build_flags} -fpermissive +build_flags = ${simulator_common.build_flags} ${simulator_common.debug_build_flags} -fno-stack-protector -Wl,-subsystem,windows -ldl -lmingw32 -lSDL2main -lSDL2 -lSDL2_net -lopengl32 -lssp +build_type = debug From 6bc9c09c1fe9957d7f48cf59f12724839c143215 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 22 Jul 2021 01:00:19 +0000 Subject: [PATCH 0441/2168] [cron] Bump distribution date (2021-07-22) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index bd8473bee3..2daf091d26 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-21" +//#define STRING_DISTRIBUTION_DATE "2021-07-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ef569263f7..4f655a7d29 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 "2021-07-21" + #define STRING_DISTRIBUTION_DATE "2021-07-22" #endif /** From 283d70bfd3149f6f16b088f825851c8ee433182a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 23 Jul 2021 01:14:46 +0000 Subject: [PATCH 0442/2168] [cron] Bump distribution date (2021-07-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 2daf091d26..aad3b0c41f 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-22" +//#define STRING_DISTRIBUTION_DATE "2021-07-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4f655a7d29..368f7b889f 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 "2021-07-22" + #define STRING_DISTRIBUTION_DATE "2021-07-23" #endif /** From 2c49283e97f4bb9cac9577af7c38bcf5e0e06826 Mon Sep 17 00:00:00 2001 From: chendo Date: Fri, 23 Jul 2021 13:53:00 +1000 Subject: [PATCH 0443/2168] =?UTF-8?q?=E2=9C=A8=20D576=20Buffer=20Monitorin?= =?UTF-8?q?g=20(#19674)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 8 + Marlin/src/MarlinCore.cpp | 1 + Marlin/src/gcode/gcode.h | 2 + Marlin/src/gcode/gcode_d.cpp | 451 +++++++++++++------------ Marlin/src/gcode/queue.cpp | 75 +++- Marlin/src/gcode/queue.h | 40 +++ buildroot/tests/STM32F103RET6_creality | 2 +- 7 files changed, 366 insertions(+), 213 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d404d0d19c..7034632421 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4174,6 +4174,14 @@ // Enable Marlin dev mode which adds some special commands //#define MARLIN_DEV_MODE +#if ENABLED(MARLIN_DEV_MODE) + /** + * D576 - Buffer Monitoring + * To help diagnose print quality issues stemming from empty command buffers. + */ + //#define BUFFER_MONITORING +#endif + /** * Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial. * When running in the debugger it will break for debugging. This is useful to help understand diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 07a6a31b94..82ef44f606 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -868,6 +868,7 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_reporter.tick()); TERN_(AUTO_REPORT_SD_STATUS, card.auto_reporter.tick()); TERN_(AUTO_REPORT_POSITION, position_auto_reporter.tick()); + TERN_(BUFFER_MONITORING, queue.auto_report_buffer_statistics()); } #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6b9d0eb47d..769b496f22 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -241,6 +241,7 @@ * M553 - Get or set IP netmask. (Requires enabled Ethernet port) * M554 - Get or set IP gateway. (Requires enabled Ethernet port) * M569 - Enable stealthChop on an axis. (Requires at least one _DRIVER_TYPE to be TMC2130/2160/2208/2209/5130/5160) + * M575 - Change the serial baud rate. (Requires BAUD_RATE_GCODE) * M600 - Pause for filament change: "M600 X Y Z E L". (Requires ADVANCED_PAUSE_FEATURE) * M603 - Configure filament change: "M603 T U L". (Requires ADVANCED_PAUSE_FEATURE) * M605 - Set Dual X-Carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) @@ -297,6 +298,7 @@ * M997 - Perform in-application firmware update * M999 - Restart after being stopped by error * D... - Custom Development G-code. Add hooks to 'gcode_D.cpp' for developers to test features. (Requires MARLIN_DEV_MODE) + * D576 - Set buffer monitoring options. (Requires BUFFER_MONITORING) * * "T" Codes * diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 52a273964a..b317a17815 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -23,248 +23,279 @@ #if ENABLED(MARLIN_DEV_MODE) - #include "gcode.h" - #include "../module/settings.h" - #include "../module/temperature.h" - #include "../libs/hex_print.h" - #include "../HAL/shared/eeprom_if.h" - #include "../HAL/shared/Delay.h" - #include "../sd/cardreader.h" - #include "../MarlinCore.h" // for kill +#include "gcode.h" - extern void dump_delay_accuracy_check(); +#if ENABLED(BUFFER_MONITORING) + #include "queue.h" +#endif - /** - * Dn: G-code for development and testing - * - * See https://reprap.org/wiki/G-code#D:_Debug_codes - * - * Put whatever else you need here to test ongoing development. - */ - void GcodeSuite::D(const int16_t dcode) { - switch (dcode) { +#include "../module/settings.h" +#include "../module/temperature.h" +#include "../libs/hex_print.h" +#include "../HAL/shared/eeprom_if.h" +#include "../HAL/shared/Delay.h" +#include "../sd/cardreader.h" +#include "../MarlinCore.h" // for kill - case -1: - for (;;) { /* loop forever (watchdog reset) */ } +extern void dump_delay_accuracy_check(); - case 0: - HAL_reboot(); - break; +/** + * Dn: G-code for development and testing + * + * See https://reprap.org/wiki/G-code#D:_Debug_codes + * + * Put whatever else you need here to test ongoing development. + */ +void GcodeSuite::D(const int16_t dcode) { + switch (dcode) { - case 10: - kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P')); - break; + case -1: + for (;;) { /* loop forever (watchdog reset) */ } - case 1: { - // Zero or pattern-fill the EEPROM data - #if ENABLED(EEPROM_SETTINGS) - persistentStore.access_start(); - size_t total = persistentStore.capacity(); - int pos = 0; - const uint8_t value = 0x0; - while (total--) persistentStore.write_data(pos, &value, 1); - persistentStore.access_finish(); - #else - settings.reset(); - settings.save(); - #endif - HAL_reboot(); - } break; + case 0: + HAL_reboot(); + break; - case 2: { // D2 Read / Write SRAM - #define SRAM_SIZE 8192 - uint8_t *pointer = parser.hex_adr_val('A'); - uint16_t len = parser.ushortval('C', 1); - uintptr_t addr = (uintptr_t)pointer; - NOMORE(addr, size_t(SRAM_SIZE - 1)); - NOMORE(len, SRAM_SIZE - addr); - if (parser.seenval('X')) { - // Write the hex bytes after the X - uint16_t val = parser.hex_val('X'); - while (len--) { - *pointer = val; - pointer++; - } - } - else { - while (len--) print_hex_byte(*(pointer++)); - SERIAL_EOL(); - } - } break; + case 10: + kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P')); + break; + case 1: { + // Zero or pattern-fill the EEPROM data #if ENABLED(EEPROM_SETTINGS) - case 3: { // D3 Read / Write EEPROM - uint8_t *pointer = parser.hex_adr_val('A'); - uint16_t len = parser.ushortval('C', 1); - uintptr_t addr = (uintptr_t)pointer; - NOMORE(addr, size_t(persistentStore.capacity() - 1)); - NOMORE(len, persistentStore.capacity() - addr); - if (parser.seenval('X')) { - uint16_t val = parser.hex_val('X'); - #if ENABLED(EEPROM_SETTINGS) - persistentStore.access_start(); - while (len--) { - int pos = 0; - persistentStore.write_data(pos, (uint8_t *)&val, sizeof(val)); - } - SERIAL_EOL(); - persistentStore.access_finish(); - #else - SERIAL_ECHOLNPGM("NO EEPROM"); - #endif - } - else { - // Read bytes from EEPROM - #if ENABLED(EEPROM_SETTINGS) - persistentStore.access_start(); - int pos = 0; - uint8_t val; - while (len--) if (!persistentStore.read_data(pos, &val, 1)) print_hex_byte(val); - SERIAL_EOL(); - persistentStore.access_finish(); - #else - SERIAL_ECHOLNPGM("NO EEPROM"); - len = 0; - #endif - SERIAL_EOL(); - } - } break; + persistentStore.access_start(); + size_t total = persistentStore.capacity(); + int pos = 0; + const uint8_t value = 0x0; + while (total--) persistentStore.write_data(pos, &value, 1); + persistentStore.access_finish(); + #else + settings.reset(); + settings.save(); #endif + HAL_reboot(); + } break; - case 4: { // D4 Read / Write PIN - //const bool is_out = parser.boolval('F'); - //const uint8_t pin = parser.byteval('P'), - // val = parser.byteval('V', LOW); - if (parser.seenval('X')) { - // TODO: Write the hex bytes after the X - //while (len--) { - //} + case 2: { // D2 Read / Write SRAM + #define SRAM_SIZE 8192 + uint8_t *pointer = parser.hex_adr_val('A'); + uint16_t len = parser.ushortval('C', 1); + uintptr_t addr = (uintptr_t)pointer; + NOMORE(addr, size_t(SRAM_SIZE - 1)); + NOMORE(len, SRAM_SIZE - addr); + if (parser.seenval('X')) { + // Write the hex bytes after the X + uint16_t val = parser.hex_val('X'); + while (len--) { + *pointer = val; + pointer++; } - else { - //while (len--) { - //// TODO: Read bytes from EEPROM - // print_hex_byte(eeprom_read_byte(adr++)); - //} - SERIAL_EOL(); - } - } break; + } + else { + while (len--) print_hex_byte(*(pointer++)); + SERIAL_EOL(); + } + } break; - case 5: { // D5 Read / Write onboard Flash - #define FLASH_SIZE 1024 + #if ENABLED(EEPROM_SETTINGS) + case 3: { // D3 Read / Write EEPROM uint8_t *pointer = parser.hex_adr_val('A'); uint16_t len = parser.ushortval('C', 1); uintptr_t addr = (uintptr_t)pointer; - NOMORE(addr, size_t(FLASH_SIZE - 1)); - NOMORE(len, FLASH_SIZE - addr); + NOMORE(addr, size_t(persistentStore.capacity() - 1)); + NOMORE(len, persistentStore.capacity() - addr); if (parser.seenval('X')) { - // TODO: Write the hex bytes after the X - //while (len--) {} + uint16_t val = parser.hex_val('X'); + #if ENABLED(EEPROM_SETTINGS) + persistentStore.access_start(); + while (len--) { + int pos = 0; + persistentStore.write_data(pos, (uint8_t *)&val, sizeof(val)); + } + SERIAL_EOL(); + persistentStore.access_finish(); + #else + SERIAL_ECHOLNPGM("NO EEPROM"); + #endif } else { - //while (len--) { - //// TODO: Read bytes from EEPROM - // print_hex_byte(eeprom_read_byte(adr++)); - //} + // Read bytes from EEPROM + #if ENABLED(EEPROM_SETTINGS) + persistentStore.access_start(); + int pos = 0; + uint8_t val; + while (len--) if (!persistentStore.read_data(pos, &val, 1)) print_hex_byte(val); + SERIAL_EOL(); + persistentStore.access_finish(); + #else + SERIAL_ECHOLNPGM("NO EEPROM"); + len = 0; + #endif SERIAL_EOL(); } } break; + #endif - case 6: // D6 Check delay loop accuracy - dump_delay_accuracy_check(); - break; + case 4: { // D4 Read / Write PIN + //const bool is_out = parser.boolval('F'); + //const uint8_t pin = parser.byteval('P'), + // val = parser.byteval('V', LOW); + if (parser.seenval('X')) { + // TODO: Write the hex bytes after the X + //while (len--) { + //} + } + else { + //while (len--) { + //// TODO: Read bytes from EEPROM + // print_hex_byte(eeprom_read_byte(adr++)); + //} + SERIAL_EOL(); + } + } break; - case 7: // D7 dump the current serial port type (hence configuration) - SERIAL_ECHOLNPAIR("Current serial configuration RX_BS:", RX_BUFFER_SIZE, ", TX_BS:", TX_BUFFER_SIZE); - SERIAL_ECHOLN(gtn(&SERIAL_IMPL)); - break; + case 5: { // D5 Read / Write onboard Flash + #define FLASH_SIZE 1024 + uint8_t *pointer = parser.hex_adr_val('A'); + uint16_t len = parser.ushortval('C', 1); + uintptr_t addr = (uintptr_t)pointer; + NOMORE(addr, size_t(FLASH_SIZE - 1)); + NOMORE(len, FLASH_SIZE - addr); + if (parser.seenval('X')) { + // TODO: Write the hex bytes after the X + //while (len--) {} + } + else { + //while (len--) { + //// TODO: Read bytes from EEPROM + // print_hex_byte(eeprom_read_byte(adr++)); + //} + SERIAL_EOL(); + } + } break; - case 100: { // D100 Disable heaters and attempt a hard hang (Watchdog Test) - SERIAL_ECHOLNPGM("Disabling heaters and attempting to trigger Watchdog"); - SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); - thermalManager.disable_all_heaters(); - delay(1000); // Allow time to print - DISABLE_ISRS(); - // Use a low-level delay that does not rely on interrupts to function - // Do not spin forever, to avoid thermal risks if heaters are enabled and - // watchdog does not work. - for (int i = 10000; i--;) DELAY_US(1000UL); - ENABLE_ISRS(); - SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); + case 6: // D6 Check delay loop accuracy + dump_delay_accuracy_check(); + break; + + case 7: // D7 dump the current serial port type (hence configuration) + SERIAL_ECHOLNPAIR("Current serial configuration RX_BS:", RX_BUFFER_SIZE, ", TX_BS:", TX_BUFFER_SIZE); + SERIAL_ECHOLN(gtn(&SERIAL_IMPL)); + break; + + case 100: { // D100 Disable heaters and attempt a hard hang (Watchdog Test) + SERIAL_ECHOLNPGM("Disabling heaters and attempting to trigger Watchdog"); + SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); + thermalManager.disable_all_heaters(); + delay(1000); // Allow time to print + DISABLE_ISRS(); + // Use a low-level delay that does not rely on interrupts to function + // Do not spin forever, to avoid thermal risks if heaters are enabled and + // watchdog does not work. + for (int i = 10000; i--;) DELAY_US(1000UL); + ENABLE_ISRS(); + SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); + } break; + + #if ENABLED(SDSUPPORT) + + case 101: { // D101 Test SD Write + card.openFileWrite("test.gco"); + if (!card.isFileOpen()) { + SERIAL_ECHOLNPAIR("Failed to open test.gco to write."); + return; + } + __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; + + uint16_t c; + for (c = 0; c < COUNT(buf); c++) + buf[c] = 'A' + (c % ('Z' - 'A')); + + c = 1024 * 4; + while (c--) { + TERN_(USE_WATCHDOG, watchdog_refresh()); + card.write(buf, COUNT(buf)); + } + SERIAL_ECHOLNPGM(" done"); + card.closefile(); } break; - #if ENABLED(SDSUPPORT) - - case 101: { // D101 Test SD Write - card.openFileWrite("test.gco"); - if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open test.gco to write."); - return; - } - __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; - - uint16_t c; - for (c = 0; c < COUNT(buf); c++) - buf[c] = 'A' + (c % ('Z' - 'A')); - - c = 1024 * 4; - while (c--) { - TERN_(USE_WATCHDOG, watchdog_refresh()); - card.write(buf, COUNT(buf)); - } - SERIAL_ECHOLNPGM(" done"); - card.closefile(); - } break; - - case 102: { // D102 Test SD Read - char testfile[] = "test.gco"; - card.openFileRead(testfile); - if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open test.gco to read."); - return; - } - __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; - uint16_t c = 1024 * 4; - while (c--) { - TERN_(USE_WATCHDOG, watchdog_refresh()); - card.read(buf, COUNT(buf)); - bool error = false; - for (uint16_t i = 0; i < COUNT(buf); i++) { - if (buf[i] != ('A' + (i % ('Z' - 'A')))) { - error = true; - break; - } - } - if (error) { - SERIAL_ECHOLNPGM(" Read error!"); + case 102: { // D102 Test SD Read + char testfile[] = "test.gco"; + card.openFileRead(testfile); + if (!card.isFileOpen()) { + SERIAL_ECHOLNPAIR("Failed to open test.gco to read."); + return; + } + __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; + uint16_t c = 1024 * 4; + while (c--) { + TERN_(USE_WATCHDOG, watchdog_refresh()); + card.read(buf, COUNT(buf)); + bool error = false; + for (uint16_t i = 0; i < COUNT(buf); i++) { + if (buf[i] != ('A' + (i % ('Z' - 'A')))) { + error = true; break; } } - SERIAL_ECHOLNPGM(" done"); - card.closefile(); - } break; - - #endif // SDSUPPORT - - #if ENABLED(POSTMORTEM_DEBUGGING) - - case 451: { // Trigger all kind of faults to test exception catcher - SERIAL_ECHOLNPGM("Disabling heaters"); - thermalManager.disable_all_heaters(); - delay(1000); // Allow time to print - volatile uint8_t type[5] = { parser.byteval('T', 1) }; - - // The code below is obviously wrong and it's full of quirks to fool the compiler from optimizing away the code - switch (type[0]) { - case 1: default: *(int*)0 = 451; break; // Write at bad address - case 2: { volatile int a = 0; volatile int b = 452 / a; *(int*)&a = b; } break; // Divide by zero (some CPUs accept this, like ARM) - case 3: { *(uint32_t*)&type[1] = 453; volatile int a = *(int*)&type[1]; type[0] = a / 255; } break; // Unaligned access (some CPUs accept this) - case 4: { volatile void (*func)() = (volatile void (*)()) 0xE0000000; func(); } break; // Invalid instruction + if (error) { + SERIAL_ECHOLNPGM(" Read error!"); + break; } - break; } + SERIAL_ECHOLNPGM(" done"); + card.closefile(); + } break; - #endif - } + #endif // SDSUPPORT + + #if ENABLED(POSTMORTEM_DEBUGGING) + + case 451: { // Trigger all kind of faults to test exception catcher + SERIAL_ECHOLNPGM("Disabling heaters"); + thermalManager.disable_all_heaters(); + delay(1000); // Allow time to print + volatile uint8_t type[5] = { parser.byteval('T', 1) }; + + // The code below is obviously wrong and it's full of quirks to fool the compiler from optimizing away the code + switch (type[0]) { + case 1: default: *(int*)0 = 451; break; // Write at bad address + case 2: { volatile int a = 0; volatile int b = 452 / a; *(int*)&a = b; } break; // Divide by zero (some CPUs accept this, like ARM) + case 3: { *(uint32_t*)&type[1] = 453; volatile int a = *(int*)&type[1]; type[0] = a / 255; } break; // Unaligned access (some CPUs accept this) + case 4: { volatile void (*func)() = (volatile void (*)()) 0xE0000000; func(); } break; // Invalid instruction + } + break; + } + + #endif + + #if ENABLED(BUFFER_MONITORING) + + /** + * D576: Return buffer stats or set the auto-report interval. + * Usage: D576 [S] + * + * With no parameters emits the following output: + * "D576 P B PU PD BU BD" + * Where: + * P : Planner buffers free + * B : Command buffers free + * PU: Planner buffer underruns (since the last report) + * PD: Longest duration (ms) the planner buffer was empty (since the last report) + * BU: Command buffer underruns (since the last report) + * BD: Longest duration (ms) command buffer was empty (since the last report) + */ + case 576: { + if (parser.seenval('S')) + queue.set_auto_report_interval((uint8_t)parser.value_byte()); + else + queue.report_buffer_statistics(); + break; + } + + #endif // BUFFER_MONITORING } +} -#endif +#endif // MARLIN_DEV_MODE diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 09755fbf21..fa83c82ddc 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -67,6 +67,23 @@ GCodeQueue::RingBuffer GCodeQueue::ring_buffer = { 0 }; static millis_t last_command_time = 0; #endif +/** + * Track buffer underruns + */ +#if ENABLED(BUFFER_MONITORING) + uint32_t GCodeQueue::command_buffer_underruns = 0, + GCodeQueue::planner_buffer_underruns = 0; + bool GCodeQueue::command_buffer_empty = false, + GCodeQueue::planner_buffer_empty = false; + millis_t GCodeQueue::max_command_buffer_empty_duration = 0, + GCodeQueue::max_planner_buffer_empty_duration = 0, + GCodeQueue::command_buffer_empty_at = 0, + GCodeQueue::planner_buffer_empty_at = 0; + + uint8_t GCodeQueue::auto_buffer_report_interval; + millis_t GCodeQueue::next_buffer_report_ms; +#endif + /** * Serial command injection */ @@ -82,7 +99,6 @@ PGM_P GCodeQueue::injected_commands_P; // = nullptr */ char GCodeQueue::injected_commands[64]; // = { 0 } - void GCodeQueue::RingBuffer::commit_command(bool skip_ok OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { @@ -621,7 +637,24 @@ void GCodeQueue::advance() { if (process_injected_command_P() || process_injected_command()) return; // Return if the G-code buffer is empty - if (ring_buffer.empty()) return; + if (ring_buffer.empty()) { + #if ENABLED(BUFFER_MONITORING) + if (!command_buffer_empty) { + command_buffer_empty = true; + command_buffer_underruns++; + command_buffer_empty_at = millis(); + } + #endif + return; + } + + #if ENABLED(BUFFER_MONITORING) + if (command_buffer_empty) { + command_buffer_empty = false; + const millis_t command_buffer_empty_duration = millis() - command_buffer_empty_at; + NOLESS(max_command_buffer_empty_duration, command_buffer_empty_duration); + } + #endif #if ENABLED(SDSUPPORT) @@ -664,3 +697,41 @@ void GCodeQueue::advance() { // The queue may be reset by a command handler or by code invoked by idle() within a handler ring_buffer.advance_pos(ring_buffer.index_r, -1); } + +#if ENABLED(BUFFER_MONITORING) + + void GCodeQueue::report_buffer_statistics() { + SERIAL_ECHOLNPAIR("D576" + " P:", planner.moves_free(), " ", -queue.planner_buffer_underruns, " (", queue.max_planner_buffer_empty_duration, ")" + " B:", BUFSIZE - ring_buffer.length, " ", -queue.command_buffer_underruns, " (", queue.max_command_buffer_empty_duration, ")" + ); + command_buffer_underruns = planner_buffer_underruns = 0; + max_command_buffer_empty_duration = max_planner_buffer_empty_duration = 0; + } + + void GCodeQueue::auto_report_buffer_statistics() { + // Bit of a hack to try to catch planner buffer underruns without having logic + // running inside Stepper::block_phase_isr + const millis_t ms = millis(); + if (planner.movesplanned() == 0) { + if (!planner_buffer_empty) { // the planner buffer wasn't empty, but now it is + planner_buffer_empty = true; + planner_buffer_underruns++; + planner_buffer_empty_at = ms; + } + } + else if (planner_buffer_empty) { // the planner buffer was empty, but now it's not + planner_buffer_empty = false; + const millis_t planner_buffer_empty_duration = ms - planner_buffer_empty_at; + NOLESS(max_planner_buffer_empty_duration, planner_buffer_empty_duration); // if it's longer than the currently tracked max duration, replace it + } + + if (queue.auto_buffer_report_interval && ELAPSED(ms, queue.next_buffer_report_ms)) { + queue.next_buffer_report_ms = ms + 1000UL * queue.auto_buffer_report_interval; + PORT_REDIRECT(SERIAL_BOTH); + report_buffer_statistics(); + PORT_RESTORE(); + } + } + +#endif // BUFFER_MONITORING diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 3474a402c3..6bcf4a97e4 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -197,6 +197,46 @@ public: */ static inline void set_current_line_number(long n) { serial_state[ring_buffer.command_port().index].last_N = n; } + #if ENABLED(BUFFER_MONITORING) + + private: + + /** + * Track buffer underruns + */ + static uint32_t command_buffer_underruns, planner_buffer_underruns; + static bool command_buffer_empty, planner_buffer_empty; + static millis_t max_command_buffer_empty_duration, max_planner_buffer_empty_duration, + command_buffer_empty_at, planner_buffer_empty_at; + + /** + * Report buffer statistics to the host to be able to detect buffer underruns + * + * Returns "D576 " followed by: + * P Planner space remaining + * B Command buffer space remaining + * PU Number of planner buffer underruns since last report + * PD Max time in ms the planner buffer was empty since last report + * BU Number of command buffer underruns since last report + * BD Max time in ms the command buffer was empty since last report + */ + static void report_buffer_statistics(); + + static uint8_t auto_buffer_report_interval; + static millis_t next_buffer_report_ms; + + public: + + static void auto_report_buffer_statistics(); + + static inline void set_auto_report_interval(uint8_t v) { + NOMORE(v, 60); + auto_buffer_report_interval = v; + next_buffer_report_ms = millis() + 1000UL * v; + } + + #endif // BUFFER_MONITORING + private: static void get_serial_commands(); diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index a3f885147e..8348b6347d 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -10,7 +10,7 @@ set -e # Build with configs included in the PR # use_example_configs "Creality/Ender-3 V2" -opt_enable MARLIN_DEV_MODE +opt_enable MARLIN_DEV_MODE BUFFER_MONITORING exec_test $1 $2 "Ender 3 v2" "$3" use_example_configs "Creality/Ender-3 V2" From 78be63b8a4ee91acab29888c8b1455917c170cce Mon Sep 17 00:00:00 2001 From: tome9111991 <57866234+tome9111991@users.noreply.github.com> Date: Fri, 23 Jul 2021 23:47:38 +0200 Subject: [PATCH 0444/2168] =?UTF-8?q?=F0=9F=93=9D=20SKR=20E3=20Turbo=20cus?= =?UTF-8?q?tom=20cable=20description=20(#22426)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 25 +++++++++++++------ 1 file changed, 18 insertions(+), 7 deletions(-) diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index e99c15e70e..f37028f15a 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -182,13 +182,13 @@ #endif /** - * _____ - * 5V | 1 2 | GND - * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) - * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) - * RESET | 7 8 | P0_19 (BTN_EN1) - * (BTN_ENC) P0_16 | 9 10| P2_08 (BEEPER) - * ----- + * ______ + * 5V | 1 2 | GND + * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) + * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) + * RESET | 7 8 | P0_19 (BTN_EN1) + * (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * ------ * EXP */ @@ -204,6 +204,17 @@ #if ENABLED(DWIN_CREALITY_LCD) #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." + /** + * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo + * ______ ______ RX 8 --> 5 P0_15 + * 5V | 1 2 | GND 5V | 1 2 | GND TX 7 --> 9 P0_16 + * (BTN_E1) A | 3 4 | B (BTN_E2) (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) BEEPER 5 --> 10 P2_08 + * BEEPER | 5 6 ENT (BTN_ENC) (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) + * (SKR_RX1) TX | 7 8 | RX (SKR_TX1) Reset | 7 8 | P0_19 (BTN_EN1) + * NC | 9 10 | NC (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * ------ ------ + */ + #define BEEPER_PIN EXP1_10_PIN #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_04_PIN From b925130db13409ba1ee671dea151c81990668d8b Mon Sep 17 00:00:00 2001 From: Marcio T Date: Fri, 23 Jul 2021 16:02:39 -0600 Subject: [PATCH 0445/2168] =?UTF-8?q?=F0=9F=93=BA=20Fix=20and=20optimize?= =?UTF-8?q?=20FTDI=20Eve=20Touch=20Interface=20(#22427)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/basic/commands.cpp | 26 ++++++++-- .../ftdi_eve_lib/basic/commands.h | 1 + .../ftdi_eve_lib/extended/text_box.cpp | 50 +++++++++---------- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 17 ++++--- .../ftdi_eve_lib/extended/unicode/unicode.h | 4 +- .../generic/about_screen.cpp | 10 ++-- .../confirm_user_request_alert_box.cpp | 9 +--- .../generic/confirm_user_request_alert_box.h | 1 - 8 files changed, 66 insertions(+), 52 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 47ce1c700d..48d60a37ac 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -902,6 +902,7 @@ bool CLCD::CommandFifo::has_fault() { } #if FTDI_API_LEVEL == 800 + void CLCD::CommandFifo::start() { if (command_write_ptr == 0xFFFFFFFFul) { command_write_ptr = mem_read_32(REG::CMD_WRITE) & 0x0FFF; @@ -979,12 +980,13 @@ template bool CLCD::CommandFifo::_write_unaligned(T data, uint16_t len template bool CLCD::CommandFifo::write(T data, uint16_t len) { const uint8_t padding = MULTIPLE_OF_4(len) - len; - - uint8_t pad_bytes[] = {0, 0, 0, 0}; + const uint8_t pad_bytes[] = { 0, 0, 0, 0 }; return _write_unaligned(data, len) && _write_unaligned(pad_bytes, padding); } -#else + +#else // FTDI_API_LEVEL != 800 ... + void CLCD::CommandFifo::start() { } @@ -1042,13 +1044,29 @@ template bool CLCD::CommandFifo::write(T data, uint16_t len) { mem_write_bulk(REG::CMDB_WRITE, data, len, padding); return true; } -#endif + +#endif // ... FTDI_API_LEVEL != 800 template bool CLCD::CommandFifo::write(const void*, uint16_t); template bool CLCD::CommandFifo::write(progmem_str, uint16_t); // CO_PROCESSOR COMMANDS +void CLCD::CommandFifo::str(const char * data, size_t maxlen) { + // Write the string without the terminating '\0' + const size_t len = strnlen(data, maxlen); + write(data, len); + + // If padding was added by the previous write, then + // the string is terminated. Otherwise write four + // more zeros. + const uint8_t padding = MULTIPLE_OF_4(len) - len; + if (padding == 0) { + const uint8_t pad_bytes[] = {0, 0, 0, 0}; + write(pad_bytes, 4); + } +} + void CLCD::CommandFifo::str(const char * data) { write(data, strlen(data)+1); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index eea24b06bd..5ce628fd36 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h @@ -248,6 +248,7 @@ class CLCD::CommandFifo { void keys (int16_t x, int16_t y, int16_t w, int16_t h, int16_t font, uint16_t options); // Sends the string portion of text, button, toggle and keys. + void str (const char * data, size_t maxlen); void str (const char * data); void str (progmem_str data); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index f3f518359c..0701e7d682 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -29,31 +29,31 @@ namespace FTDI { * be broken so that the display width is less than w. The line will also * be broken after a '\n'. Returns the display width of the line. */ - static uint16_t find_line_break(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const uint16_t w, const char *str, const char *&end, bool use_utf8) { - const char *p = str; - end = str; + static uint16_t find_line_break(const FontMetrics &utf8_fm, const CLCD::FontMetrics &clcd_fm, const uint16_t w, const char *start, const char *&end, bool use_utf8) { + const char *p = start; + end = start; uint16_t lw = 0, result = 0; for (;;) { const char *next = p; - utf8_char_t c = get_utf8_char_and_inc(next); + const utf8_char_t c = get_utf8_char_and_inc(next); // Decide whether to break the string at this location if (c == '\n' || c == '\0' || c == ' ') { end = p; result = lw; } if (c == '\n' || c == '\0') break; - // Now add the length of the current character to the tally. - lw += use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c]; + // Measure the next character + const uint16_t cw = use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c]; // Stop processing once string exceeds the display width - if (lw >= w) { - if (end == str) { - end = p; - result = lw; - } - break; - } + if (lw + cw > w) break; + // Now add the length of the current character to the tally. + lw += cw; p = next; } + if (end == start) { + end = p; + result = lw; + } return result; } @@ -66,12 +66,13 @@ namespace FTDI { const uint16_t wrap_width = width; width = height = 0; for (;;) { - uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); + const uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); + if (line_end == line_start) break; width = max(width, line_width); height += utf8_fm.get_height(); line_start = line_end; - if (line_start[0] == '\n' || line_start[0] == ' ') line_start++; - if (line_start[0] == '\0') break; + if (*line_start == '\n' || *line_start == ' ') line_start++; + if (*line_start == '\0') break; } } @@ -108,28 +109,25 @@ namespace FTDI { const char *line_start = str, *line_end; for (;;) { find_line_break(utf8_fm, clcd_fm, w, line_start, line_end, use_utf8); + if (line_end == line_start) break; const size_t line_len = line_end - line_start; if (line_len) { - char line[line_len + 1]; - strncpy(line, line_start, line_len); - line[line_len] = 0; - #if ENABLED(TOUCH_UI_USE_UTF8) - if (use_utf8) { - draw_utf8_text(cmd, x + dx, y + dy, line, utf8_fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY)); - } else + if (use_utf8) + draw_utf8_text(cmd, x + dx, y + dy, line_start, utf8_fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY), line_len); + else #endif { cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~(OPT_CENTERY | OPT_BOTTOMY)); - cmd.CLCD::CommandFifo::str(line); + cmd.CLCD::CommandFifo::str(line_start, line_len); } } y += utf8_fm.get_height(); line_start = line_end; - if (line_start[0] == '\n' || line_start[0] == ' ') line_start++; - if (line_start[0] == '\0') break; + if (*line_start == '\n' || *line_start == ' ') line_start++; + if (*line_start == '\0') break; } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 55dd496e1c..2bb44e81d0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -95,9 +95,9 @@ * fs - A scaling object used to specify the font size. */ - static uint16_t render_utf8_text(CommandProcessor* cmd, int x, int y, const char *str, font_size_t fs) { + static uint16_t render_utf8_text(CommandProcessor* cmd, int x, int y, const char *str, font_size_t fs, size_t maxlen=SIZE_MAX) { const int start_x = x; - while (*str) { + while (*str && maxlen--) { const utf8_char_t c = get_utf8_char_and_inc(str); #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET CyrillicCharSet::render_glyph(cmd, x, y, fs, c) || @@ -185,8 +185,8 @@ * Returns: A width in pixels */ - uint16_t FTDI::get_utf8_text_width(const char *str, font_size_t fs) { - return render_utf8_text(nullptr, 0, 0, str, fs); + uint16_t FTDI::get_utf8_text_width(const char *str, font_size_t fs, size_t maxlen) { + return render_utf8_text(nullptr, 0, 0, str, fs, maxlen); } uint16_t FTDI::get_utf8_text_width(progmem_str pstr, font_size_t fs) { @@ -210,9 +210,10 @@ * * options - Text alignment options (i.e. OPT_CENTERX, OPT_CENTERY, OPT_CENTER or OPT_RIGHTX) * + * maxlen - Maximum characters to draw */ - void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, const char *str, font_size_t fs, uint16_t options) { + void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, const char *str, font_size_t fs, uint16_t options, size_t maxlen) { cmd.cmd(SAVE_CONTEXT()); cmd.cmd(BITMAP_TRANSFORM_A(fs.get_coefficient())); cmd.cmd(BITMAP_TRANSFORM_E(fs.get_coefficient())); @@ -220,14 +221,14 @@ // Apply alignment options if (options & OPT_CENTERX) - x -= get_utf8_text_width(str, fs) / 2; + x -= get_utf8_text_width(str, fs, maxlen) / 2; else if (options & OPT_RIGHTX) - x -= get_utf8_text_width(str, fs); + x -= get_utf8_text_width(str, fs, maxlen); if (options & OPT_CENTERY) y -= fs.get_height()/2; // Render the text - render_utf8_text(&cmd, x, y, str, fs); + render_utf8_text(&cmd, x, y, str, fs, maxlen); cmd.cmd(RESTORE_CONTEXT()); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h index 5bb87d9684..3ca6dfd563 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h @@ -67,10 +67,10 @@ namespace FTDI { uint16_t get_utf8_char_width(utf8_char_t, font_size_t); uint16_t get_utf8_text_width(progmem_str, font_size_t); - uint16_t get_utf8_text_width(const char *, font_size_t); + uint16_t get_utf8_text_width(const char *, font_size_t, size_t maxlen=SIZE_MAX); void draw_utf8_text(CommandProcessor&, int x, int y, progmem_str, font_size_t, uint16_t options = 0); - void draw_utf8_text(CommandProcessor&, int x, int y, const char *, font_size_t, uint16_t options = 0); + void draw_utf8_text(CommandProcessor&, int x, int y, const char *, font_size_t, uint16_t options = 0, size_t maxlen=SIZE_MAX); // Similar to CLCD::FontMetrics, but can be used with UTF8 encoded strings. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 3e07735edf..d2aec0baf7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -76,7 +76,9 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); - cmd.tag(3); + #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + cmd.tag(3); + #endif draw_text_box(cmd, FW_VERS_POS, #ifdef TOUCH_UI_VERSION F(TOUCH_UI_VERSION) @@ -89,7 +91,7 @@ void AboutScreen::onRedraw(draw_mode_t) { draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium); - #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) + #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) cmd.colors(normal_btn) .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); #endif @@ -100,10 +102,10 @@ void AboutScreen::onRedraw(draw_mode_t) { bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) + #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) && defined(FTDI_DEVELOPER_MENU) + #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp index c10d372743..8c06fa9a9e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.cpp @@ -53,17 +53,12 @@ bool ConfirmUserRequestAlertBox::onTouchEnd(uint8_t tag) { } } -void ConfirmUserRequestAlertBox::onIdle() { - if (!ExtUI::awaitingUserConfirm()) { - hide(); - } -} - void ConfirmUserRequestAlertBox::show(const char *msg) { drawMessage(msg); storeBackground(); screen_data.AlertDialogBox.isError = false; - GOTO_SCREEN(ConfirmUserRequestAlertBox); + if (!AT_SCREEN(ConfirmUserRequestAlertBox)) + GOTO_SCREEN(ConfirmUserRequestAlertBox); } void ConfirmUserRequestAlertBox::hide() { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h index d9a6c4a4fe..f83b1a24f5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_user_request_alert_box.h @@ -31,5 +31,4 @@ class ConfirmUserRequestAlertBox : public AlertDialogBox { static bool onTouchEnd(uint8_t); static void hide(); static void show(const char*); - static void onIdle(); }; From c56109c7a484fda3daada3e49f77aae8cdfdd80f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 24 Jul 2021 05:00:51 +0000 Subject: [PATCH 0446/2168] [cron] Bump distribution date (2021-07-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index aad3b0c41f..384c209816 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-23" +//#define STRING_DISTRIBUTION_DATE "2021-07-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 368f7b889f..3c22da21d1 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 "2021-07-23" + #define STRING_DISTRIBUTION_DATE "2021-07-24" #endif /** From 27f5e64acf0a8b087c899db677618785028bb06f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jul 2021 15:55:45 -0500 Subject: [PATCH 0447/2168] =?UTF-8?q?=F0=9F=8E=A8=20NULL=20=3D>=20nullptr?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 4 ++-- Marlin/src/HAL/STM32F1/SPI.h | 4 ++-- .../src/lcd/extui/mks_ui/draw_cloud_bind.cpp | 18 +++++++++--------- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 4 ++-- .../src/lcd/extui/mks_ui/draw_move_motor.cpp | 6 +++--- Marlin/src/lcd/tft/tft_queue.h | 2 +- Marlin/src/lcd/tft/touch.h | 2 +- 7 files changed, 20 insertions(+), 20 deletions(-) diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 05f859a4af..55e807f94e 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -290,13 +290,13 @@ static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, NULL, dst)) return true; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) return true; return false; } bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, NULL)) return true; + while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; return false; } diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 828644f1dd..2467432e07 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -138,8 +138,8 @@ private: spi_dev *spi_d; dma_channel spiRxDmaChannel, spiTxDmaChannel; dma_dev* spiDmaDev; - void (*receiveCallback)() = NULL; - void (*transmitCallback)() = NULL; + void (*receiveCallback)() = nullptr; + void (*transmitCallback)() = nullptr; friend class SPIClass; }; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp index 55cfe4491d..56b0e8f5ca 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -33,8 +33,8 @@ extern lv_group_t * g; static lv_obj_t * scr; -static lv_obj_t *button_bind_or_not = NULL, *label_bind_or_not = NULL; -static lv_obj_t *buttonReleaseBind = NULL, *label_ReleaseBind = NULL; +static lv_obj_t *button_bind_or_not = nullptr, *label_bind_or_not = nullptr; +static lv_obj_t *buttonReleaseBind = nullptr, *label_ReleaseBind = nullptr; static lv_obj_t * text_id; static uint8_t unbinding_flag = 0; @@ -61,29 +61,29 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } void lv_draw_cloud_bind() { - lv_obj_t *buttonBack = NULL, *label_Back = NULL; + lv_obj_t *buttonBack = nullptr, *label_Back = nullptr; scr = lv_screen_create(BIND_UI); - button_bind_or_not = lv_btn_create(scr, NULL); + button_bind_or_not = lv_btn_create(scr, nullptr); lv_obj_set_pos(button_bind_or_not, TFT_WIDTH - 130, TFT_HEIGHT - 80 * 3); lv_obj_set_size(button_bind_or_not, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); - lv_obj_set_event_cb_mks(button_bind_or_not, event_handler, ID_CLOUD_BIND_OR_NOT, NULL, 0); + lv_obj_set_event_cb_mks(button_bind_or_not, event_handler, ID_CLOUD_BIND_OR_NOT, nullptr, 0); lv_btn_set_style(button_bind_or_not, LV_BTN_STYLE_REL, &style_para_value); lv_btn_set_style(button_bind_or_not, LV_BTN_STYLE_PR, &style_para_value); label_bind_or_not = lv_label_create_empty(button_bind_or_not); - buttonReleaseBind = lv_btn_create(scr, NULL); + buttonReleaseBind = lv_btn_create(scr, nullptr); lv_obj_set_pos(buttonReleaseBind, TFT_WIDTH - 130, TFT_HEIGHT - 80 * 2); lv_obj_set_size(buttonReleaseBind, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); - lv_obj_set_event_cb_mks(buttonReleaseBind, event_handler, ID_CLOUD_RELEASE_BIND, NULL, 0); + lv_obj_set_event_cb_mks(buttonReleaseBind, event_handler, ID_CLOUD_RELEASE_BIND, nullptr, 0); label_ReleaseBind = lv_label_create_empty(buttonReleaseBind); lv_label_set_text(label_ReleaseBind, cloud_menu.unbind); lv_obj_align(label_ReleaseBind, buttonReleaseBind, LV_ALIGN_CENTER, 0, 0); - buttonBack = lv_btn_create(scr, NULL); + buttonBack = lv_btn_create(scr, nullptr); lv_obj_set_pos(buttonBack, TFT_WIDTH - 130, TFT_HEIGHT - 80); lv_obj_set_size(buttonBack, PARA_UI_VALUE_BTN_X_SIZE + 15, PARA_UI_VALUE_BTN_Y_SIZE + 15); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_CLOUD_BIND_RETURN, NULL, 0); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_CLOUD_BIND_RETURN, nullptr, 0); lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); label_Back = lv_label_create_empty(buttonBack); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 3f2cd32c73..44cee6cb60 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -431,7 +431,7 @@ void lv_draw_dialog(uint8_t type) { } else if (DIALOG_IS(TYPE_UPDATE_ESP_FIRMWARE)) { lv_label_set_text(labelDialog, DIALOG_UPDATE_WIFI_FIRMWARE_EN); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); } #endif // MKS_WIFI_MODULE else if (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT)) { @@ -469,7 +469,7 @@ void lv_draw_dialog(uint8_t type) { #if ENABLED(MKS_WIFI_MODULE) else if (DIALOG_IS(TYPE_UNBIND)) { lv_label_set_text(labelDialog, common_menu.unbind_printer_tips); - lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -70); + lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -70); } #endif #if HAS_ROTARY_ENCODER diff --git a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp index 4b413c5c62..19abb855f5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp @@ -119,10 +119,10 @@ void lv_draw_move_motor() { lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_M_RETURN); // We need to patch the title to leave some space on the right for displaying the status - lv_obj_t * title = lv_obj_get_child_back(scr, NULL); - if (title != NULL) lv_obj_set_width(title, TFT_WIDTH - 101); + lv_obj_t * title = lv_obj_get_child_back(scr, nullptr); + if (title != nullptr) lv_obj_set_width(title, TFT_WIDTH - 101); labelP = lv_label_create(scr, TFT_WIDTH - 100, TITLE_YPOS, "Z:0.0mm"); - if (labelP != NULL) + if (labelP != nullptr) updatePosTask = lv_task_create(refresh_pos, 300, LV_TASK_PRIO_LOWEST, 0); disp_move_dist(); diff --git a/Marlin/src/lcd/tft/tft_queue.h b/Marlin/src/lcd/tft/tft_queue.h index 7eaa0c01c1..51387254c5 100644 --- a/Marlin/src/lcd/tft/tft_queue.h +++ b/Marlin/src/lcd/tft/tft_queue.h @@ -134,7 +134,7 @@ class TFT_Queue { public: static void reset(); static void async(); - static void sync() { while (current_task != NULL) async(); } + static void sync() { while (current_task != nullptr) async(); } static void fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); static void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height); diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 8d6001b8d8..54dfb420d8 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -109,7 +109,7 @@ class Touch { public: static void init(); - static void reset() { controls_count = 0; touch_time = 0; current_control = NULL; } + static void reset() { controls_count = 0; touch_time = 0; current_control = nullptr; } static void clear() { controls_count = 0; } static void idle(); static bool is_clicked() { From a66d85c7e50197f744a9bfb97dba762e25c1f54c Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Sat, 24 Jul 2021 17:08:47 -0400 Subject: [PATCH 0448/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20delta=20calibrat?= =?UTF-8?q?e=20manual=20move=20scale=20(#22430)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index e6d23b1fae..810f376f82 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -31,6 +31,7 @@ #include "menu_item.h" #include "../../module/delta.h" #include "../../module/motion.h" +#include "../../module/planner.h" #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" @@ -46,7 +47,7 @@ void _man_probe_pt(const xy_pos_t &xy) { do_blocking_move_to_xy_z(xy, Z_CLEARANCE_BETWEEN_PROBES); ui.wait_for_move = false; ui.synchronize(); - ui.manual_move.menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT)); + ui.manual_move.menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / planner.settings.axis_steps_per_mm[0]); // Use first axis as for delta XYZ should always match ui.goto_screen(lcd_move_z); } } From 4b94fb7558918d9ce38ef97d808887108b356066 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 25 Jul 2021 01:00:36 +0000 Subject: [PATCH 0449/2168] [cron] Bump distribution date (2021-07-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 384c209816..0f8d2956bc 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-24" +//#define STRING_DISTRIBUTION_DATE "2021-07-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3c22da21d1..9ecb34c27f 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 "2021-07-24" + #define STRING_DISTRIBUTION_DATE "2021-07-25" #endif /** From e1907a99e2404ae9a0d1c1115978bc9640aa96f1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jul 2021 21:41:09 -0500 Subject: [PATCH 0450/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20some=20formattin?= =?UTF-8?q?g,=20F()=20versus=20PSTR()?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LINUX/hardware/Gpio.h | 2 +- Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp | 2 +- Marlin/src/HAL/LINUX/hardware/Timer.h | 2 +- Marlin/src/feature/leds/pca9533.cpp | 4 ++-- Marlin/src/feature/power.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 2 +- .../extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp | 2 +- .../ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp | 4 ++-- .../extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp | 2 +- .../extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp | 2 +- .../extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp | 6 +++--- .../src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp | 2 +- .../extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp | 8 ++++---- Marlin/src/libs/hex_print.cpp | 2 +- 18 files changed, 25 insertions(+), 25 deletions(-) diff --git a/Marlin/src/HAL/LINUX/hardware/Gpio.h b/Marlin/src/HAL/LINUX/hardware/Gpio.h index 2d9b1f29eb..f946be6484 100644 --- a/Marlin/src/HAL/LINUX/hardware/Gpio.h +++ b/Marlin/src/HAL/LINUX/hardware/Gpio.h @@ -40,7 +40,7 @@ struct GpioEvent { pin_type pin_id; GpioEvent::Type event; - GpioEvent(uint64_t timestamp, pin_type pin_id, GpioEvent::Type event){ + GpioEvent(uint64_t timestamp, pin_type pin_id, GpioEvent::Type event) { this->timestamp = timestamp; this->pin_id = pin_id; this->event = event; diff --git a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp index c5b3ccc986..e122ef3666 100644 --- a/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp +++ b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp @@ -51,7 +51,7 @@ void LinearAxis::update() { } void LinearAxis::interrupt(GpioEvent ev) { - if (ev.pin_id == step_pin && !Gpio::pin_map[enable_pin].value){ + if (ev.pin_id == step_pin && !Gpio::pin_map[enable_pin].value) { if (ev.event == GpioEvent::RISE) { last_update = ev.timestamp; position += -1 + 2 * Gpio::pin_map[dir_pin].value; diff --git a/Marlin/src/HAL/LINUX/hardware/Timer.h b/Marlin/src/HAL/LINUX/hardware/Timer.h index 757efdcdbd..1b3b800dca 100644 --- a/Marlin/src/HAL/LINUX/hardware/Timer.h +++ b/Marlin/src/HAL/LINUX/hardware/Timer.h @@ -52,7 +52,7 @@ public: return (*(intptr_t*)timerid); } - static void handler(int sig, siginfo_t *si, void *uc){ + static void handler(int sig, siginfo_t *si, void *uc) { Timer* _this = (Timer*)si->si_value.sival_ptr; _this->avg_error += (Clock::nanos() - _this->start_time) - _this->period; //high_resolution_clock is also limited in precision, but best we have _this->avg_error /= 2; //very crude precision analysis (actually within +-500ns usually) diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp index 0fd4d66757..914db21ba3 100644 --- a/Marlin/src/feature/leds/pca9533.cpp +++ b/Marlin/src/feature/leds/pca9533.cpp @@ -36,7 +36,7 @@ void PCA9533_init() { PCA9533_reset(); } -static void PCA9533_writeAllRegisters(uint8_t psc0, uint8_t pwm0, uint8_t psc1, uint8_t pwm1, uint8_t ls0){ +static void PCA9533_writeAllRegisters(uint8_t psc0, uint8_t pwm0, uint8_t psc1, uint8_t pwm1, uint8_t ls0) { uint8_t data[6] = { PCA9533_REG_PSC0 | PCA9533_REGM_AI, psc0, pwm0, psc1, pwm1, ls0 }; Wire.beginTransmission(PCA9533_Addr >> 1); Wire.write(data, 6); @@ -44,7 +44,7 @@ static void PCA9533_writeAllRegisters(uint8_t psc0, uint8_t pwm0, uint8_t psc1, delayMicroseconds(1); } -static void PCA9533_writeRegister(uint8_t reg, uint8_t val){ +static void PCA9533_writeRegister(uint8_t reg, uint8_t val) { uint8_t data[2] = { reg, val }; Wire.beginTransmission(PCA9533_Addr >> 1); Wire.write(data, 2); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 30bf0d764d..b86249fbc0 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -57,7 +57,7 @@ bool Power::psu_on; * Initialize pins & state for the power manager. * */ -void Power::init(){ +void Power::init() { psu_on = ENABLED(PSU_DEFAULT_OFF); // Set opposite state to get full power_off/on TERN(PSU_DEFAULT_OFF, power_off(), power_on()); } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index ca9cbb8cc9..6baef030bf 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -268,7 +268,7 @@ void GcodeSuite::G28() { #endif #if HAS_HOMING_CURRENT - auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){ + auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp index dedda6d215..21788c7f86 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp @@ -36,7 +36,7 @@ bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { switch (tag) { case 1: #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) - SpinnerDialogBox::enqueueAndWait_P(F( + SpinnerDialogBox::enqueueAndWait_P(PSTR( "G28 E\n" AXIS_LEVELING_COMMANDS "\n" PARK_AND_RELEASE_COMMANDS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp index bff1808d0d..f3d7cdcbe4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp @@ -36,7 +36,7 @@ bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { switch (tag) { case 1: #ifdef PARK_AND_RELEASE_COMMANDS - SpinnerDialogBox::enqueueAndWait_P(F( + SpinnerDialogBox::enqueueAndWait_P(PSTR( "G28\n" PARK_AND_RELEASE_COMMANDS )); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index 8109ecef76..c7e18e2718 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -69,10 +69,10 @@ bool MainMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; + case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? PSTR("G0 E0 F120") : PSTR("G112")); break; case 4: StatusScreen::unlockMotors(); break; #ifdef AXIS_LEVELING_COMMANDS - case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + case 5: SpinnerDialogBox::enqueueAndWait_P(PSTR(AXIS_LEVELING_COMMANDS)); break; #endif case 6: GOTO_SCREEN(TemperatureScreen); break; case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp index 6fa4d761f6..a349e04173 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -316,7 +316,7 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { case 9: GOTO_SCREEN(FilesScreen); break; case 10: GOTO_SCREEN(MainMenu); break; case 13: GOTO_SCREEN(BioConfirmHomeE); break; - case 14: SpinnerDialogBox::enqueueAndWait_P(F("G28Z")); break; + case 14: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Z")); break; case 15: GOTO_SCREEN(TemperatureScreen); break; case 16: fine_motion = !fine_motion; break; default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp index 2f94555784..4c4875a603 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -67,7 +67,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { case 3: GOTO_SCREEN(TemperatureScreen); break; case 4: GOTO_SCREEN(NudgeNozzleScreen); break; case 5: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 6: SpinnerDialogBox::enqueueAndWait_P(F("G0 E0 F120")); break; + case 6: SpinnerDialogBox::enqueueAndWait_P(PSTR("G0 E0 F120")); break; case 7: StatusScreen::unlockMotors(); break; default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index d3950a7c6c..6d3037da4b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -82,7 +82,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { case 3: BedMeshViewScreen::show(); break; case 4: BedMeshEditScreen::show(); break; case 5: injectCommands_P(PSTR("M280 P0 S60")); break; - case 6: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + case 6: SpinnerDialogBox::enqueueAndWait_P(PSTR("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; default: return false; } return true; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index 467d3b9119..96572e0538 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -233,7 +233,7 @@ bool StatusScreen::onTouchStart(uint8_t) { bool StatusScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: SpinnerDialogBox::enqueueAndWait_P(F("G28 O\nG27")); break; + case 1: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28 O\nG27")); break; case 2: GOTO_SCREEN(LoadChocolateScreen); break; case 3: GOTO_SCREEN(PreheatMenu); break; case 4: GOTO_SCREEN(MainMenu); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 30b9d1c78a..27611eefab 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -191,7 +191,7 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { void BedMeshEditScreen::show() { // On entry, always home (to account for possible Z offset changes) and save current mesh - SpinnerDialogBox::enqueueAndWait_P(F("G28\nG29 S1")); + SpinnerDialogBox::enqueueAndWait_P(PSTR("G28\nG29 S1")); // After the spinner, go to this screen. current_screen.forget(); PUSH_SCREEN(BedMeshEditScreen); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index e693bfb05c..29b9f47ddd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -104,7 +104,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) - case 2: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; + case 2: SpinnerDialogBox::enqueueAndWait_P(PSTR("G34")); break; #endif #if HAS_BED_PROBE case 3: @@ -114,7 +114,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #if ENABLED(AUTO_BED_LEVELING_UBL) BedMeshViewScreen::doProbe(); #else - SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); + SpinnerDialogBox::enqueueAndWait_P(PSTR(BED_LEVELING_COMMANDS)); #endif break; #endif @@ -127,7 +127,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #endif #if ENABLED(BLTOUCH) case 7: injectCommands_P(PSTR("M280 P0 S60")); break; - case 8: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + case 8: SpinnerDialogBox::enqueueAndWait_P(PSTR("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; #endif default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index 3f614ec344..f02bfac99f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -104,7 +104,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; + case 2: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28")); break; #if ENABLED(NOZZLE_CLEAN_FEATURE) case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index 3bfe1784fc..6fbfd258e6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -98,10 +98,10 @@ bool BaseMoveAxisScreen::onTouchHeld(uint8_t tag) { case 14: UI_DECREMENT_AXIS(E3); mydata.e_rel[3] -= increment; break; case 15: UI_INCREMENT_AXIS(E3); mydata.e_rel[3] += increment; break; #endif - case 20: SpinnerDialogBox::enqueueAndWait_P(F("G28X")); break; - case 21: SpinnerDialogBox::enqueueAndWait_P(F("G28Y")); break; - case 22: SpinnerDialogBox::enqueueAndWait_P(F("G28Z")); break; - case 23: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; + case 20: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28X")); break; + case 21: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Y")); break; + case 22: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Z")); break; + case 23: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28")); break; case 24: raiseZtoTop(); break; default: return false; diff --git a/Marlin/src/libs/hex_print.cpp b/Marlin/src/libs/hex_print.cpp index 0f746d6284..1958084abb 100644 --- a/Marlin/src/libs/hex_print.cpp +++ b/Marlin/src/libs/hex_print.cpp @@ -80,7 +80,7 @@ void print_hex_address(const void * const w) { SERIAL_ECHO(hex_address(w)); } void print_hex_long(const uint32_t w, const char delimiter) { SERIAL_ECHOPGM("0x"); - for (int B = 24; B >= 8; B -= 8){ + for (int B = 24; B >= 8; B -= 8) { print_hex_byte(w >> B); SERIAL_CHAR(delimiter); } From a76d8c70dd5924ec52e82c05a8fd5d219e1af7e1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 25 Jul 2021 02:07:34 -0500 Subject: [PATCH 0451/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20some=20board=20n?= =?UTF-8?q?ames?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_CREALITY_V452.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V453.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index ad4ddff0ce..64e07a0bc8 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -29,7 +29,7 @@ #error "Creality v4.5.2 only supports one hotend / E-stepper. Comment out this line to continue." #endif -#define BOARD_NAME "Creality v4.5.2" +#define BOARD_INFO_NAME "Creality v4.5.2" #define HEATER_0_PIN PA1 // HEATER1 #define HEATER_BED_PIN PA2 // HOT BED diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index cdb87adece..ca437312c8 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -29,7 +29,7 @@ #error "Creality v4.5.3 only supports one hotend / E-stepper. Comment out this line to continue." #endif -#define BOARD_NAME "Creality v4.5.3" +#define BOARD_INFO_NAME "Creality v4.5.3" #define HEATER_0_PIN PB14 // HEATER1 #define HEATER_BED_PIN PB13 // HOT BED From 3b57c3316a7024223ed4d00173e38206cabe4f8b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 25 Jul 2021 02:19:30 -0500 Subject: [PATCH 0452/2168] Misc. Cleanup --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/feature/pause.cpp | 4 ++-- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_bed_corners.cpp | 6 ++---- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 82ef44f606..96c4d82948 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1593,7 +1593,7 @@ void setup() { HMI_Init(); DWIN_JPG_CacheTo1(Language_English); HMI_StartFrame(true); - DWIN_StatusChanged(GET_TEXT(WELCOME_MSG)); + DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG)); #endif #if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 2bd3033808..94c564a9aa 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -535,8 +535,8 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR)); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished."))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); wait_for_user = true; nozzle_timed_out = false; diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 6920f00d36..acd45e4820 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -727,6 +727,7 @@ namespace Language_en { #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Reheat Done"); PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 0ab82a9b16..4811e2c60c 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -201,7 +201,7 @@ static void _lcd_level_bed_corners_get_next_position() { void _lcd_draw_raise() { if (!ui.should_draw()) return; MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) + GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) , []{ corner_probing_done = true; wait_for_probe = false; } , []{ wait_for_probe = false; } , GET_TEXT(MSG_LEVEL_CORNERS_RAISE) @@ -212,9 +212,7 @@ static void _lcd_level_bed_corners_get_next_position() { void _lcd_draw_level_prompt() { if (!ui.should_draw()) return; MenuItem_confirm::confirm_screen( - []{ queue.inject_P(TERN(HAS_LEVELING, PSTR("G29N"), G28_STR)); - ui.return_to_status(); - } + []{ queue.inject_P(TERN(HAS_LEVELING, PSTR("G29N"), G28_STR)); ui.return_to_status(); } , []{ ui.goto_previous_screen_no_defer(); } , GET_TEXT(MSG_LEVEL_CORNERS_IN_RANGE) , (const char*)nullptr, PSTR("?") From b1bc2e80036131cde58b4fbc02b76ac08b5a7924 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 25 Jul 2021 02:12:48 -0500 Subject: [PATCH 0453/2168] =?UTF-8?q?=F0=9F=8C=90=20Level=20Corners=20=3D>?= =?UTF-8?q?=20Bed=20Tramming?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_cz.h | 2 +- Marlin/src/lcd/language/language_de.h | 3 +-- Marlin/src/lcd/language/language_en.h | 11 +++++------ Marlin/src/lcd/language/language_es.h | 3 +-- Marlin/src/lcd/language/language_eu.h | 2 +- Marlin/src/lcd/language/language_fr.h | 7 +++---- Marlin/src/lcd/language/language_gl.h | 2 +- Marlin/src/lcd/language/language_hu.h | 11 +++++------ Marlin/src/lcd/language/language_it.h | 11 +++++------ Marlin/src/lcd/language/language_pl.h | 11 +++++------ Marlin/src/lcd/language/language_pt_br.h | 2 +- Marlin/src/lcd/language/language_ro.h | 2 +- Marlin/src/lcd/language/language_ru.h | 14 +++++++------- Marlin/src/lcd/language/language_sk.h | 11 +++++------ Marlin/src/lcd/language/language_sv.h | 11 +++++------ Marlin/src/lcd/language/language_tr.h | 2 +- Marlin/src/lcd/language/language_uk.h | 14 +++++++------- Marlin/src/lcd/language/language_vi.h | 2 +- Marlin/src/lcd/language/language_zh_CN.h | 2 +- Marlin/src/lcd/language/language_zh_TW.h | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 8 ++++---- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/lcd/menu/menu_motion.cpp | 2 +- Marlin/src/lcd/menu/menu_tramming.cpp | 2 +- 24 files changed, 65 insertions(+), 74 deletions(-) diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index ab2aaa943f..fa6a8e21a3 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -109,7 +109,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunout osy"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnat podložku"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnat podložku"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Vyrovnat rohy"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Vyrovnat rohy"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Další roh"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sítě"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upravit síť bodů"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 7e40d42665..f06370078a 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -62,7 +62,6 @@ namespace Language_de { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Bett ausrichten"); // Bettausrichtung PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); @@ -103,7 +102,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Achsen bewegen"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bett-Nivellierung"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Bett nivellieren"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Ecken nivellieren"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bett ausrichten"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nächste Ecke"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Netz Editor"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index acd45e4820..cd204eef59 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -93,7 +93,6 @@ namespace Language_en { PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Select Origin"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Last value "); @@ -139,11 +138,11 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Move Axis"); 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_LEVEL_CORNERS_RAISE = _UxGT("Raise Bed Until Probe Triggered"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Good Points: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Last Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bed Tramming"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); 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"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index f342732161..8fdf0bd47e 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -62,7 +62,6 @@ namespace Language_es { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origen Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origen Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto alineado Z"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Recorrido asistido"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteración: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("¡Precisión disminuyendo!"); PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Precisión conseguida"); @@ -106,7 +105,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover ejes"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Esquinas"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Recorrido asistido"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 2be6f399d8..530742d6d3 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -82,7 +82,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ardatzak mugitu"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ohe berdinketa"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ohea berdindu"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Ertzak berdindu"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Ertzak berdindu"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Hurrengo ertza"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Sarea editatu"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 78a649f626..6032937e0f 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -78,7 +78,6 @@ namespace Language_fr { PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Régler origine"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assistant Molettes"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Molette du lit"); // Not a selection of the origin PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ecart origine "); @@ -111,9 +110,9 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Niveau des coins"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Assistant Molettes"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Coin suivant"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Modif. maille"); // 13 car. max PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifier grille"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 3eec75e138..8defd2b01f 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -103,7 +103,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index d4ff151f57..6fb41f90ff 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -87,7 +87,6 @@ namespace Language_hu { PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Elektromos segéd"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Eredeti választása"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Utolsó érték "); @@ -133,11 +132,11 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek mozgatása"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy szintezés"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ágy szintezése"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Sarok szint"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Ágy emelése a szonda váltásig"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Jó pontok: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Utolsó Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Elektromos segéd"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Ágy emelése a szonda váltásig"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Jó pontok: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Utolsó Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Következö sarok"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló szerkesztö"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló szerkesztése"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 85b9d3f399..32bc7ff7c7 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -91,7 +91,6 @@ namespace Language_it { PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Imposta Origine"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Tramming assistito"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Selez. origine"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ultimo valore "); @@ -137,11 +136,11 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muovi Asse"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Livella piano"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Livella piano"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Calibra piano"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Regola la vite finche' la sonda non rileva il piano."); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Punti buoni: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Ultimo Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Tramming piano"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finche' la sonda non rileva il piano."); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Punti buoni: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Ultimo Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Prossimo punto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifica Mesh"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index fee627b2fe..e467178f6a 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -85,7 +85,6 @@ namespace Language_pl { //PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); - //PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); //PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); @@ -131,11 +130,11 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ruch osi"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Narożniki poziomowania"); - //PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Raise Bed Until Probe Triggered"); - //PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); - //PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Good Points: "); - //PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Last Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Narożniki poziomowania"); + //PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + //PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + //PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + //PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 88135f5e28..12904aa7ea 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -94,7 +94,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixo"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelação Mesa"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Mesa"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Próximo Canto"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor de Malha"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Malha"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 9313adf3f6..3d21e1a58d 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -102,7 +102,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muta Axa"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelarea Patului"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveleaza Patul"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Niveleaza Colturile"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Niveleaza Colturile"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Urmatorul Colt"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editeaza Mesh"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index bf2bb02ba3..6ccfe5f47a 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -159,17 +159,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Движение по осям"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Выравнивание стола"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Выровнять стол"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Выровнять углы"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Выровнять углы"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Следующий угол"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до срабатыв. зонда"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до срабатыв. зонда"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); #else - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до сраб. зонда"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав."); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до сраб. зонда"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав."); #endif - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хорошие точки: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Последняя Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хорошие точки: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Последняя Z: "); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение по Z"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 96f1bc7ee5..717fa49b33 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -87,7 +87,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Asist. vyrovnanie"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Vyberte začiatok"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Posl. hodnota "); @@ -133,11 +132,11 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunúť osy"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Vyrovnať rohy"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Dobré body: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Posl. Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Asist. vyrovnanie"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Ďalší roh"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index f7b0f06769..baa0f64506 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -75,7 +75,6 @@ namespace Language_sv { PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sätt Origo"); - PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisterad justering"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard"); PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Välj Origo"); PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Senaste värde "); @@ -122,11 +121,11 @@ namespace Language_sv { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Flytta Axel"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bädd Nivellering"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivellera Bädd"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivellera Hörn"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Bra Punkter: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Senaste Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bädd Justering"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd"); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra Punkter: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Senaste Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nästa Hörn"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Nät Redigerare"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Redigera Nät"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 6858616b4d..bf218f136f 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -105,7 +105,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Eksen Hareketleri"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Tabla Hizalama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Tabla Hizası"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Hizalama Köşeleri"); + PROGMEM Language_Str MSG_BED_TRAMMING = _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"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index cee795745c..2e4a1b068c 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -161,16 +161,16 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Рух по осям"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Вирівнювання столу"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Вирівняти кути"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Вирівняти кути"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрацюв. зонду"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрацюв. зонду"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); #else - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрац.зонду"); - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирівн"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрац.зонду"); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирівн"); #endif - PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хороші точки: "); - PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Остання Z: "); + PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хороші точки: "); + PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Остання Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Наступний кут"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 825666d1e1..013a915921 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -90,7 +90,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Di chuyển trục"); // Move axis PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("San Lấp Bàn"); // Bed Leveling PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Làm bằng mặt bàn"); // Level bed - PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Làm bằng góc bàn"); // Level corners + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Làm bằng góc bàn"); // Level corners PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Góc tiếp theo"); // Next corner PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Chỉnh lưới đã dừng"); // Mesh Editing Stopped PROGMEM Language_Str MSG_MESH_X = _UxGT("Mục lục X"); // Index X diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 33eb7fca15..31d2623604 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -100,7 +100,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移动轴"); //"Move axis" 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_BED_TRAMMING = _UxGT("调平边角"); // "Bed Tramming" PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下个边角"); // "Next corner" PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("网格编辑器"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("编辑网格"); // "Edit Mesh" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 2061a66ad8..f162536132 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -98,7 +98,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移動軸"); //"Move axis" 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_BED_TRAMMING = _UxGT("調平邊角"); // "Bed Tramming" 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" diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 4811e2c60c..767c818851 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -179,7 +179,7 @@ static void _lcd_level_bed_corners_get_next_position() { // Display # of good points found vs total needed if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); - lcd_put_u8str_P(GET_TEXT(MSG_LEVEL_CORNERS_GOOD_POINTS)); + lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_GOOD_POINTS)); IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, cy)); lcd_put_u8str(GOOD_POINTS_TO_STR(good_points)); lcd_put_wchar('/'); @@ -192,7 +192,7 @@ static void _lcd_level_bed_corners_get_next_position() { // Display the Last Z value if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); - lcd_put_u8str_P(GET_TEXT(MSG_LEVEL_CORNERS_LAST_Z)); + lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_LAST_Z)); IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, 2)); lcd_put_u8str(LAST_Z_TO_STR(last_z)); } @@ -204,7 +204,7 @@ static void _lcd_level_bed_corners_get_next_position() { GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) , []{ corner_probing_done = true; wait_for_probe = false; } , []{ wait_for_probe = false; } - , GET_TEXT(MSG_LEVEL_CORNERS_RAISE) + , GET_TEXT(MSG_BED_TRAMMING_RAISE) , (const char*)nullptr, NUL_STR ); } @@ -214,7 +214,7 @@ static void _lcd_level_bed_corners_get_next_position() { MenuItem_confirm::confirm_screen( []{ queue.inject_P(TERN(HAS_LEVELING, PSTR("G29N"), G28_STR)); ui.return_to_status(); } , []{ ui.goto_previous_screen_no_defer(); } - , GET_TEXT(MSG_LEVEL_CORNERS_IN_RANGE) + , GET_TEXT(MSG_BED_TRAMMING_IN_RANGE) , (const char*)nullptr, PSTR("?") ); } diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 62cf8cf1c1..c03b933014 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -288,7 +288,7 @@ void menu_bed_leveling() { #endif #if ENABLED(LEVEL_BED_CORNERS) - SUBMENU(MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif #if ENABLED(EEPROM_SETTINGS) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 70f7acd547..45e751e29a 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -419,7 +419,7 @@ void menu_motion() { #endif #if ENABLED(LEVEL_BED_CORNERS) && DISABLED(LCD_BED_LEVELING) - SUBMENU(MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index 7ccb320f31..b5868f4056 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -61,7 +61,7 @@ static void _menu_single_probe(const uint8_t point) { tram_index = point; DEBUG_ECHOLNPAIR("Screen: single probe screen Arg:", point); START_MENU(); - STATIC_ITEM(MSG_LEVEL_CORNERS, SS_LEFT); + STATIC_ITEM(MSG_BED_TRAMMING, SS_LEFT); STATIC_ITEM(MSG_LAST_VALUE_SP, SS_LEFT, ftostr42_52(z_measured[0] - z_measured[point])); // Print diff ACTION_ITEM(MSG_UBL_BC_INSERT2, []{ if (probe_single_point()) ui.refresh(); }); ACTION_ITEM(MSG_BUTTON_DONE, []{ ui.goto_previous_screen(); }); // Back From 91db6038930528b06913a40884355d85c7550d70 Mon Sep 17 00:00:00 2001 From: George Fu Date: Sun, 25 Jul 2021 16:40:43 +0800 Subject: [PATCH 0454/2168] =?UTF-8?q?=F0=9F=94=A8=20Fix=20FYSETC=20S6=20en?= =?UTF-8?q?vs=20(#22421)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../PlatformIO/boards/marlin_fysetc_s6.json | 2 +- .../boards/marlin_fysetc_s6_8000.json | 35 ------------------- .../variants/MARLIN_FYSETC_S6/ldscript.ld | 4 +-- ini/stm32f4.ini | 2 +- 4 files changed, 4 insertions(+), 39 deletions(-) delete mode 100644 buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json diff --git a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json index 42a203786d..286e46ffbd 100644 --- a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json +++ b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6.json @@ -21,7 +21,7 @@ "name": "3D Printer control board", "upload": { "maximum_ram_size": 131072, - "maximum_size": 458752, + "maximum_size": 524288, "protocol": "stlink", "protocols": [ "jlink", diff --git a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json b/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json deleted file mode 100644 index 1d808a23d7..0000000000 --- a/buildroot/share/PlatformIO/boards/marlin_fysetc_s6_8000.json +++ /dev/null @@ -1,35 +0,0 @@ -{ - "build": { - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F446xx", - "f_cpu": "180000000L", - "mcu": "stm32f446ret6", - "variant": "MARLIN_FYSETC_S6" - }, - "connectivity": [ - "can" - ], - "debug": { - "jlink_device": "STM32F446RE", - "openocd_target": "stm32f4x", - "svd_path": "STM32F446x.svd" - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "3D Printer control board", - "upload": { - "maximum_ram_size": 131072, - "maximum_size": 491520, - "protocol": "stlink", - "protocols": [ - "jlink", - "stlink", - "blackmagic", - "serial" - ] - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html", - "vendor": "FYSETC" -} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld index 2a61072cb1..fee7418b04 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld @@ -60,8 +60,8 @@ _Min_Stack_Size = 0x400;; /* required amount of stack */ /* Specify the memory areas */ MEMORY { -FLASH (rx) : ORIGIN = 0x8010000, LENGTH = 512K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET } /* Define output sections */ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 901f145113..04fd03bf72 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -82,7 +82,7 @@ upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" [env:FYSETC_S6_8000] platform = ${common_stm32.platform} extends = env:FYSETC_S6 -board = marlin_fysetc_s6_8000 +board = marlin_fysetc_s6 board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" From 52718f3385fd663fc573c551b2dfb8123141a591 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 25 Jul 2021 03:58:16 -0500 Subject: [PATCH 0455/2168] =?UTF-8?q?=F0=9F=8E=A8=20Add=20DWIN=5FStatusCha?= =?UTF-8?q?nged=5FP?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 6 ++++++ Marlin/src/lcd/dwin/e3v2/dwin.h | 1 + 2 files changed, 7 insertions(+) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 114590a043..38017b64d6 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -4128,6 +4128,12 @@ void DWIN_StatusChanged(const char *text) { DWIN_UpdateLCD(); } +void DWIN_StatusChanged_P(PGM_P const pstr) { + char str[strlen_P((const char*)pstr) + 1]; + strcpy_P(str, (const char*)pstr); + DWIN_StatusChanged(str); +} + // GUI extension void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode=false) { DWIN_Draw_String(false,true,font8x16,Select_Color,bcolor,x+4,y,F(mode ? "x" : " ")); diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index 0272748cd5..4b3460aae5 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -404,6 +404,7 @@ void DWIN_Update(); void EachMomentUpdate(); void DWIN_HandleScreen(); void DWIN_StatusChanged(const char *text); +void DWIN_StatusChanged_P(PGM_P const pstr); void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode /* = false*/); inline void DWIN_StartHoming() { HMI_flag.home_flag = true; } From fc4f4ab5f5e47b5ac764ca6c2fe127dc9ecbf55d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 26 Jul 2021 00:58:34 +0000 Subject: [PATCH 0456/2168] [cron] Bump distribution date (2021-07-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0f8d2956bc..ef5cdcb464 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-25" +//#define STRING_DISTRIBUTION_DATE "2021-07-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9ecb34c27f..a3f7dbfca9 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 "2021-07-25" + #define STRING_DISTRIBUTION_DATE "2021-07-26" #endif /** From 70038a9961d45c91f4d30e7bfb8ca69af6646dcd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 27 Jul 2021 01:00:06 +0000 Subject: [PATCH 0457/2168] [cron] Bump distribution date (2021-07-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ef5cdcb464..71bbff479f 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-26" +//#define STRING_DISTRIBUTION_DATE "2021-07-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a3f7dbfca9..59260d252b 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 "2021-07-26" + #define STRING_DISTRIBUTION_DATE "2021-07-27" #endif /** From bf39c66d340fc34e111840554a5f644576c6447c Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 28 Jul 2021 09:05:44 +1200 Subject: [PATCH 0458/2168] =?UTF-8?q?=F0=9F=92=9A=20Specify=20compatible?= =?UTF-8?q?=20Teensy=20@4.12=20(#22448)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/teensy.ini | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/ini/teensy.ini b/ini/teensy.ini index ae33cc7a02..ef1ad766bc 100644 --- a/ini/teensy.ini +++ b/ini/teensy.ini @@ -9,11 +9,20 @@ # # ################################# +# +# Teensy++ 2.0 +# +[env:teensy20] +platform = teensy +extends = common_avr8 +board = teensy2pp +lib_ignore = ${env:common_avr8.lib_ignore}, NativeEthernet + # # Teensy 3.1 / 3.2 (ARM Cortex-M4) # [env:teensy31] -platform = teensy +platform = teensy@~4.12.0 board = teensy31 src_filter = ${common.default_src_filter} + lib_ignore = NativeEthernet @@ -22,13 +31,13 @@ lib_ignore = NativeEthernet # Teensy 3.5 / 3.6 (ARM Cortex-M4) # [env:teensy35] -platform = teensy +platform = teensy@~4.12.0 board = teensy35 src_filter = ${common.default_src_filter} + lib_ignore = NativeEthernet [env:teensy36] -platform = teensy +platform = teensy@~4.12.0 board = teensy36 src_filter = ${common.default_src_filter} + lib_ignore = NativeEthernet @@ -37,6 +46,6 @@ lib_ignore = NativeEthernet # Teensy 4.0 / 4.1 (ARM Cortex-M7) # [env:teensy41] -platform = teensy +platform = teensy@~4.12.0 board = teensy41 src_filter = ${common.default_src_filter} + From 284d0bf5a0ec141d31a7c52634236c29700116a2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 28 Jul 2021 01:01:06 +0000 Subject: [PATCH 0459/2168] [cron] Bump distribution date (2021-07-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 71bbff479f..5c2494d232 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-27" +//#define STRING_DISTRIBUTION_DATE "2021-07-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 59260d252b..9260d359fe 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 "2021-07-27" + #define STRING_DISTRIBUTION_DATE "2021-07-28" #endif /** From 4942cb796c24a669e6d9d177eb21e5b2f71fbde0 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 28 Jul 2021 16:28:15 +1200 Subject: [PATCH 0460/2168] =?UTF-8?q?=F0=9F=90=9B=20SAV=5F3DGLCD=20conditi?= =?UTF-8?q?onals=20(#22447)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 7e2239b3f6..4d6055b435 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -141,6 +141,13 @@ #define IS_RRD_SC 1 #define IS_U8GLIB_SSD1306 +#elif ENABLED(SAV_3DGLCD) + + #ifdef U8GLIB_SSD1306 + #define IS_U8GLIB_SSD1306 + #endif + #define IS_NEWPANEL 1 + #elif ENABLED(FYSETC_242_OLED_12864) #define IS_RRD_SC 1 From 296d0d495cad942cccd611b74a6b8a414a089a65 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Wed, 28 Jul 2021 06:30:41 +0200 Subject: [PATCH 0461/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Longer3D=20SDSS?= =?UTF-8?q?=20/=20SD=5FSS=20(#22444)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 391610522d..f9ec42b68e 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -140,6 +140,10 @@ #define TFT_BUFFER_SIZE 3200 #endif +#if ENABLED(SDIO_SUPPORT) + #define SD_SS_PIN -1 // else SDSS set to PA4 in M43 (spi_pins.h) +#endif + /** * Note: Alfawise U20/U30 boards DON'T use SPI2, as the hardware designer * mixed up MOSI and MISO pins. SPI is managed in SW, and needs pins @@ -148,7 +152,7 @@ #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PB12 // pin 51 SPI2_NSS #define TOUCH_SCK_PIN PB13 // pin 52 - #define TOUCH_MOSI_PIN PB14 // pin 53 + #define TOUCH_MOSI_PIN PB14 // pin 53 (Inverted MOSI/MISO = No HW SPI2) #define TOUCH_MISO_PIN PB15 // pin 54 #define TOUCH_INT_PIN PC6 // pin 63 (PenIRQ coming from ADS7843) #endif @@ -159,6 +163,7 @@ // #if NO_EEPROM_SELECTED //#define SPI_EEPROM + //#define HAS_SPI_FLASH 1 // need MARLIN_DEV_MODE for M993/M994 eeprom backup tests #define FLASH_EEPROM_EMULATION #endif @@ -171,6 +176,12 @@ #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... +#elif HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x40000U // limit to 256KB (M993 will reboot with 512) + #define W25QXX_CS_PIN PC5 + #define W25QXX_MOSI_PIN PA7 + #define W25QXX_MISO_PIN PA6 + #define W25QXX_SCK_PIN PA5 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2KB From 4ca5f6da3f8c0248fdf1c1572b1fa0c04a7e550d Mon Sep 17 00:00:00 2001 From: vyacheslav-shubin Date: Wed, 28 Jul 2021 22:55:04 +0300 Subject: [PATCH 0462/2168] =?UTF-8?q?=F0=9F=90=9B=20Reset=20workDirDepth?= =?UTF-8?q?=20in=20cdroot()=20(#22441)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index f3a913ced3..61b2b72bb6 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1024,6 +1024,7 @@ int8_t CardReader::cdup() { void CardReader::cdroot() { workDir = root; flag.workDirIsRoot = true; + workDirDepth = 0; TERN_(SDCARD_SORT_ALPHA, presort()); } From d5a9a04abecf6eaf819e9ccabd6702dccd984a9a Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 28 Jul 2021 12:56:26 -0700 Subject: [PATCH 0463/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20SKR=20Pro=20bad?= =?UTF-8?q?=20directive=20(#22438)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index fdc6c6f6e5..231dd9f594 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -254,7 +254,7 @@ #define TEMP_BED_PIN PF3 // T0 <-> Bed #endif -#ifdef TEMP_SENSOR_PROBE && !defined(TEMP_PROBE_PIN) +#if TEMP_SENSOR_PROBE && !defined(TEMP_PROBE_PIN) #if TEMP_SENSOR_PROBE_IS_AD8495 || TEMP_SENSOR_PROBE == 20 #if HOTENDS == 2 #define TEMP_PROBE_PIN PF10 From eacf1e33c468457bdcb26c8f6b7febd7133f769e Mon Sep 17 00:00:00 2001 From: charlespick <17918019+charlespick@users.noreply.github.com> Date: Wed, 28 Jul 2021 14:09:33 -0700 Subject: [PATCH 0464/2168] M76 Host Pause Feature (#21738) --- Marlin/Configuration_adv.h | 1 + Marlin/src/gcode/stats/M75-M78.cpp | 4 ++++ buildroot/tests/rambo | 2 +- 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7034632421..d32b61cbfa 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3819,6 +3819,7 @@ */ //#define HOST_ACTION_COMMANDS #if ENABLED(HOST_ACTION_COMMANDS) + //#define HOST_PAUSE_M76 //#define HOST_PROMPT_SUPPORT //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start #endif diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 568d9b0e27..f74d9204bd 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -23,6 +23,9 @@ #include "../gcode.h" #include "../../module/printcounter.h" #include "../../lcd/marlinui.h" +#if ENABLED(HOST_PAUSE_M76) + #include "../../feature/host_actions.h" +#endif #include "../../MarlinCore.h" // for startOrResumeJob @@ -38,6 +41,7 @@ void GcodeSuite::M75() { */ void GcodeSuite::M76() { print_job_timer.pause(); + TERN_(HOST_PAUSE_M76, host_action_pause()); } /** diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 6b87d01a5e..e755f81cf1 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -120,7 +120,7 @@ opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE PROBE_OFFSET_WIZARD \ Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ - SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT ADVANCED_OK M114_DETAIL \ + SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_PAUSE_M76 ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_USE_Z_ONLY exec_test $1 $2 "Rambo | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." "$3" From 885c63c35fdf41bdb91b67266be09cae93910787 Mon Sep 17 00:00:00 2001 From: borland1 Date: Wed, 28 Jul 2021 15:45:32 -0700 Subject: [PATCH 0465/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LCD=20Menu=20MBL?= =?UTF-8?q?=20Z-Offset=20Adjustment=20(#22450)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index c03b933014..f01c7899fb 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -278,7 +278,12 @@ void menu_bed_leveling() { // Mesh Bed Leveling Z-Offset // #if ENABLED(MESH_BED_LEVELING) - EDIT_ITEM(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); + #if WITHIN(Z_PROBE_OFFSET_RANGE_MIN, -9, 9) + #define LCD_Z_OFFSET_TYPE float43 // Values from -9.000 to +9.000 + #else + #define LCD_Z_OFFSET_TYPE float42_52 // Values from -99.99 to 99.99 + #endif + EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_BED_Z, &mbl.z_offset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) From 4111d1d5add6290ff02da668b0a024b06f189694 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Wed, 28 Jul 2021 17:15:01 -0600 Subject: [PATCH 0466/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FTDI=20Eve=20Tou?= =?UTF-8?q?ch=20UI=20progmem=20strings=20(#22439)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../bioprinter/confirm_home_e.cpp | 2 +- .../bioprinter/confirm_home_xyz.cpp | 2 +- .../ftdi_eve_touch_ui/bioprinter/main_menu.cpp | 18 +++++++++--------- .../bioprinter/status_screen.cpp | 2 +- .../ftdi_eve_touch_ui/bioprinter/tune_menu.cpp | 2 +- .../cocoa_press/leveling_menu.cpp | 2 +- .../ftdi_eve_touch_ui/cocoa_press/screens.h | 2 +- .../cocoa_press/status_screen.cpp | 2 +- .../generic/alert_dialog_box.cpp | 8 ++++---- .../generic/bed_mesh_edit_screen.cpp | 2 +- .../generic/dialog_box_base_class.cpp | 8 ++++++-- .../generic/dialog_box_base_class.h | 4 ++-- .../generic/leveling_menu.cpp | 6 +++--- .../ftdi_eve_touch_ui/generic/main_menu.cpp | 2 +- .../generic/move_axis_screen.cpp | 8 ++++---- .../generic/spinner_dialog_box.cpp | 15 +++++++++------ .../generic/spinner_dialog_box.h | 10 +++++++--- .../generic/z_offset_screen.cpp | 2 +- 18 files changed, 54 insertions(+), 43 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp index 21788c7f86..a5511f94b9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp @@ -36,7 +36,7 @@ bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { switch (tag) { case 1: #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) - SpinnerDialogBox::enqueueAndWait_P(PSTR( + SpinnerDialogBox::enqueueAndWait(F( "G28 E\n" AXIS_LEVELING_COMMANDS "\n" PARK_AND_RELEASE_COMMANDS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp index f3d7cdcbe4..e34df42b84 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp @@ -36,7 +36,7 @@ bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { switch (tag) { case 1: #ifdef PARK_AND_RELEASE_COMMANDS - SpinnerDialogBox::enqueueAndWait_P(PSTR( + SpinnerDialogBox::enqueueAndWait(F( "G28\n" PARK_AND_RELEASE_COMMANDS )); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index c7e18e2718..adc84dfa25 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -67,17 +67,17 @@ bool MainMenu::onTouchEnd(uint8_t tag) { const bool e_homed = isAxisPositionKnown(E0); switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? PSTR("G0 E0 F120") : PSTR("G112")); break; - case 4: StatusScreen::unlockMotors(); break; + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; + case 3: SpinnerDialogBox::enqueueAndWait(e_homed ? F("G0 E0 F120") : F("G112")); break; + case 4: StatusScreen::unlockMotors(); break; #ifdef AXIS_LEVELING_COMMANDS - case 5: SpinnerDialogBox::enqueueAndWait_P(PSTR(AXIS_LEVELING_COMMANDS)); break; + case 5: SpinnerDialogBox::enqueueAndWait(F(AXIS_LEVELING_COMMANDS)); break; #endif - case 6: GOTO_SCREEN(TemperatureScreen); break; - case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; - case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - case 9: GOTO_SCREEN(AboutScreen); break; + case 6: GOTO_SCREEN(TemperatureScreen); break; + case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; + case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; + case 9: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp index a349e04173..1382a13bf8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -316,7 +316,7 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { case 9: GOTO_SCREEN(FilesScreen); break; case 10: GOTO_SCREEN(MainMenu); break; case 13: GOTO_SCREEN(BioConfirmHomeE); break; - case 14: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Z")); break; + case 14: SpinnerDialogBox::enqueueAndWait(F("G28Z")); break; case 15: GOTO_SCREEN(TemperatureScreen); break; case 16: fine_motion = !fine_motion; break; default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp index 4c4875a603..48eff0a661 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -67,7 +67,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { case 3: GOTO_SCREEN(TemperatureScreen); break; case 4: GOTO_SCREEN(NudgeNozzleScreen); break; case 5: GOTO_SCREEN(BioConfirmHomeXYZ); break; - case 6: SpinnerDialogBox::enqueueAndWait_P(PSTR("G0 E0 F120")); break; + case 6: SpinnerDialogBox::enqueueAndWait(F("G0 E0 F120")); break; case 7: StatusScreen::unlockMotors(); break; default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index 6d3037da4b..2e3472987e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -82,7 +82,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { case 3: BedMeshViewScreen::show(); break; case 4: BedMeshEditScreen::show(); break; case 5: injectCommands_P(PSTR("M280 P0 S60")); break; - case 6: SpinnerDialogBox::enqueueAndWait_P(PSTR("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + case 6: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; default: return false; } return true; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h index 87d31da6f6..8481e446c4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -108,7 +108,6 @@ enum { #include "../generic/display_tuning_screen.h" #include "../generic/statistics_screen.h" #include "../generic/stepper_current_screen.h" -#include "../generic/leveling_menu.h" #include "../generic/z_offset_screen.h" #include "../generic/bed_mesh_base.h" #include "../generic/bed_mesh_view_screen.h" @@ -130,5 +129,6 @@ enum { #include "preheat_menu.h" #include "preheat_screen.h" #include "load_chocolate.h" +#include "leveling_menu.h" #include "move_xyz_screen.h" #include "move_e_screen.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index 96572e0538..af3875967d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -233,7 +233,7 @@ bool StatusScreen::onTouchStart(uint8_t) { bool StatusScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28 O\nG27")); break; + case 1: SpinnerDialogBox::enqueueAndWait(F("G28 O\nG27")); break; case 2: GOTO_SCREEN(LoadChocolateScreen); break; case 3: GOTO_SCREEN(PreheatMenu); break; case 4: GOTO_SCREEN(MainMenu); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp index ccdfa89419..0d309bff75 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp @@ -43,7 +43,7 @@ void AlertDialogBox::onRedraw(draw_mode_t what) { } template -void AlertDialogBox::show(const T message) { +void AlertDialogBox::show(T message) { drawMessage(message); storeBackground(); mydata.isError = false; @@ -51,7 +51,7 @@ void AlertDialogBox::show(const T message) { } template -void AlertDialogBox::showError(const T message) { +void AlertDialogBox::showError(T message) { drawMessage(message); storeBackground(); mydata.isError = true; @@ -64,8 +64,8 @@ void AlertDialogBox::hide() { } template void AlertDialogBox::show(const char *); -template void AlertDialogBox::show(const progmem_str); +template void AlertDialogBox::show(progmem_str); template void AlertDialogBox::showError(const char *); -template void AlertDialogBox::showError(const progmem_str); +template void AlertDialogBox::showError(progmem_str); #endif // FTDI_ALERT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 27611eefab..c7d0cc3f73 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -191,7 +191,7 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { void BedMeshEditScreen::show() { // On entry, always home (to account for possible Z offset changes) and save current mesh - SpinnerDialogBox::enqueueAndWait_P(PSTR("G28\nG29 S1")); + SpinnerDialogBox::enqueueAndWait(F("G28\nG29 S1")); // After the spinner, go to this screen. current_screen.forget(); PUSH_SCREEN(BedMeshEditScreen); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index 0d604751f1..500551e862 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -32,7 +32,7 @@ using namespace Theme; #define GRID_ROWS 8 template -void DialogBoxBaseClass::drawMessage(const T message, int16_t font) { +void DialogBoxBaseClass::drawMessage(T message, int16_t font) { CommandProcessor cmd; cmd.cmd(CMD_DLSTART) .cmd(CLEAR_COLOR_RGB(bg_color)) @@ -59,12 +59,16 @@ void DialogBoxBaseClass::drawOkayButton() { .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); } -void DialogBoxBaseClass::drawButton(const progmem_str label) { +template +void DialogBoxBaseClass::drawButton(T label) { CommandProcessor cmd; cmd.font(font_medium) .tag(1).button(BTN_POS(1,8), BTN_SIZE(2,1), label); } +template void DialogBoxBaseClass::drawButton(const char *); +template void DialogBoxBaseClass::drawButton(progmem_str); + void DialogBoxBaseClass::drawSpinner() { CommandProcessor cmd; cmd.cmd(COLOR_RGB(bg_text_enabled)) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h index ef5e6b569b..d48f3a03b3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h @@ -27,11 +27,11 @@ class DialogBoxBaseClass : public BaseScreen { protected: - template static void drawMessage(const T, int16_t font = 0); + template static void drawMessage(T, int16_t font = 0); + template static void drawButton(T); static void drawYesNoButtons(uint8_t default_btn = 0); static void drawOkayButton(); static void drawSpinner(); - static void drawButton(const progmem_str); static void onRedraw(draw_mode_t) {}; public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 29b9f47ddd..fe5324ae62 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -104,7 +104,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) - case 2: SpinnerDialogBox::enqueueAndWait_P(PSTR("G34")); break; + case 2: SpinnerDialogBox::enqueueAndWait(F("G34")); break; #endif #if HAS_BED_PROBE case 3: @@ -114,7 +114,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #if ENABLED(AUTO_BED_LEVELING_UBL) BedMeshViewScreen::doProbe(); #else - SpinnerDialogBox::enqueueAndWait_P(PSTR(BED_LEVELING_COMMANDS)); + SpinnerDialogBox::enqueueAndWait(F(BED_LEVELING_COMMANDS)); #endif break; #endif @@ -127,7 +127,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #endif #if ENABLED(BLTOUCH) case 7: injectCommands_P(PSTR("M280 P0 S60")); break; - case 8: SpinnerDialogBox::enqueueAndWait_P(PSTR("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + case 8: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; #endif default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index f02bfac99f..a6c39db796 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -104,7 +104,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28")); break; + case 2: SpinnerDialogBox::enqueueAndWait(F("G28")); break; #if ENABLED(NOZZLE_CLEAN_FEATURE) case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index 6fbfd258e6..ae396c4ec5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -98,10 +98,10 @@ bool BaseMoveAxisScreen::onTouchHeld(uint8_t tag) { case 14: UI_DECREMENT_AXIS(E3); mydata.e_rel[3] -= increment; break; case 15: UI_INCREMENT_AXIS(E3); mydata.e_rel[3] += increment; break; #endif - case 20: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28X")); break; - case 21: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Y")); break; - case 22: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28Z")); break; - case 23: SpinnerDialogBox::enqueueAndWait_P(PSTR("G28")); break; + case 20: SpinnerDialogBox::enqueueAndWait(F("G28X")); break; + case 21: SpinnerDialogBox::enqueueAndWait(F("G28Y")); break; + case 22: SpinnerDialogBox::enqueueAndWait(F("G28Z")); break; + case 23: SpinnerDialogBox::enqueueAndWait(F("G28")); break; case 24: raiseZtoTop(); break; default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 489beabe6b..1b267698c3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -34,7 +34,7 @@ constexpr static SpinnerDialogBoxData &mydata = screen_data.SpinnerDialogBox; void SpinnerDialogBox::onRedraw(draw_mode_t) { } -void SpinnerDialogBox::show(const progmem_str message) { +void SpinnerDialogBox::show(progmem_str message) { drawMessage(message); drawSpinner(); storeBackground(); @@ -46,17 +46,20 @@ void SpinnerDialogBox::hide() { cmd.stop().execute(); } -void SpinnerDialogBox::enqueueAndWait_P(const progmem_str commands) { - enqueueAndWait_P(GET_TEXT_F(MSG_PLEASE_WAIT), commands); -} - -void SpinnerDialogBox::enqueueAndWait_P(const progmem_str message, const progmem_str commands) { +void SpinnerDialogBox::enqueueAndWait(progmem_str message, progmem_str commands) { show(message); GOTO_SCREEN(SpinnerDialogBox); ExtUI::injectCommands_P((const char*)commands); mydata.auto_hide = true; } +void SpinnerDialogBox::enqueueAndWait(progmem_str message, char *commands) { + show(message); + GOTO_SCREEN(SpinnerDialogBox); + ExtUI::injectCommands(commands); + mydata.auto_hide = true; +} + void SpinnerDialogBox::onIdle() { reset_menu_timeout(); if (mydata.auto_hide && !commandsInQueue()) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h index c5f0ae8e9f..deb07285a9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h @@ -34,8 +34,12 @@ class SpinnerDialogBox : public DialogBoxBaseClass, public CachedScreen + static void enqueueAndWait(T commands) {enqueueAndWait(GET_TEXT_F(MSG_PLEASE_WAIT), commands);} + + static void enqueueAndWait(progmem_str message, char *commands); + static void enqueueAndWait(progmem_str message, progmem_str commands); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp index 2a75596a03..eb36798794 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/z_offset_screen.cpp @@ -84,7 +84,7 @@ void ZOffsetScreen::runWizard() { strcat(cmd, str); injectCommands(cmd); // Show instructions for user. - AlertDialogBox::show(PSTR("After the printer finishes homing, adjust the Z Offset so that a sheet of paper can pass between the nozzle and bed with slight resistance.")); + AlertDialogBox::show(F("After the printer finishes homing, adjust the Z Offset so that a sheet of paper can pass between the nozzle and bed with slight resistance.")); } bool ZOffsetScreen::wizardRunning() { From b37e851f3664f6b349f609115ffe55ef5b5b9280 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 29 Jul 2021 00:57:39 +0000 Subject: [PATCH 0467/2168] [cron] Bump distribution date (2021-07-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5c2494d232..a53db6aea8 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-28" +//#define STRING_DISTRIBUTION_DATE "2021-07-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9260d359fe..86b87a033c 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 "2021-07-28" + #define STRING_DISTRIBUTION_DATE "2021-07-29" #endif /** From a70d0726caf0c3a235c1bf9047833d60b45189ed Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Wed, 28 Jul 2021 21:56:22 -0500 Subject: [PATCH 0468/2168] =?UTF-8?q?=F0=9F=93=BA=20MKS=20MINI12864=20V3?= =?UTF-8?q?=20for=20Robin=20E3P,=20etc.=20(#22453)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 4 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 78 +++++++++++++------ .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 1 + Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 3 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 4 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 1 + Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 4 +- 8 files changed, 66 insertions(+), 31 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index bdf3f48c3a..31b03f6b07 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -41,7 +41,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role @@ -65,7 +65,7 @@ #define SD_SCK_PIN PB13 // SPI2 #define SD_MISO_PIN PB14 // SPI2 #define SD_MOSI_PIN PB15 // SPI2 -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // SPI Flash #define HAS_SPI_FLASH 1 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index c7850903e7..b32d0aa0b8 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -38,6 +38,9 @@ #define BOARD_NO_NATIVE_USB #define MKS_HARDWARE_TEST_ONLY_E0 +// Avoid conflict with TIMER_SERVO when using the STM32 HAL +#define TEMP_TIMER 5 + // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // @@ -214,17 +217,23 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT -#define SDIO_CLOCK 4500000 // 4.5 MHz -#define SD_DETECT_PIN PD12 -#define ONBOARD_SD_CS_PIN PC11 +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT + #define SDIO_CLOCK 4500000 // 4.5 MHz + #define SD_DETECT_PIN PD12 + #define ONBOARD_SD_CS_PIN PC11 +#elif SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 +#endif // // LCD / Controller // -#ifndef BEEPER_PIN - #define BEEPER_PIN PC5 -#endif /** * Note: MKS Robin TFT screens use various TFT controllers. @@ -261,33 +270,29 @@ #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef TFT_WIDTH - #define TFT_WIDTH 480 - #endif - #ifndef TFT_HEIGHT - #define TFT_HEIGHT 320 - #endif - - #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI #endif -#if HAS_SPI_GRAPHICAL_TFT +#if ENABLED(TFT_CLASSIC_UI) // Emulated DOGM SPI #define LCD_PINS_ENABLE PD13 #define LCD_PINS_RS PC6 #define BTN_ENC PE13 #define BTN_EN1 PE8 #define BTN_EN2 PE11 -#elif ENABLED(TFT_480x320_SPI) - #define TFT_DRIVER ST7796 +#elif ENABLED(TFT_COLOR_UI) #define TFT_BUFFER_SIZE 14400 #endif #if HAS_WIRED_LCD && !HAS_SPI_TFT - - // NON TFT Displays + #define BEEPER_PIN PC5 + #define BTN_ENC PE13 + #define LCD_PINS_ENABLE PD13 + #define LCD_PINS_RS PC6 + #define BTN_EN1 PE8 + #define BTN_EN2 PE11 + #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) @@ -301,9 +306,32 @@ #define DOGLCD_SCK PA5 #define DOGLCD_MOSI PA7 - // Required for MKS_MINI_12864 with this board - #define MKS_LCD12864B - #undef SHOW_BOOTSCREEN + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define PIN_SPI_SCK PA5 + #define PIN_TFT_MISO PA6 + #define PIN_TFT_MOSI PA7 + #define TFTGLCD_CS PE8 + #endif + + #ifndef BEEPER_PIN + #define BEEPER_PIN -1 + #endif + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PD13 + #define DOGLCD_A0 PC6 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PE14 + #define NEOPIXEL_PIN PE15 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 @@ -342,6 +370,10 @@ #define W25QXX_SCK_PIN PB13 #endif +#ifndef BEEPER_PIN + #define BEEPER_PIN PC5 +#endif + #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 #error "MKS Robin nano default BEEPER_PIN is not a SPEAKER." #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index b5d02942f3..44c35b9d04 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -166,6 +166,7 @@ #define DOGLCD_SCK PB13 #define FORCE_SOFT_SPI #define SOFTWARE_SPI + //#define LCD_SCREEN_ROT_180 #else diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 95d62f05a4..147aec5e9f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -37,7 +37,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 7bbc2b26da..4b0ba2fdab 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -38,7 +38,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role @@ -345,6 +345,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 34124a9b02..77257f818a 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -33,8 +33,8 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME // Avoid conflict with fans and TIMER_TONE -#define TEMP_TIMER 3 -#define STEP_TIMER 5 +#define TEMP_TIMER 3 +#define STEP_TIMER 5 // // EEPROM Emulation diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 182506f11e..6795b92892 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -365,6 +365,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index be6e4f8a34..7bf148874c 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -45,8 +45,8 @@ // This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant // included with the STM32 framework. -#define STEP_TIMER 10 -#define TEMP_TIMER 14 +#define STEP_TIMER 10 +#define TEMP_TIMER 14 // // Limit Switches From 363e83731f7b045d7b3e9842882b1f53e032ca89 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jul 2021 23:24:30 -0500 Subject: [PATCH 0469/2168] =?UTF-8?q?=F0=9F=94=A7=20HAS=5FCUSTOM=5FPROBE?= =?UTF-8?q?=5FPIN=20=3D>=20USES=5FZ=5FMIN=5FPROBE=5FPIN?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 4 ++-- Marlin/src/inc/Conditionals_LCD.h | 4 ++-- Marlin/src/inc/Conditionals_post.h | 4 ++-- Marlin/src/module/endstops.cpp | 16 ++++++++-------- Marlin/src/module/endstops.h | 2 +- Marlin/src/module/probe.h | 2 +- Marlin/src/pins/pins_postprocess.h | 2 +- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 2 +- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 2 +- 9 files changed, 19 insertions(+), 19 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 46a876a836..23d797b2ab 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -146,7 +146,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (2) conflict with other pins!" #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" - #elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) + #elif USES_Z_MIN_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" #elif ANY_TX(2, X_ENABLE_PIN, Y_ENABLE_PIN) || ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with X/Y stepper pins!" @@ -237,7 +237,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #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) + #elif USES_Z_MIN_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!" diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 4d6055b435..cd9f127e28 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -911,9 +911,9 @@ #define HAS_PROBE_XY_OFFSET 1 #endif #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) - #define HAS_CUSTOM_PROBE_PIN 1 + #define USES_Z_MIN_PROBE_PIN 1 #endif - #if Z_HOME_TO_MIN && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && (!USES_Z_MIN_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index b6cf8eccb6..da17d18af1 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2092,7 +2092,7 @@ // // Is an endstop plug used for extra Z endstops or the probe? -#define IS_PROBE_PIN(A,M) (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN) +#define IS_PROBE_PIN(A,M) (USES_Z_MIN_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN) #define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_) #define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_) #define IS_Z2_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_) @@ -2166,7 +2166,7 @@ #if PIN_EXISTS(Z4_MAX) #define HAS_Z4_MAX 1 #endif -#if BOTH(HAS_BED_PROBE, HAS_CUSTOM_PROBE_PIN) && PIN_EXISTS(Z_MIN_PROBE) +#if BOTH(HAS_BED_PROBE, USES_Z_MIN_PROBE_PIN) && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 420acccb58..39aefd21d8 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -329,7 +329,7 @@ void Endstops::init() { #endif #endif - #if HAS_CUSTOM_PROBE_PIN + #if USES_Z_MIN_PROBE_PIN #if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE) SET_INPUT_PULLUP(Z_MIN_PROBE_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN_PROBE) @@ -453,7 +453,7 @@ void Endstops::event_handler() { _ENDSTOP_HIT_TEST(K,'K') ); - #if HAS_CUSTOM_PROBE_PIN + #if USES_Z_MIN_PROBE_PIN #define P_AXIS Z_AXIS if (TEST(hit_state, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P'); #endif @@ -566,7 +566,7 @@ void _O2 Endstops::report_states() { #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN)); #endif - #if HAS_CUSTOM_PROBE_PIN + #if USES_Z_MIN_PROBE_PIN print_es_state(PROBE_TRIGGERED(), PSTR(STR_Z_PROBE)); #endif #if MULTI_FILAMENT_SENSOR @@ -720,7 +720,7 @@ void Endstops::update() { #if HAS_BED_PROBE // When closing the gap check the enabled probe if (probe_switch_activated()) - UPDATE_ENDSTOP_BIT(Z, TERN(HAS_CUSTOM_PROBE_PIN, MIN_PROBE, MIN)); + UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); #endif #if HAS_Z_MAX && !Z_SPI_SENSORLESS @@ -746,7 +746,7 @@ void Endstops::update() { COPY_LIVE_STATE(Z_MAX, Z4_MAX); #endif #endif - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN + #elif !USES_Z_MIN_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // If this pin isn't the bed probe it's the Z endstop UPDATE_ENDSTOP_BIT(Z, MAX); #endif @@ -1021,7 +1021,7 @@ void Endstops::update() { #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) - && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) + && TERN1(USES_Z_MIN_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); #if CORE_DIAG(XZ, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); @@ -1035,7 +1035,7 @@ void Endstops::update() { #endif // When closing the gap check the enabled probe - #if HAS_CUSTOM_PROBE_PIN + #if USES_Z_MIN_PROBE_PIN if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); #endif } @@ -1043,7 +1043,7 @@ void Endstops::update() { #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) #if ENABLED(Z_MULTI_ENDSTOPS) PROCESS_ENDSTOP_Z(MAX); - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX + #elif !USES_Z_MIN_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX PROCESS_ENDSTOP(Z, MAX); #endif #if CORE_DIAG(XZ, X, MIN) diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index e8365ce1ed..f4532ca1a0 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -69,7 +69,7 @@ enum EndstopEnum : char { #endif // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) - _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(HAS_CUSTOM_PROBE_PIN, = Z_MIN)) + _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(USES_Z_MIN_PROBE_PIN, = Z_MIN)) // The total number of states NUM_ENDSTOP_STATES diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 62880c865f..ce690593f2 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -38,7 +38,7 @@ }; #endif -#if HAS_CUSTOM_PROBE_PIN +#if USES_Z_MIN_PROBE_PIN #define PROBE_TRIGGERED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) #else #define PROBE_TRIGGERED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index ac4459bd02..f7152770e5 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -1134,7 +1134,7 @@ #define USE_ZMIN_PLUG #endif #undef _STOP_IN_USE -#if !HAS_CUSTOM_PROBE_PIN +#if !USES_Z_MIN_PROBE_PIN #undef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN -1 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index b217428911..b5569c810d 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -117,7 +117,7 @@ //#define E3_MS2_PIN ? //#define E3_MS3_PIN ? -#if HAS_CUSTOM_PROBE_PIN +#if USES_Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 49 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 7002886908..b06de1bc69 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -105,7 +105,7 @@ #define E2_CS_PIN 61 #endif -#if HAS_CUSTOM_PROBE_PIN +#if USES_Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 49 #endif From cdcb45b87eef8a590ea3f7adef24a10f8dce8e9e Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 29 Jul 2021 17:19:49 -0600 Subject: [PATCH 0470/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FTDI=20Eve=20uni?= =?UTF-8?q?code=20and=20spinner=20dialog=20(#22459)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 10 ++++++---- .../ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp | 9 +++++---- .../ftdi_eve_touch_ui/generic/spinner_dialog_box.h | 1 + 3 files changed, 12 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 2bb44e81d0..bb622c3cc5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -68,15 +68,17 @@ utf8_char_t FTDI::get_utf8_char_and_inc(const char *&c) { utf8_char_t val = *(uint8_t*)c++; - while ((*c & 0xC0) == 0x80) - val = (val << 8) | *(uint8_t*)c++; + if ((val & 0xC0) == 0x80) + while ((*c & 0xC0) == 0x80) + val = (val << 8) | *(uint8_t*)c++; return val; } utf8_char_t FTDI::get_utf8_char_and_inc(char *&c) { utf8_char_t val = *(uint8_t*)c++; - while ((*c & 0xC0) == 0x80) - val = (val << 8) | *(uint8_t*)c++; + if ((val & 0xC0) == 0x80) + while ((*c & 0xC0) == 0x80) + val = (val << 8) | *(uint8_t*)c++; return val; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 1b267698c3..fecf407285 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -31,6 +31,10 @@ using namespace ExtUI; constexpr static SpinnerDialogBoxData &mydata = screen_data.SpinnerDialogBox; +void SpinnerDialogBox::onEntry() { + mydata.auto_hide = true; +} + void SpinnerDialogBox::onRedraw(draw_mode_t) { } @@ -38,6 +42,7 @@ void SpinnerDialogBox::show(progmem_str message) { drawMessage(message); drawSpinner(); storeBackground(); + GOTO_SCREEN(SpinnerDialogBox); mydata.auto_hide = false; } @@ -48,16 +53,12 @@ void SpinnerDialogBox::hide() { void SpinnerDialogBox::enqueueAndWait(progmem_str message, progmem_str commands) { show(message); - GOTO_SCREEN(SpinnerDialogBox); ExtUI::injectCommands_P((const char*)commands); - mydata.auto_hide = true; } void SpinnerDialogBox::enqueueAndWait(progmem_str message, char *commands) { show(message); - GOTO_SCREEN(SpinnerDialogBox); ExtUI::injectCommands(commands); - mydata.auto_hide = true; } void SpinnerDialogBox::onIdle() { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h index deb07285a9..4a561980c0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h @@ -31,6 +31,7 @@ struct SpinnerDialogBoxData { class SpinnerDialogBox : public DialogBoxBaseClass, public CachedScreen { public: + static void onEntry(); static void onRedraw(draw_mode_t); static void onIdle(); From 543d834a254544671bbeee937601704fc2dfad7a Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 30 Jul 2021 11:25:06 +1200 Subject: [PATCH 0471/2168] =?UTF-8?q?=F0=9F=93=9D=20Document=20DGUS=20disp?= =?UTF-8?q?lay=20options=20(#22443)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4adc40a19f..1b4d630681 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2535,11 +2535,33 @@ // DGUS Touch Display with DWIN OS. (Choose one.) // ORIGIN : https://www.aliexpress.com/item/32993409517.html // FYSETC : https://www.aliexpress.com/item/32961471929.html +// MKS : https://www.aliexpress.com/item/1005002008179262.html +// +// Flash display with DGUS Displays for Marlin: +// - Format the SD card to FAT32 with an allocation size of 4kb. +// - Download files as specified for your type of display. +// - Plug the microSD card into the back of the display. +// - Boot the display and wait for the update to complete. +// +// ORIGIN (Marlin DWIN_SET) +// - Download https://github.com/coldtobi/Marlin_DGUS_Resources +// - Copy the downloaded DWIN_SET folder to the SD card. +// +// FYSETC (Supplier default) +// - Download https://github.com/FYSETC/FYSTLCD-2.0 +// - Copy the downloaded SCREEN folder to the SD card. +// +// HIPRECY (Supplier default) +// - Download https://github.com/HiPrecy/Touch-Lcd-LEO +// - Copy the downloaded DWIN_SET folder to the SD card. +// +// MKS (MKS-H43) (Supplier default) +// - Download https://github.com/makerbase-mks/MKS-H43 +// - Copy the downloaded DWIN_SET folder to the SD card. // //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC //#define DGUS_LCD_UI_HIPRECY - //#define DGUS_LCD_UI_MKS #if ENABLED(DGUS_LCD_UI_MKS) #define USE_MKS_GREEN_UI From 46dc8e916f2b235dfcc73d258e66acf530cb51ee Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 19:34:49 -0500 Subject: [PATCH 0472/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=203-point=20leveli?= =?UTF-8?q?ng=20position?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #22457. Fixes a G29 regression from #19112. --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 729bca93a6..0c0fb07760 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -568,7 +568,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points if (abl.abl_probe_index < abl.abl_points) { - abl.probePos = points[abl.abl_probe_index]; + abl.probePos = xy_pos_t(points[abl.abl_probe_index]); _manual_goto_xy(abl.probePos); // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled From 99a53e2c86e95cea0427742b267b244870526304 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 19:55:04 -0500 Subject: [PATCH 0473/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=205-axis=20no=20ex?= =?UTF-8?q?truder=20compile?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22446 --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/module/planner.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index cd9f127e28..d47bfcb81a 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1060,7 +1060,7 @@ #endif // 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)) +#if HAS_EXTRUDERS && (ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE))) #define HAS_CLASSIC_E_JERK 1 #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e48d05b09f..52ca76308c 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2684,7 +2684,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #ifndef TRAVEL_EXTRA_XYJERK #define TRAVEL_EXTRA_XYJERK 0 #endif - const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; + const float extra_xyjerk = TERN0(HAS_EXTRUDERS, de <= 0) ? TRAVEL_EXTRA_XYJERK : 0; uint8_t limited = 0; TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) { From 2b8ef7416208488dde3ff9f75912eef58bb3996b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 30 Jul 2021 01:01:02 +0000 Subject: [PATCH 0474/2168] [cron] Bump distribution date (2021-07-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a53db6aea8..7ef779ac84 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-29" +//#define STRING_DISTRIBUTION_DATE "2021-07-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 86b87a033c..264777d3a8 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 "2021-07-29" + #define STRING_DISTRIBUTION_DATE "2021-07-30" #endif /** From 6eae68c402d13237e020c0b358003e618e1ecec3 Mon Sep 17 00:00:00 2001 From: George Fu Date: Fri, 30 Jul 2021 09:09:38 +0800 Subject: [PATCH 0475/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Larger=20FYSETC?= =?UTF-8?q?=20S6=20I2C=20EEPROM=20size=20(#22424)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 504a86d7d0..492383048e 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -50,7 +50,7 @@ // 128 kB sector allocated for EEPROM emulation. #define FLASH_EEPROM_LEVELING #elif ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x0800 // 2KB + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif // From 6efd7285ccbacc55402ca7b704be0f051af34097 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 22:23:06 -0500 Subject: [PATCH 0476/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20PAUSE=5FPROBE=5F?= =?UTF-8?q?DEPLOY=5FWHEN=5FTRIGGERED?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22295. Regression from #20241. --- Marlin/src/module/probe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index d585afb8b2..d0f32a32c0 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -287,7 +287,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #if ENABLED(PAUSE_BEFORE_DEPLOY_STOW) do { #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) - if (deploy == PROBE_TRIGGERED()) break; + if (deploy != PROBE_TRIGGERED()) break; #endif BUZZ(100, 659); From 14d40fb95721f0e95099f2aafea196290b218d6c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 22:59:33 -0500 Subject: [PATCH 0477/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20PAUSE=5FMESSAGE?= =?UTF-8?q?=5FPAUSING=3D>PARKING?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22250. Regression from #17460. --- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_dialog.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 44cee6cb60..a1bfb7fc86 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -238,7 +238,7 @@ void lv_draw_dialog(uint8_t type) { lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text } - else if (DIALOG_IS(PAUSE_MESSAGE_PAUSING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_LOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_RESUME, PAUSE_MESSAGE_HEATING)) { + else if (DIALOG_IS(PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_LOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_RESUME, PAUSE_MESSAGE_HEATING)) { // nothing to do } else if (DIALOG_IS(WIFI_ENABLE_TIPS)) { @@ -324,7 +324,7 @@ void lv_draw_dialog(uint8_t type) { lv_label_set_text(labelDialog, print_file_dialog_menu.print_finish); lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); } - else if (DIALOG_IS(PAUSE_MESSAGE_PAUSING)) { + else if (DIALOG_IS(PAUSE_MESSAGE_PARKING)) { lv_label_set_text(labelDialog, pause_msg_menu.pausing); lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h index e53d48a2b8..7e98a80c0a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h @@ -54,7 +54,7 @@ enum { DIALOG_WIFI_ENABLE_TIPS, - DIALOG_PAUSE_MESSAGE_PAUSING, + DIALOG_PAUSE_MESSAGE_PARKING, DIALOG_PAUSE_MESSAGE_CHANGING, DIALOG_PAUSE_MESSAGE_UNLOAD, DIALOG_PAUSE_MESSAGE_WAITING, diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index 608b3366b1..485e010251 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -31,7 +31,7 @@ void lv_draw_pause_message(const PauseMessage msg) { switch (msg) { - case PAUSE_MESSAGE_PAUSING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_PAUSING); break; + case PAUSE_MESSAGE_PARKING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_PARKING); break; case PAUSE_MESSAGE_CHANGING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_CHANGING); break; case PAUSE_MESSAGE_UNLOAD: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_UNLOAD); break; case PAUSE_MESSAGE_WAITING: clear_cur_ui(); lv_draw_dialog(DIALOG_PAUSE_MESSAGE_WAITING); break; From 84ca21edf76d1e2e4830b5fcc3b454db05cbe871 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 23:40:27 -0500 Subject: [PATCH 0478/2168] =?UTF-8?q?=F0=9F=8E=A8=20abs=20=3D>=20ABS?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/probe_temp_comp.cpp | 4 ++-- Marlin/src/gcode/bedlevel/G35.cpp | 6 +++--- Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 20 +++++++++---------- .../generic/move_axis_screen.cpp | 2 +- .../lcd/extui/mks_ui/draw_baby_stepping.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 4 ++-- .../src/lcd/extui/mks_ui/draw_extrusion.cpp | 2 +- .../lcd/extui/mks_ui/draw_filament_change.cpp | 4 ++-- .../src/lcd/extui/mks_ui/draw_move_motor.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- 11 files changed, 26 insertions(+), 26 deletions(-) diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index c9d6c6cb3f..e39896d4dc 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -143,13 +143,13 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { // Sanity check for (calib_idx = 0; calib_idx < measurements; ++calib_idx) { // Restrict the max. offset - if (abs(data[calib_idx]) > 2000) { + if (ABS(data[calib_idx]) > 2000) { SERIAL_ECHOLNPGM("!Invalid Z-offset detected (0-2)."); clear_offsets(tsi); return false; } // Restrict the max. offset difference between two probings - if (calib_idx > 0 && abs(data[calib_idx - 1] - data[calib_idx]) > 800) { + if (calib_idx > 0 && ABS(data[calib_idx - 1] - data[calib_idx]) > 800) { SERIAL_ECHOLNPGM("!Invalid Z-offset between two probings detected (0-0.8)."); clear_offsets(TSI_PROBE); return false; diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 44df6d9273..12b6f4793b 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -130,7 +130,7 @@ void GcodeSuite::G35() { // Calculate adjusts LOOP_S_L_N(i, 1, G35_PROBE_COUNT) { const float diff = z_measured[0] - z_measured[i], - adjust = abs(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; + adjust = ABS(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; const int full_turns = trunc(adjust); const float decimal_part = adjust - float(full_turns); @@ -138,8 +138,8 @@ void GcodeSuite::G35() { SERIAL_ECHOPGM("Turn "); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); - SERIAL_ECHOPAIR(" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", " by ", abs(full_turns), " turns"); - if (minutes) SERIAL_ECHOPAIR(" and ", abs(minutes), " minutes"); + SERIAL_ECHOPAIR(" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", " by ", ABS(full_turns), " turns"); + if (minutes) SERIAL_ECHOPAIR(" and ", ABS(minutes), " minutes"); if (ENABLED(REPORT_TRAMMING_MM)) SERIAL_ECHOPAIR(" (", -diff, "mm)"); SERIAL_EOL(); } diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp index 6c229b7aca..97e516e70a 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp +++ b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp @@ -121,7 +121,7 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { lastEncoderBits = newbutton; } - if (abs(temp_diff) >= ENCODER_PULSES_PER_STEP) { + if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; else temp_diffState = ENCODER_DIFF_CCW; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 0ee3828387..0c022d3e88 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -624,25 +624,25 @@ void DGUSScreenHandler::ManualAssistLeveling(DGUS_VP_Variable &var, void *val_pt switch (point_value) { case 0x0001: - enqueue_corner_move(X_MIN_POS + abs(mks_corner_offsets[0].x), - Y_MIN_POS + abs(mks_corner_offsets[0].y), level_speed); + enqueue_corner_move(X_MIN_POS + ABS(mks_corner_offsets[0].x), + Y_MIN_POS + ABS(mks_corner_offsets[0].y), level_speed); queue.enqueue_now_P(PSTR("G28Z")); break; case 0x0002: - enqueue_corner_move(X_MAX_POS - abs(mks_corner_offsets[1].x), - Y_MIN_POS + abs(mks_corner_offsets[1].y), level_speed); + enqueue_corner_move(X_MAX_POS - ABS(mks_corner_offsets[1].x), + Y_MIN_POS + ABS(mks_corner_offsets[1].y), level_speed); break; case 0x0003: - enqueue_corner_move(X_MAX_POS - abs(mks_corner_offsets[2].x), - Y_MAX_POS - abs(mks_corner_offsets[2].y), level_speed); + enqueue_corner_move(X_MAX_POS - ABS(mks_corner_offsets[2].x), + Y_MAX_POS - ABS(mks_corner_offsets[2].y), level_speed); break; case 0x0004: - enqueue_corner_move(X_MIN_POS + abs(mks_corner_offsets[3].x), - Y_MAX_POS - abs(mks_corner_offsets[3].y), level_speed); + enqueue_corner_move(X_MIN_POS + ABS(mks_corner_offsets[3].x), + Y_MAX_POS - ABS(mks_corner_offsets[3].y), level_speed); break; case 0x0005: - enqueue_corner_move(abs(mks_corner_offsets[4].x), - abs(mks_corner_offsets[4].y), level_speed); + enqueue_corner_move(ABS(mks_corner_offsets[4].x), + ABS(mks_corner_offsets[4].y), level_speed); break; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index ae396c4ec5..a3c3b503d8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -121,7 +121,7 @@ float BaseMoveAxisScreen::getManualFeedrate(uint8_t axis, float increment_mm) { // being held down, this allows enough margin for the planner to // connect segments and even out the motion. constexpr xyze_feedrate_t max_manual_feedrate = MANUAL_FEEDRATE; - return min(max_manual_feedrate[axis] / 60.0f, abs(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); + return min(max_manual_feedrate[axis] / 60.0f, ABS(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); } void BaseMoveAxisScreen::setManualFeedrate(ExtUI::axis_t axis, float increment_mm) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp index 312353f47e..3165190579 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -93,9 +93,9 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { has_adjust_z = 1; break; case ID_BABY_STEP_DIST: - if (abs((int)(100 * babystep_dist)) == 1) + if (ABS((int)(100 * babystep_dist)) == 1) babystep_dist = 0.05; - else if (abs((int)(100 * babystep_dist)) == 5) + else if (ABS((int)(100 * babystep_dist)) == 5) babystep_dist = 0.1; else babystep_dist = 0.01; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index a1bfb7fc86..638d0c5ec3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -519,7 +519,7 @@ void filament_dialog_handle() { if (uiCfg.filament_load_heat_flg) { const celsius_t diff = thermalManager.wholeDegHotend(uiCfg.extruderIndex) - gCfgItems.filament_limit_temp; - if (abs(diff) < 2 || diff > 0) { + if (ABS(diff) < 2 || diff > 0) { uiCfg.filament_load_heat_flg = false; lv_clear_dialog(); lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); @@ -535,7 +535,7 @@ void filament_dialog_handle() { if (uiCfg.filament_unload_heat_flg) { const celsius_t diff = thermalManager.wholeDegHotend(uiCfg.extruderIndex) - gCfgItems.filament_limit_temp; - if (abs(diff) < 2 || diff > 0) { + if (ABS(diff) < 2 || diff > 0) { uiCfg.filament_unload_heat_flg = false; lv_clear_dialog(); lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index d070d249f3..2f9009bcdb 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -89,7 +89,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { disp_extru_amount(); break; case ID_E_STEP: - switch (abs(uiCfg.extruStep)) { + switch (ABS(uiCfg.extruStep)) { case 1: uiCfg.extruStep = 5; break; case 5: uiCfg.extruStep = 10; break; case 10: uiCfg.extruStep = 1; break; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp index a3da638be6..311894825d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -50,7 +50,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_FILAMNT_IN: uiCfg.filament_load_heat_flg = true; - if (abs(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 + if (ABS(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 || gCfgItems.filament_limit_temp <= thermalManager.wholeDegHotend(uiCfg.extruderIndex)) { lv_clear_filament_change(); lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); @@ -67,7 +67,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_FILAMNT_OUT: uiCfg.filament_unload_heat_flg = true; if (thermalManager.degTargetHotend(uiCfg.extruderIndex) - && (abs(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 + && (ABS(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 || thermalManager.wholeDegHotend(uiCfg.extruderIndex) >= gCfgItems.filament_limit_temp) ) { lv_clear_filament_change(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp index 19abb855f5..7a37dc6a15 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp @@ -75,7 +75,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_M_STEP: - if (abs(10 * (int)uiCfg.move_dist) == 100) + if (ABS(10 * (int)uiCfg.move_dist) == 100) uiCfg.move_dist = 0.1; else uiCfg.move_dist *= 10.0f; diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 767c818851..e0c694673e 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -87,7 +87,7 @@ constexpr int lco[] = LEVEL_CORNERS_LEVELING_ORDER; constexpr bool level_corners_3_points = COUNT(lco) == 2; static_assert(level_corners_3_points || COUNT(lco) == 4, "LEVEL_CORNERS_LEVELING_ORDER must have exactly 2 or 4 corners."); -constexpr int lcodiff = abs(lco[0] - lco[1]); +constexpr int lcodiff = ABS(lco[0] - lco[1]); static_assert(COUNT(lco) == 4 || lcodiff == 1 || lcodiff == 3, "The first two LEVEL_CORNERS_LEVELING_ORDER corners must be on the same edge."); constexpr int nr_edge_points = level_corners_3_points ? 3 : 4; From 5ecef6e584d71c2a5cbe983a2c7424c0fcffdf93 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jul 2021 23:41:48 -0500 Subject: [PATCH 0479/2168] =?UTF-8?q?=F0=9F=90=9B=20One-based=20G35=20poin?= =?UTF-8?q?t=20index=20output?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/G35.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 12b6f4793b..3d75a76915 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -106,7 +106,7 @@ void GcodeSuite::G35() { const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { - SERIAL_ECHOPAIR("G35 failed at point ", i, " ("); + SERIAL_ECHOPAIR("G35 failed at point ", i + 1, " ("); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); SERIAL_CHAR(')'); SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y); @@ -115,7 +115,7 @@ void GcodeSuite::G35() { } if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("Probing point ", i, " ("); + DEBUG_ECHOPAIR("Probing point ", i + 1, " ("); DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); DEBUG_CHAR(')'); DEBUG_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height); From 39e5c865444000fa22f12b9ff1593dc48afb21e1 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Fri, 30 Jul 2021 17:57:50 -0600 Subject: [PATCH 0480/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FTDI=20Eve=20uni?= =?UTF-8?q?code=20and=20spinner=20dialog=20(#22468)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 4 ++-- .../extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index bb622c3cc5..2da5d55ff0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -68,7 +68,7 @@ utf8_char_t FTDI::get_utf8_char_and_inc(const char *&c) { utf8_char_t val = *(uint8_t*)c++; - if ((val & 0xC0) == 0x80) + if ((val & 0xC0) == 0xC0) while ((*c & 0xC0) == 0x80) val = (val << 8) | *(uint8_t*)c++; return val; @@ -76,7 +76,7 @@ utf8_char_t FTDI::get_utf8_char_and_inc(char *&c) { utf8_char_t val = *(uint8_t*)c++; - if ((val & 0xC0) == 0x80) + if ((val & 0xC0) == 0xC0) while ((*c & 0xC0) == 0x80) val = (val << 8) | *(uint8_t*)c++; return val; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index fecf407285..47bb0eebdb 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -49,6 +49,7 @@ void SpinnerDialogBox::show(progmem_str message) { void SpinnerDialogBox::hide() { CommandProcessor cmd; cmd.stop().execute(); + GOTO_PREVIOUS(); } void SpinnerDialogBox::enqueueAndWait(progmem_str message, progmem_str commands) { @@ -66,7 +67,6 @@ void SpinnerDialogBox::onIdle() { if (mydata.auto_hide && !commandsInQueue()) { mydata.auto_hide = false; hide(); - GOTO_PREVIOUS(); } } From 1fed25c44020224c9499eac73422657b53783e74 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 30 Jul 2021 19:39:38 -0500 Subject: [PATCH 0481/2168] =?UTF-8?q?=F0=9F=94=A8=20Fix:=20BIGTREE=5FE3=5F?= =?UTF-8?q?RRF=20doesn't=20use=20user=20RX/TX=20sizes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22466. Regression from #22377. --- ini/stm32f4.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 04fd03bf72..2b77bf2e3c 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -152,6 +152,7 @@ extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_BIGTREE_E3_RRF board_build.offset = 0x8000 +extra_scripts = ${common.extra_scripts} build_flags = ${stm32_variant.build_flags} -DSTM32F407_5VX -DSERIAL_RX_BUFFER_SIZE=255 From 9e68aea8a14339d71aac5ab2274905af29e44464 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sat, 31 Jul 2021 12:50:22 +1200 Subject: [PATCH 0482/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20DGUS=20displays?= =?UTF-8?q?=20compile=20(#22464)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/dgus/DGUSDisplay.h | 6 +- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 49 ++++++++------- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 13 +++- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 60 +++++++++---------- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 6 +- .../lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 20 +++---- .../lcd/extui/dgus/origin/DGUSDisplayDef.h | 22 +++---- .../extui/dgus/origin/DGUSScreenHandler.cpp | 7 ++- 8 files changed, 100 insertions(+), 83 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h index f1071f6b0a..ed8178449d 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -108,14 +108,14 @@ private: static bool Initialized, no_reentrance; }; -#define GET_VARIABLE(f, t, V...) (&DGUSDisplay::GetVariable) -#define SET_VARIABLE(f, t, V...) (&DGUSDisplay::SetVariable) - extern DGUSDisplay dgusdisplay; // compile-time x^y constexpr float cpow(const float x, const int y) { return y == 0 ? 1.0 : x * cpow(x, y - 1); } +/// +const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen); + /// Find the flash address of a DGUS_VP_Variable for the VP. const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp); diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 79f39f93d8..39cb6e2bef 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -41,7 +41,10 @@ uint16_t distanceToMove = 10; #endif -const uint16_t VPList_Boot[] PROGMEM = { VP_MARLIN_VERSION, 0x0000 }; +const uint16_t VPList_Boot[] PROGMEM = { + VP_MARLIN_VERSION, + 0x0000 +}; const uint16_t VPList_Main[] PROGMEM = { // VP_M117, for completeness, but it cannot be auto-uploaded. @@ -101,7 +104,7 @@ const uint16_t VPList_Status[] PROGMEM = { }; const uint16_t VPList_Status2[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ + // VP_M117, for completeness, but it cannot be auto-uploaded #if HAS_HOTEND VP_Flowrate_E0, #if HAS_MULTI_EXTRUDER @@ -286,28 +289,28 @@ const uint16_t VPList_Z_Offset[] PROGMEM = { }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { 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 }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { 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 }, + { DGUSLCD_SCREEN_INFOS, VPList_Infos }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 78828e14c5..0012a0e5e0 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -42,6 +42,8 @@ #if ENABLED(SDSUPPORT) + static ExtUI::FileList filelist; + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; @@ -83,7 +85,7 @@ case 1: // Pause - GotoScreen(MKSLCD_SCREEN_PAUSE); + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); if (!ExtUI::isPrintingFromMediaPaused()) { ExtUI::pausePrint(); //ExtUI::mks_pausePrint(); @@ -409,8 +411,15 @@ bool DGUSScreenHandler::loop() { if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) booted = true; - if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) + if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; + + if (TERN0(POWER_LOSS_RECOVERY, recovery.valid())) + GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); + else + GotoScreen(DGUSLCD_SCREEN_MAIN); + } + #endif return IsScreenComplete(); } diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index 3d0e073e5c..f1f4308d22 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -47,7 +47,7 @@ const uint16_t VPList_Boot[] PROGMEM = { }; const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ + // VP_M117, for completeness, but it cannot be auto-uploaded. #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, #if HOTENDS >= 2 @@ -83,7 +83,7 @@ const uint16_t VPList_Temp[] PROGMEM = { }; const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ + // VP_M117, for completeness, but it cannot be auto-uploaded #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #if HOTENDS >= 2 @@ -104,7 +104,7 @@ const uint16_t VPList_Status[] PROGMEM = { }; const uint16_t VPList_Status2[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ + // VP_M117, for completeness, but it cannot be auto-uploaded #if HAS_HOTEND VP_Flowrate_E0, #if HOTENDS >= 2 @@ -292,28 +292,28 @@ const uint16_t VPList_Z_Offset[] PROGMEM = { }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, - { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, - { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, - { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, - { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, - { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, + { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, + { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, + { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, + { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, + { DGUSLCD_SCREEN_INFOS, VPList_Infos }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; @@ -395,7 +395,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), - #if ENABLED(PIDTEMP) + #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), @@ -445,11 +445,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index eab5e27507..2100febc32 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -22,7 +22,7 @@ #include "../../../../inc/MarlinConfigPre.h" -#if ENABLED(DGUS_LCD_UI_HYPRECY) +#if ENABLED(DGUS_LCD_UI_HIPRECY) #include "../DGUSScreenHandler.h" @@ -42,6 +42,8 @@ #if ENABLED(SDSUPPORT) + static ExtUI::FileList filelist; + void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; @@ -415,4 +417,4 @@ bool DGUSScreenHandler::loop() { return IsScreenComplete(); } -#endif // DGUS_LCD_UI_HYPRECY +#endif // DGUS_LCD_UI_HIPRECY diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index af57f3dccc..39d89fc174 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -50,7 +50,7 @@ const uint16_t VPList_Boot[] PROGMEM = { }; const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ + // VP_M117, for completeness, but it cannot be auto-uploaded. 0x0000 }; @@ -68,7 +68,7 @@ const uint16_t VPList_Temp[] PROGMEM = { }; const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ + // VP_M117, for completeness, but it cannot be auto-uploaded #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #if HOTENDS >= 2 @@ -162,8 +162,8 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, nullptr, nullptr, SET_VARIABLE(getActualTemp_celsius, E0, long)), - VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), SET_VARIABLE(getTargetTemp_celsius, E0)), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), @@ -194,7 +194,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), @@ -247,11 +247,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename ), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h index 7885621d0b..06f0dcf001 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -24,17 +24,17 @@ #include "../DGUSDisplayDef.h" enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 10, - DGUSLCD_SCREEN_TEMPERATURE = 20, - DGUSLCD_SCREEN_STATUS = 30, - DGUSLCD_SCREEN_STATUS2 = 32, - DGUSLCD_SCREEN_MANUALMOVE = 40, - DGUSLCD_SCREEN_MANUALEXTRUDE = 42, - DGUSLCD_SCREEN_FANANDFEEDRATE = 44, - DGUSLCD_SCREEN_FLOWRATES = 46, - DGUSLCD_SCREEN_SDFILELIST = 50, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, + DGUSLCD_SCREEN_BOOT = 0, + DGUSLCD_SCREEN_MAIN = 10, + DGUSLCD_SCREEN_TEMPERATURE = 20, + DGUSLCD_SCREEN_STATUS = 30, + DGUSLCD_SCREEN_STATUS2 = 32, + DGUSLCD_SCREEN_MANUALMOVE = 40, + DGUSLCD_SCREEN_MANUALEXTRUDE = 42, + DGUSLCD_SCREEN_FANANDFEEDRATE = 44, + DGUSLCD_SCREEN_FLOWRATES = 46, + DGUSLCD_SCREEN_SDFILELIST = 50, + DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, DGUSLCD_SCREEN_POWER_LOSS = 100, DGUSLCD_SCREEN_PREHEAT = 120, DGUSLCD_SCREEN_UTILITY = 110, diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index 70efb355fc..827d74967a 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -85,7 +85,7 @@ case 1: // Pause - GotoScreen(MKSLCD_SCREEN_PAUSE); + GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); if (!ExtUI::isPrintingFromMediaPaused()) { ExtUI::pausePrint(); //ExtUI::mks_pausePrint(); @@ -411,9 +411,12 @@ bool DGUSScreenHandler::loop() { if (!booted && TERN0(POWER_LOSS_RECOVERY, recovery.valid())) booted = true; - if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) + if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; + GotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUSLCD_SCREEN_POWER_LOSS : DGUSLCD_SCREEN_MAIN); + } #endif + return IsScreenComplete(); } From d9ab20ec27599d99f0a7fa901086687a6d9139d5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 31 Jul 2021 01:01:28 +0000 Subject: [PATCH 0483/2168] [cron] Bump distribution date (2021-07-31) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 7ef779ac84..25cd5410ad 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-30" +//#define STRING_DISTRIBUTION_DATE "2021-07-31" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 264777d3a8..d2999cde5e 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 "2021-07-30" + #define STRING_DISTRIBUTION_DATE "2021-07-31" #endif /** From b6f720ca1ae1fb3a9998db168cbb4e87e14df9e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 30 Jul 2021 22:43:58 -0500 Subject: [PATCH 0484/2168] =?UTF-8?q?=E2=9C=85=20Custom=20logging=20for=20?= =?UTF-8?q?MBL?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 14 +++++--------- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 13 +++++++++++++ 2 files changed, 18 insertions(+), 9 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 0c0fb07760..a88e089479 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -217,6 +217,8 @@ public: * There's no extra effect if you have a fixed Z probe. */ G29_TYPE GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); + TERN_(PROBE_MANUALLY, static) G29_State abl; TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); @@ -227,11 +229,7 @@ G29_TYPE GcodeSuite::G29() { // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) - const uint8_t old_debug_flags = marlin_debug_flags; - if (seenQ) marlin_debug_flags |= MARLIN_DEBUG_LEVELING; - DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) log_machine_info(); - marlin_debug_flags = old_debug_flags; + if (seenQ || DEBUGGING(LEVELING)) log_machine_info(); if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false); #endif @@ -472,10 +470,8 @@ G29_TYPE GcodeSuite::G29() { // Query G29 status if (abl.verbose_level || seenQ) { SERIAL_ECHOPGM("Manual G29 "); - if (g29_in_progress) { - SERIAL_ECHOPAIR("point ", _MIN(abl.abl_probe_index + 1, abl.abl_points)); - SERIAL_ECHOLNPAIR(" of ", abl.abl_points); - } + if (g29_in_progress) + SERIAL_ECHOLNPAIR("point ", _MIN(abl.abl_probe_index + 1, abl.abl_points), " of ", abl.abl_points); else SERIAL_ECHOLNPGM("idle"); } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 03f2c58e81..984e008d27 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -42,6 +42,9 @@ #include "../../../lcd/extui/ui_api.h" #endif +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../../core/debug_out.h" + // Save 130 bytes with non-duplication of PSTR inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" not entered."); } @@ -59,6 +62,16 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" * S5 Reset and disable mesh */ void GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", true); + + // G29 Q is also available if debugging + #if ENABLED(DEBUG_LEVELING_FEATURE) + const bool seenQ = parser.seen_test('Q'); + if (seenQ || DEBUGGING(LEVELING)) { + log_machine_info(); + if (seenQ) return; + } + #endif TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); From 35b0083dfee0f5508d1ecfd4756ebcac8892b067 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 30 Jul 2021 23:05:53 -0500 Subject: [PATCH 0485/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20custom=20menus?= =?UTF-8?q?=20on=20TFT=20LVGL?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #21423. Regression from #18177. --- Marlin/src/inc/Conditionals_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 55ae6ec535..c259750c6f 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -969,7 +969,7 @@ #endif #if BOTH(HAS_TFT_LVGL_UI, CUSTOM_MENU_MAIN) - #define _HAS_1(N) (defined(USER_DESC_##N) && defined(USER_GCODE_##N)) + #define _HAS_1(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) #define HAS_USER_ITEM(V...) DO(HAS,||,V) #else #define HAS_USER_ITEM(N) 0 From 002c500b7185284b0644b3ccbd60d95f7c4bb713 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sat, 31 Jul 2021 06:49:12 +0200 Subject: [PATCH 0486/2168] =?UTF-8?q?=F0=9F=94=A8=20Update=20Longer=20and?= =?UTF-8?q?=20Chitu=20envs=20(#22467)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 175d0e45b0..029763b9ed 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -333,6 +333,7 @@ platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx +board_build.rename = project.bin board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 build_flags = ${stm32_variant.build_flags} @@ -342,7 +343,6 @@ build_flags = ${stm32_variant.build_flags} build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED extra_scripts = ${stm32_variant.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py # # TRIGORILLA PRO (STM32F103ZET6) @@ -363,8 +363,6 @@ board_build.variant = MARLIN_F103Zx build_flags = ${stm32_variant.build_flags} -DSTM32F1xx -DSTM32_XL_DENSITY build_unflags = ${stm32_variant.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= - -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = ${stm32_variant.extra_scripts} buildroot/share/PlatformIO/scripts/chitu_crypt.py From 332dde935d58906e31a2e5f6d03e280f7c9c0919 Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Sat, 31 Jul 2021 00:47:30 -0500 Subject: [PATCH 0487/2168] =?UTF-8?q?=E2=9C=A8=20MKS=20Monster8=20board=20?= =?UTF-8?q?(#22455)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 8 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 +- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 372 ++++++++++++++++++ ini/stm32f4.ini | 50 ++- 5 files changed, 428 insertions(+), 8 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index b5b33692a0..ba3c9f978c 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -385,10 +385,10 @@ #define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) #define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) #define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_ANET_ET4 4227 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4228 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4229 // FYSETC Cheetah V2.0 - +#define BOARD_MKS_MONSTER8 4227 // MKS Monster8 (STM32F407VGT6) +#define BOARD_ANET_ET4 4228 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4229 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4230 // FYSETC Cheetah V2.0 // // ARM Cortex M7 diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index f37028f15a..d648b25efb 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -204,8 +204,8 @@ #if ENABLED(DWIN_CREALITY_LCD) #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." - /** - * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo + /** + * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo * ______ ______ RX 8 --> 5 P0_15 * 5V | 1 2 | GND 5V | 1 2 | GND TX 7 --> 9 P0_16 * (BTN_E1) A | 3 4 | B (BTN_E2) (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) BEEPER 5 --> 10 P2_08 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a4ef4f080c..b3e1605613 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -631,6 +631,8 @@ #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_OpenBLT #elif MB(FYSETC_CHEETAH_V20) #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 +#elif MB(MKS_MONSTER8) + #include "stm32f4/pins_MKS_MONSTER8.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc // // ARM Cortex M7 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h new file mode 100644 index 0000000000..939edc6052 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -0,0 +1,372 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 5 + #error "MKS Monster supports up to 3 hotends and 5 E-steppers." +#elif HAS_FSMC_TFT + #error "MKS Monster doesn't support FSMC-based TFT displays." +#endif + +#define BOARD_INFO_NAME "MKS Monster8 V1.x" + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +//#define DISABLE_DEBUG + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// Use one of these or SDCard-based Emulation will be used +//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation +//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#define I2C_EEPROM // Need use jumpers set i2c for EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#define I2C_SCL_PIN PB8 // I2C_SCL and CAN_RX +#define I2C_SDA_PIN PB9 // I2C_SDA and CAN_TX + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches for diag signal +// +#define X_DIAG_PIN PA14 // Driver0 diag signal is connect to X- +#define Y_DIAG_PIN PA15 // Driver1 diag signal is connect to Y- +#define Z_DIAG_PIN PB13 // Driver2 diag signal is connect to Z- +#define E0_DIAG_PIN PA13 // Driver3 diag signal is connect to X+ +#define E1_DIAG_PIN PC5 // Driver4 diag signal is connect to Y+ +#define E2_DIAG_PIN PB12 // Driver5 diag signal is connect to Z+ +#define E3_DIAG_PIN -1 // Driver6 diag signal is not connect +#define E4_DIAG_PIN -1 // Driver7 diag signal is not connect + +// Limit Switches for endstop +#define X_MIN_PIN PA14 +#define X_MAX_PIN PA13 +#define Y_MIN_PIN PA15 +#define Y_MAX_PIN PC5 +#define Z_MIN_PIN PB13 +#define Z_MAX_PIN PB12 + +// +// Steppers +// Driver 0 1 2 3 4 5 6 7 +// For X Y Z E0 E1 E2 E3 E4(default pin settings) +// +//Driver0 +#define X_ENABLE_PIN PC15 +#define X_STEP_PIN PC14 +#define X_DIR_PIN PC13 +#ifndef X_CS_PIN + #define X_CS_PIN PE6 +#endif +//Driver1 +#define Y_ENABLE_PIN PC15 +#define Y_STEP_PIN PE5 +#define Y_DIR_PIN PE4 +#ifndef Y_CS_PIN + #define Y_CS_PIN PE3 +#endif +//Driver2 +#define Z_ENABLE_PIN PE2 +#define Z_STEP_PIN PE1 +#define Z_DIR_PIN PE0 +#ifndef Z_CS_PIN + #define Z_CS_PIN PB7 +#endif +//Driver3 +#define E0_ENABLE_PIN PB6 +#define E0_STEP_PIN PB5 +#define E0_DIR_PIN PB4 +#ifndef E0_CS_PIN + #define E0_CS_PIN PB3 +#endif +//Driver4 +#define E1_ENABLE_PIN PD7 +#define E1_STEP_PIN PD6 +#define E1_DIR_PIN PD5 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD4 +#endif +//Driver5 +#define E2_ENABLE_PIN PD3 +#define E2_STEP_PIN PD2 +#define E2_DIR_PIN PD1 +#ifndef E2_CS_PIN + #define E2_CS_PIN PD0 +#endif +//Driver6 +#define E3_ENABLE_PIN PC8 +#define E3_STEP_PIN PC7 +#define E3_DIR_PIN PC6 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD15 +#endif +//Driver7 +#define E4_ENABLE_PIN PD14 +#define E4_STEP_PIN PD13 +#define E4_DIR_PIN PD12 +#ifndef E4_CS_PIN + #define E4_CS_PIN PD11 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// This board only supports SW SPI for stepper drivers +// +#if HAS_TMC_SPI + #define TMC_USE_SW_SPI +#endif +#if ENABLED(TMC_USE_SW_SPI) + #if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1 + #define TMC_SW_MOSI PE14 + #endif + #if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1 + #define TMC_SW_MISO PE13 + #endif + #if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1 + #define TMC_SW_SCK PE12 + #endif +#endif + +#if HAS_TMC_UART + // + // Software serial + // No Hardware serial for steppers + // + #define X_SERIAL_TX_PIN PE6 + #define X_SERIAL_RX_PIN PE6 + + #define Y_SERIAL_TX_PIN PE3 + #define Y_SERIAL_RX_PIN PE3 + + #define Z_SERIAL_TX_PIN PB7 + #define Z_SERIAL_RX_PIN PB7 + + #define E0_SERIAL_TX_PIN PB3 + #define E0_SERIAL_RX_PIN PB3 + + #define E1_SERIAL_TX_PIN PD4 + #define E1_SERIAL_RX_PIN PD4 + + #define E2_SERIAL_TX_PIN PD0 + #define E2_SERIAL_RX_PIN PD0 + + #define E3_SERIAL_TX_PIN PD15 + #define E3_SERIAL_RX_PIN PD15 + + #define E4_SERIAL_TX_PIN PD11 + #define E4_SERIAL_RX_PIN PD11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH0 +#define TEMP_1_PIN PC2 // TH1 +#define TEMP_2_PIN PC3 // TH2 +#define TEMP_BED_PIN PC0 // TB + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB1 // HE0 +#define HEATER_1_PIN PB0 // HE1 +#define HEATER_2_PIN PA3 // HE2 +#define HEATER_BED_PIN PB10 // H-BED + +#define FAN_PIN PA2 // FAN0 +#define FAN1_PIN PA1 // FAN1 +#define FAN2_PIN PA0 // FAN2 + +// +// Misc. Functions +// +#define MT_DET_1 Y_MAX_PIN +#define MT_DET_2 Z_MAX_PIN +#define PW_DET Y_MAX_PIN +#define PW_OFF Z_MAX_PIN + +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN MT_DET_1 +#endif +#ifndef FIL_RUNOUT2_PIN + #define FIL_RUNOUT2_PIN MT_DET_2 +#endif + +#define POWER_LOSS_PIN PW_DET +#define PS_ON_PIN PW_OFF + +// Random Info +#define USB_SERIAL -1 // USB Serial + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +// +// Onboard SD card +// +// detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled +#if SD_CONNECTION_IS(ONBOARD) + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PC4 +// +// LCD SD +// +#elif SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS PA4 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PB11 +#endif + +/** + * _____ _____ + * (BEEPER)PB2 | · · | PE10(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) + * (LCD_EN)PE11 | · · | PD10(LCD_RS) (BTN_EN1) PE9 | · · | PA4 (SPI1 CS) + * (LCD_D4)PD9 | · · PD8(LCD_D5) (BTN_EN2) PE8 | · · PA7 (SPI1 MOSI) + * (LCD_D6)PE15 | · · | PE7(LCD_D7) (SPI1_RS) PB11 | · · | RESET + * GND | · · | 5V GND | · · | 3.3V + *  ̄ ̄ ̄  ̄ ̄ ̄ + * EXP1 EXP2 + */ + +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -17253 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11579 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 514 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -24 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif + + #define TFT_CS_PIN PE15 + #define TFT_SCK_PIN PA5 + #define TFT_MISO_PIN PA6 + #define TFT_MOSI_PIN PA7 + #define TFT_DC_PIN PE7 + #define TFT_RST_PIN PD10 + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN PD10 + #define TFT_BACKLIGHT_PIN PE11 + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN PE11 + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define TOUCH_CS_PIN PD9 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + + #define BTN_EN1 PE9 + #define BTN_EN2 PE8 + #define BEEPER_PIN PB2 + #define BTN_ENC PE10 + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_SIZE 14400 + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN PB2 + #define BTN_ENC PE10 + #define LCD_PINS_ENABLE PE11 + #define LCD_PINS_RS PD10 + #define BTN_EN1 PE9 + #define BTN_EN2 PE8 + #define LCD_BACKLIGHT_PIN -1 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 + #define DOGLCD_A0 PD11 + #define DOGLCD_CS PE15 + //#define DOGLCD_SCK PA5 + //#define DOGLCD_MOSI PA7 + + #elif ENABLED(MKS_MINI_12864_V3) + #define DOGLCD_CS PE11 + #define DOGLCD_A0 PD10 + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN PD9 + #define NEOPIXEL_PIN PD8 + #define DOGLCD_MOSI PA7 + #define DOGLCD_SCK PA5 + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + //#define LCD_SCREEN_ROT_180 + + #else + + #define LCD_PINS_D4 PD9 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PD8 + #define LCD_PINS_D6 PE15 + #define LCD_PINS_D7 PE7 + #endif + + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 2b77bf2e3c..2d3b5a0f32 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -347,7 +347,7 @@ debug_tool = jlink upload_protocol = jlink # -# This SPI is used by Robin Nano V3 +# This I2C1(PB6:I2C1_SCL PB7:I2C1_SDA) is used by Robin Nano V3 # [stm32f4_I2C1] build_flags = -DPIN_WIRE_SCL=PB6 -DPIN_WIRE_SDA=PB7 @@ -361,8 +361,8 @@ extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx board_build.offset = 0xC000 -board_build.rename = Robin_nano_v3.bin board_upload.offset_address = 0x0800C000 +board_build.rename = Robin_nano_v3.bin build_flags = ${stm32_variant.build_flags} ${stm32f4_I2C1.build_flags} -DHAL_PCD_MODULE_ENABLED debug_tool = jlink @@ -391,3 +391,49 @@ platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3_usb_flash_drive build_flags = ${env:mks_robin_nano_v3_usb_flash_drive} -DUSBD_USE_CDC_MSC + +# +# This I2C1(PB8:I2C1_SCL PB9:I2C1_SDA) is used by MKS Monster8 +# +[stm32f4_I2C1_CAN] +build_flags = -DPIN_WIRE_SCL=PB8 -DPIN_WIRE_SDA=PB9 + +# +# MKS Monster8 +# +[env:mks_monster8] +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_STM32F407VGT6_CCM +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0xC000 +board_upload.offset_address = 0x0800C000 +board_build.rename = mks_monster8.bin +build_flags = ${stm32_variant.build_flags} ${stm32f4_I2C1_CAN.build_flags} + -DHAL_PCD_MODULE_ENABLED +debug_tool = jlink +upload_protocol = jlink + +# +# MKS Monster8 with USB Flash Drive Support +# Currently, using a STM32duino fork, until USB Host get merged +# +[env:mks_monster8_usb_flash_drive] +platform = ${common_stm32.platform} +extends = env:mks_monster8 +platform_packages = ${stm_flash_drive.platform_packages} +build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flags} + -DUSE_USBHOST_HS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSE_USB_HS_IN_FS + +# +# MKS Monster8 with USB Flash Drive Support and Shared Media +# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged +# +[env:mks_monster8_usb_flash_drive_msc] +platform = ${common_stm32.platform} +extends = env:mks_monster8_usb_flash_drive +build_flags = ${env:mks_monster8_usb_flash_drive} + -DUSBD_USE_CDC_MSC From 9bb5b10c0c9cf5a61d2bfb9dfdb6cfe210b6002b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 Jul 2021 05:32:13 -0500 Subject: [PATCH 0488/2168] =?UTF-8?q?=F0=9F=9A=9A=20Relocate=20and=20adjus?= =?UTF-8?q?t=20DWIN=20E3V2=20(#22471)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 13 +- Marlin/src/MarlinCore.cpp | 10 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 8 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 7 +- .../{dwin/e3v2 => e3v2/creality}/README.md | 0 .../lcd/{dwin/e3v2 => e3v2/creality}/dwin.cpp | 131 +++++++------- .../lcd/{dwin/e3v2 => e3v2/creality}/dwin.h | 147 +-------------- .../lcd/{dwin => e3v2/creality}/dwin_lcd.cpp | 29 ++- .../lcd/{dwin => e3v2/creality}/dwin_lcd.h | 168 +++++++++++++++++- .../e3v2 => e3v2/creality}/rotary_encoder.cpp | 2 +- .../e3v2 => e3v2/creality}/rotary_encoder.h | 2 +- .../ftdi_eve_touch_ui/generic/lock_screen.h | 4 +- Marlin/src/lcd/fontutils.cpp | 2 +- Marlin/src/lcd/lcdprint.h | 12 +- Marlin/src/lcd/marlinui.cpp | 13 +- Marlin/src/lcd/marlinui.h | 11 ++ Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 2 +- ini/features.ini | 2 +- platformio.ini | 2 +- 23 files changed, 305 insertions(+), 268 deletions(-) rename Marlin/src/lcd/{dwin/e3v2 => e3v2/creality}/README.md (100%) rename Marlin/src/lcd/{dwin/e3v2 => e3v2/creality}/dwin.cpp (96%) rename Marlin/src/lcd/{dwin/e3v2 => e3v2/creality}/dwin.h (54%) rename Marlin/src/lcd/{dwin => e3v2/creality}/dwin_lcd.cpp (93%) rename Marlin/src/lcd/{dwin => e3v2/creality}/dwin_lcd.h (55%) rename Marlin/src/lcd/{dwin/e3v2 => e3v2/creality}/rotary_encoder.cpp (99%) rename Marlin/src/lcd/{dwin/e3v2 => e3v2/creality}/rotary_encoder.h (98%) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d32b61cbfa..67c875e81f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1304,11 +1304,14 @@ //#define LCD_SHOW_E_TOTAL #endif -#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && ANY(HAS_MARLINUI_U8GLIB, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, EXTENSIBLE_UI) - //#define SHOW_REMAINING_TIME // Display estimated time to completion - #if ENABLED(SHOW_REMAINING_TIME) - //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation - //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time +// LCD Print Progress options +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) + #if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + //#define SHOW_REMAINING_TIME // Display estimated time to completion + #if ENABLED(SHOW_REMAINING_TIME) + //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation + //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time + #endif #endif #if EITHER(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 96c4d82948..6134699aa1 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -75,8 +75,8 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/dwin/e3v2/dwin.h" - #include "lcd/dwin/e3v2/rotary_encoder.h" + #include "lcd/e3v2/creality/dwin.h" + #include "lcd/e3v2/creality/rotary_encoder.h" #endif #if ENABLED(EXTENSIBLE_UI) @@ -1310,11 +1310,7 @@ void setup() { // (because EEPROM code calls the UI). #if ENABLED(DWIN_CREALITY_LCD) - delay(800); // Required delay (since boot?) - SERIAL_ECHOPGM("\nDWIN handshake "); - if (DWIN_Handshake()) SERIAL_ECHOLNPGM("ok."); else SERIAL_ECHOLNPGM("error."); - DWIN_Frame_SetDir(1); // Orientation 90° - DWIN_UpdateLCD(); // Show bootscreen (first image) + SETUP_RUN(DWIN_Startup()); #else SETUP_RUN(ui.init()); #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index a88e089479..29009c6e2d 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -61,7 +61,7 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/dwin/e3v2/dwin.h" + #include "../../../lcd/e3v2/creality/dwin.h" #endif #if HAS_MULTI_HOTEND diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 6baef030bf..89ad20d906 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -47,7 +47,7 @@ #include "../../lcd/marlinui.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/dwin/e3v2/dwin.h" + #include "../../lcd/e3v2/creality/dwin.h" #endif #if ENABLED(EXTENSIBLE_UI) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index d47bfcb81a..0ebe8e265a 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -482,10 +482,6 @@ #endif // Aliases for LCD features -#if EITHER(IS_ULTRA_LCD, EXTENSIBLE_UI) - #define HAS_DISPLAY 1 -#endif - #if IS_ULTRA_LCD #define HAS_WIRED_LCD 1 #if ENABLED(DOGLCD) @@ -497,6 +493,10 @@ #endif #endif +#if EITHER(HAS_WIRED_LCD, EXTENSIBLE_UI) + #define HAS_DISPLAY 1 +#endif + #if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD, GLOBAL_STATUS_MESSAGE) #define HAS_STATUS_MESSAGE 1 #endif diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 3324819955..5991fc3b8b 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -791,9 +791,10 @@ void MarlinUI::draw_status_screen() { // lcd.setCursor(0, 0); - _draw_axis_value(X_AXIS, ftostr4sign(LOGICAL_X_POSITION(current_position.x)), blink); lcd.write(' '); - _draw_axis_value(Y_AXIS, ftostr4sign(LOGICAL_Y_POSITION(current_position.y)), blink); lcd.write(' '); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); + const xyz_pos_t lpos = current_position.asLogical(); + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); lcd.write(' '); + _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); lcd.write(' '); + _draw_axis_value(Z_AXIS, ftostr52sp(lpos.z), blink); #if HAS_LEVELING && !HAS_HEATED_BED lcd.write(planner.leveling_active || blink ? '_' : ' '); diff --git a/Marlin/src/lcd/dwin/e3v2/README.md b/Marlin/src/lcd/e3v2/creality/README.md similarity index 100% rename from Marlin/src/lcd/dwin/e3v2/README.md rename to Marlin/src/lcd/e3v2/creality/README.md diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp similarity index 96% rename from Marlin/src/lcd/dwin/e3v2/dwin.cpp rename to Marlin/src/lcd/e3v2/creality/dwin.cpp index 38017b64d6..05da343f9e 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -42,10 +42,6 @@ #define JUST_BABYSTEP 1 #endif -#include -#include -#include - #include "../../fontutils.h" #include "../../marlinui.h" @@ -85,6 +81,10 @@ #include "../../../feature/powerloss.h" #endif +#include +#include +#include + #ifndef MACHINE_SIZE #define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) #endif @@ -97,10 +97,6 @@ #define USE_STRING_HEADINGS //#define USE_STRING_TITLES -#define DWIN_FONT_MENU font8x16 -#define DWIN_FONT_STAT font10x20 -#define DWIN_FONT_HEAD font10x20 - #define MENU_CHAR_LIMIT 24 #define STATUS_Y 360 @@ -135,6 +131,9 @@ constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other #define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) +#define DWIN_BOTTOM (DWIN_HEIGHT-1) +#define DWIN_RIGHT (DWIN_WIDTH-1) + /* Value Init */ HMI_value_t HMI_ValueStruct; HMI_Flag_t HMI_flag{0}; @@ -220,11 +219,11 @@ void HMI_ToggleLanguage() { void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { if (value < 0) { - DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F("-")); + DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F("-")); DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); } else { - DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F(" ")); + DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F(" ")); DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); } } @@ -391,20 +390,20 @@ void ICON_Stop() { } } -void Clear_Title_Bar() { - DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, 30); +inline void Clear_Title_Bar() { + DWIN_Draw_Box(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, TITLE_HEIGHT); } void Draw_Title(const char * const title) { - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); + DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } void Draw_Title(const __FlashStringHelper * title) { - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); + DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } -void Clear_Menu_Area() { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y - 1); +inline void Clear_Menu_Area() { + DWIN_Draw_Box(1, Color_Bg_Black, 0, TITLE_HEIGHT, DWIN_WIDTH, STATUS_Y - TITLE_HEIGHT); } void Clear_Main_Window() { @@ -465,7 +464,7 @@ void Erase_Menu_Text(const uint8_t line) { } void Draw_Menu_Item(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { - if (label) DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); + if (label) DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); if (icon) Draw_Menu_Icon(line, icon); if (more) Draw_More_Icon(line); } @@ -494,7 +493,8 @@ void Draw_Back_First(const bool is_sel=true) { if (is_sel) Draw_Menu_Cursor(0); } -inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, auto &valref) { +template +inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) { if (encoder_diffState == ENCODER_DIFF_CW) valref += EncoderRate.encoderMoveValue; else if (encoder_diffState == ENCODER_DIFF_CCW) @@ -563,7 +563,7 @@ inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, auto &valr // void DWIN_Draw_Label(const uint16_t y, char *string) { - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, y, string); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, LBLX, y, string); } void DWIN_Draw_Label(const uint16_t y, const __FlashStringHelper *title) { DWIN_Draw_Label(y, (char*)title); @@ -577,7 +577,9 @@ void draw_move_en(const uint16_t line) { #endif } -void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); } +inline void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); +} void Item_Prepare_Move(const uint8_t row) { if (HMI_IsChinese()) @@ -703,7 +705,7 @@ void Item_Prepare_Lang(const uint8_t row) { DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" #endif } - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), HMI_IsChinese() ? F("CN") : F("EN")); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), HMI_IsChinese() ? F("CN") : F("EN")); Draw_Menu_Icon(row, ICON_Language); } @@ -849,7 +851,7 @@ void Draw_Tune_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 73, 2, 100, 13, 14, 9); + DWIN_Frame_TitleCopy(1, 73, 2, 100, 13); DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(TUNE_CASE_SPEED)); #if HAS_HOTEND DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TUNE_CASE_TEMP)); @@ -883,6 +885,7 @@ void Draw_Tune_Menu() { #endif DWIN_Draw_Label(MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else + DWIN_Frame_TitleCopy(1, 94, 2, 126, 12); DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed #if HAS_HOTEND DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TUNE_CASE_TEMP)); // Hotend... @@ -1008,6 +1011,7 @@ void Draw_Motion_Menu() { // // Draw Popup Windows // + #if HAS_HOTEND || HAS_HEATED_BED void DWIN_Popup_Temperature(const bool toohigh) { @@ -1021,8 +1025,8 @@ void Draw_Motion_Menu() { DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too high")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too high")); } } else { @@ -1032,8 +1036,8 @@ void Draw_Motion_Menu() { DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too low")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too low")); } } } @@ -1052,11 +1056,11 @@ void Draw_Popup_Bkgd_60() { DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); if (HMI_IsChinese()) { DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); - DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); + DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 69 + 33, 240); DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); } } @@ -1073,9 +1077,9 @@ void Popup_Window_Resume() { DWIN_ICON_Show(ICON, ICON_Continue_C, 146, 307); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 14) / 2, 115, F("Continue Print")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 14) / 2, 115, F("Continue Print")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); DWIN_ICON_Show(ICON, ICON_Cancel_E, 26, 307); DWIN_ICON_Show(ICON, ICON_Continue_E, 146, 307); } @@ -1091,8 +1095,8 @@ void Popup_Window_Home(const bool parking/*=false*/) { DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); } } @@ -1107,8 +1111,8 @@ void Popup_Window_Home(const bool parking/*=false*/) { DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); } else { - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); } } @@ -1135,8 +1139,8 @@ void Popup_window_PauseOrStop() { DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); } else { - if (select_print.now == 1) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + if (select_print.now == 1) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == 2) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); } @@ -1160,19 +1164,19 @@ void Draw_Print_ProgressBar() { DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); DWIN_Draw_Rectangle(1, BarFill_Color, 16 + _card_percent * 240 / 100, 93, 256, 113); DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, _card_percent); - DWIN_Draw_String(false, false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); + DWIN_Draw_String(false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); } void Draw_Print_ProgressElapsed() { duration_t elapsed = print_job_timer.duration(); // print timer DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 66, 212, (elapsed.value % 3600) / 60); } void Draw_Print_ProgressRemain() { DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 176, 212, _remain_time / 3600); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (_remain_time % 3600) / 60); } @@ -1189,7 +1193,7 @@ void Goto_PrintProcess() { // Copy into filebuf string before entry char * const name = card.longest_filename(); const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); @@ -1204,14 +1208,13 @@ void Goto_MainMenu() { Clear_Main_Window(); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 2, 2, 27, 14, 14, 9); // "Home" - } + if (HMI_IsChinese()) + DWIN_Frame_TitleCopy(1, 2, 2, 27, 14); // "Home" else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MAIN)); #else - DWIN_Frame_AreaCopy(1, 0, 2, 39, 12, 14, 9); + DWIN_Frame_TitleCopy(1, 0, 2, 39, 12); #endif } @@ -1588,9 +1591,9 @@ void _update_axis_value(const AxisEnum axis, const uint16_t x, const uint16_t y, if (force || changed || draw_qmark || draw_empty) { if (blink && draw_qmark) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, x, y, F("???.?")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x, y, F("???.?")); else if (blink && draw_empty) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, x, y, F(" ")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x, y, F(" ")); else DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, x, y, p * 10); } @@ -1706,11 +1709,11 @@ void update_variable() { _offset = BABY_Z_VAR; if (BABY_Z_VAR < 0) { DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -_offset * 100); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); } else { DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, _offset * 100); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); } } @@ -1853,7 +1856,7 @@ void Redraw_SD_List() { } else { DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - DWIN_Draw_String(false, false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); + DWIN_Draw_String(false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); } } @@ -1911,24 +1914,24 @@ void Draw_Status_Area(const bool with_update) { #if HAS_HOTEND DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 384, thermalManager.wholeDegHotend(0)); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.degTargetHotend(0)); DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); #endif #if HAS_HEATED_BED DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 417, thermalManager.wholeDegBed()); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); #endif DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); #if HAS_FAN DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); @@ -1941,11 +1944,11 @@ void Draw_Status_Area(const bool with_update) { if (BABY_Z_VAR < 0) { DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -BABY_Z_VAR * 100); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); } else { DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, BABY_Z_VAR * 100); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); } DWIN_Draw_Rectangle(1, Line_Color, 0, 449, DWIN_WIDTH, 451); @@ -1969,8 +1972,8 @@ void HMI_StartFrame(const bool with_update) { void Draw_Info_Menu() { Clear_Main_Window(); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, F(MACHINE_SIZE)); - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, F(SHORT_BUILD_VERSION)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, F(MACHINE_SIZE)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, F(SHORT_BUILD_VERSION)); if (HMI_IsChinese()) { DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" @@ -1990,7 +1993,7 @@ void Draw_Info_Menu() { DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); DWIN_Frame_AreaCopy(1, 0, 165, 94, 175, 89, 248); } - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); Draw_Back_First(); LOOP_L_N(i, 3) { @@ -4007,7 +4010,7 @@ void EachMomentUpdate() { //(void)recovery.interrupted_file_exists(); char * const name = card.longest_filename(); const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; - DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); + DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); DWIN_UpdateLCD(); while (recovery_flag) { @@ -4033,7 +4036,7 @@ void EachMomentUpdate() { Goto_PrintProcess(); Draw_Status_Area(true); } - #endif + #endif // POWER_LOSS_RECOVERY DWIN_UpdateLCD(); } @@ -4124,7 +4127,7 @@ void DWIN_CompletedLeveling() { void DWIN_StatusChanged(const char *text) { DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(text) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 2, F(text)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 2, F(text)); DWIN_UpdateLCD(); } @@ -4136,8 +4139,8 @@ void DWIN_StatusChanged_P(PGM_P const pstr) { // GUI extension void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode=false) { - DWIN_Draw_String(false,true,font8x16,Select_Color,bcolor,x+4,y,F(mode ? "x" : " ")); - DWIN_Draw_Rectangle(0,color,x+2,y+2,x+17,y+17); + DWIN_Draw_String(true, font8x16, Select_Color, bcolor, x + 4, y, F(mode ? "x" : " ")); + DWIN_Draw_Rectangle(0, color, x + 2, y + 2, x + 17, y + 17); } #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h similarity index 54% rename from Marlin/src/lcd/dwin/e3v2/dwin.h rename to Marlin/src/lcd/e3v2/creality/dwin.h index 4b3460aae5..36948678aa 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -25,7 +25,7 @@ * DWIN by Creality3D */ -#include "../dwin_lcd.h" +#include "dwin_lcd.h" #include "rotary_encoder.h" #include "../../../libs/BL24CXX.h" @@ -103,151 +103,6 @@ enum processID : uint8_t { Popup_Window }; -// Picture ID -#define Start_Process 0 -#define Language_English 1 -#define Language_Chinese 2 - -// ICON ID -#define ICON 0x09 -#define ICON_LOGO 0 -#define ICON_Print_0 1 -#define ICON_Print_1 2 -#define ICON_Prepare_0 3 -#define ICON_Prepare_1 4 -#define ICON_Control_0 5 -#define ICON_Control_1 6 -#define ICON_Leveling_0 7 -#define ICON_Leveling_1 8 -#define ICON_HotendTemp 9 -#define ICON_BedTemp 10 -#define ICON_Speed 11 -#define ICON_Zoffset 12 -#define ICON_Back 13 -#define ICON_File 14 -#define ICON_PrintTime 15 -#define ICON_RemainTime 16 -#define ICON_Setup_0 17 -#define ICON_Setup_1 18 -#define ICON_Pause_0 19 -#define ICON_Pause_1 20 -#define ICON_Continue_0 21 -#define ICON_Continue_1 22 -#define ICON_Stop_0 23 -#define ICON_Stop_1 24 -#define ICON_Bar 25 -#define ICON_More 26 - -#define ICON_Axis 27 -#define ICON_CloseMotor 28 -#define ICON_Homing 29 -#define ICON_SetHome 30 -#define ICON_PLAPreheat 31 -#define ICON_ABSPreheat 32 -#define ICON_Cool 33 -#define ICON_Language 34 - -#define ICON_MoveX 35 -#define ICON_MoveY 36 -#define ICON_MoveZ 37 -#define ICON_Extruder 38 - -#define ICON_Temperature 40 -#define ICON_Motion 41 -#define ICON_WriteEEPROM 42 -#define ICON_ReadEEPROM 43 -#define ICON_ResumeEEPROM 44 -#define ICON_Info 45 - -#define ICON_SetEndTemp 46 -#define ICON_SetBedTemp 47 -#define ICON_FanSpeed 48 -#define ICON_SetPLAPreheat 49 -#define ICON_SetABSPreheat 50 - -#define ICON_MaxSpeed 51 -#define ICON_MaxAccelerated 52 -#define ICON_MaxJerk 53 -#define ICON_Step 54 -#define ICON_PrintSize 55 -#define ICON_Version 56 -#define ICON_Contact 57 -#define ICON_StockConfiguraton 58 -#define ICON_MaxSpeedX 59 -#define ICON_MaxSpeedY 60 -#define ICON_MaxSpeedZ 61 -#define ICON_MaxSpeedE 62 -#define ICON_MaxAccX 63 -#define ICON_MaxAccY 64 -#define ICON_MaxAccZ 65 -#define ICON_MaxAccE 66 -#define ICON_MaxSpeedJerkX 67 -#define ICON_MaxSpeedJerkY 68 -#define ICON_MaxSpeedJerkZ 69 -#define ICON_MaxSpeedJerkE 70 -#define ICON_StepX 71 -#define ICON_StepY 72 -#define ICON_StepZ 73 -#define ICON_StepE 74 -#define ICON_Setspeed 75 -#define ICON_SetZOffset 76 -#define ICON_Rectangle 77 -#define ICON_BLTouch 78 -#define ICON_TempTooLow 79 -#define ICON_AutoLeveling 80 -#define ICON_TempTooHigh 81 -#define ICON_NoTips_C 82 -#define ICON_NoTips_E 83 -#define ICON_Continue_C 84 -#define ICON_Continue_E 85 -#define ICON_Cancel_C 86 -#define ICON_Cancel_E 87 -#define ICON_Confirm_C 88 -#define ICON_Confirm_E 89 -#define ICON_Info_0 90 -#define ICON_Info_1 91 - -#define ICON_AdvSet ICON_Language -#define ICON_HomeOff ICON_AdvSet -#define ICON_HomeOffX ICON_StepX -#define ICON_HomeOffY ICON_StepY -#define ICON_HomeOffZ ICON_StepZ -#define ICON_ProbeOff ICON_AdvSet -#define ICON_ProbeOffX ICON_StepX -#define ICON_ProbeOffY ICON_StepY -#define ICON_PIDNozzle ICON_SetEndTemp -#define ICON_PIDbed ICON_SetBedTemp - -/** - * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: - * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 - * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 - */ -#define font6x12 0x00 -#define font8x16 0x01 -#define font10x20 0x02 -#define font12x24 0x03 -#define font14x28 0x04 -#define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 - -// Color -#define Color_White 0xFFFF -#define Color_Yellow 0xFF0F -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_Bg_Red 0xF00F // Red background color -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color - extern uint8_t checkkey; extern float zprobe_zoffset; extern char print_filename[16]; diff --git a/Marlin/src/lcd/dwin/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp similarity index 93% rename from Marlin/src/lcd/dwin/dwin_lcd.cpp rename to Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp index 59bc46925a..1ce95bd729 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp @@ -21,24 +21,24 @@ */ /******************************************************************************** - * @file dwin_lcd.cpp + * @file lcd/e3v2/creality/dwin_lcd.cpp * @author LEO / Creality3D * @date 2019/07/18 * @version 2.0.1 * @brief DWIN screen control functions ********************************************************************************/ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD) -#include "../../inc/MarlinConfig.h" +#include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" #include // for memset //#define DEBUG_OUT 1 -#include "../../core/debug_out.h" +#include "../../../core/debug_out.h" // Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. // Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. @@ -122,6 +122,17 @@ bool DWIN_Handshake(void) { && databuf[3] == 'K' ); } +void DWIN_Startup(void) { + DEBUG_ECHOPGM("\r\nDWIN handshake "); + delay(750); // Delay here or init later in the boot process + if (DWIN_Handshake()) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); + DWIN_Frame_SetDir(1); + #if DISABLED(SHOW_BOOTSCREEN) + DWIN_Frame_Clear(Color_Bg_Black); // MarlinUI handles the bootscreen so just clear here + #endif + DWIN_UpdateLCD(); +} + // Set the backlight luminance // luminance: (0x00-0xFF) void DWIN_Backlight_SetLuminance(const uint8_t luminance) { @@ -164,9 +175,10 @@ void DWIN_Frame_Clear(const uint16_t color) { // width: point width 0x01-0x0F // height: point height 0x01-0x0F // x,y: upper left point -void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y) { +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { size_t i = 0; DWIN_Byte(i, 0x02); + DWIN_Word(i, color); DWIN_Byte(i, width); DWIN_Byte(i, height); DWIN_Word(i, x); @@ -238,8 +250,8 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // bColor: Background color // x/y: Upper-left coordinate of the string // *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { + uint8_t widthAdjust = 0; size_t i = 0; DWIN_Byte(i, 0x11); // Bit 7: widthAdjust @@ -356,6 +368,7 @@ void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { DWIN_Word(i, x); DWIN_Word(i, y); DWIN_Byte(i, 0x80 | libID); + //DWIN_Byte(i, libID); DWIN_Byte(i, picID); DWIN_Send(i); } @@ -421,7 +434,7 @@ void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t pi // state: 16 bits, each bit is the state of an animation id void DWIN_ICON_AnimationControl(uint16_t state) { size_t i = 0; - DWIN_Byte(i, 0x28); + DWIN_Byte(i, 0x29); DWIN_Word(i, state); DWIN_Send(i); } diff --git a/Marlin/src/lcd/dwin/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h similarity index 55% rename from Marlin/src/lcd/dwin/dwin_lcd.h rename to Marlin/src/lcd/e3v2/creality/dwin_lcd.h index 9ae6d076d5..e5e79df0fd 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -42,6 +42,163 @@ #define DWIN_WIDTH 272 #define DWIN_HEIGHT 480 +// Character matrix width x height +//#define LCD_WIDTH ((DWIN_WIDTH) / 8) +//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) + +// Picture ID +#define DWIN_Boot_Screen 0 +#define Language_English 1 +#define Language_Chinese 2 + +// ICON ID +#define ICON 0x09 + +#define ICON_LOGO 0 +#define ICON_Print_0 1 +#define ICON_Print_1 2 +#define ICON_Prepare_0 3 +#define ICON_Prepare_1 4 +#define ICON_Control_0 5 +#define ICON_Control_1 6 +#define ICON_Leveling_0 7 +#define ICON_Leveling_1 8 +#define ICON_HotendTemp 9 +#define ICON_BedTemp 10 +#define ICON_Speed 11 +#define ICON_Zoffset 12 +#define ICON_Back 13 +#define ICON_File 14 +#define ICON_PrintTime 15 +#define ICON_RemainTime 16 +#define ICON_Setup_0 17 +#define ICON_Setup_1 18 +#define ICON_Pause_0 19 +#define ICON_Pause_1 20 +#define ICON_Continue_0 21 +#define ICON_Continue_1 22 +#define ICON_Stop_0 23 +#define ICON_Stop_1 24 +#define ICON_Bar 25 +#define ICON_More 26 + +#define ICON_Axis 27 +#define ICON_CloseMotor 28 +#define ICON_Homing 29 +#define ICON_SetHome 30 +#define ICON_PLAPreheat 31 +#define ICON_ABSPreheat 32 +#define ICON_Cool 33 +#define ICON_Language 34 + +#define ICON_MoveX 35 +#define ICON_MoveY 36 +#define ICON_MoveZ 37 +#define ICON_Extruder 38 + +#define ICON_Temperature 40 +#define ICON_Motion 41 +#define ICON_WriteEEPROM 42 +#define ICON_ReadEEPROM 43 +#define ICON_ResumeEEPROM 44 +#define ICON_Info 45 + +#define ICON_SetEndTemp 46 +#define ICON_SetBedTemp 47 +#define ICON_FanSpeed 48 +#define ICON_SetPLAPreheat 49 +#define ICON_SetABSPreheat 50 + +#define ICON_MaxSpeed 51 +#define ICON_MaxAccelerated 52 +#define ICON_MaxJerk 53 +#define ICON_Step 54 +#define ICON_PrintSize 55 +#define ICON_Version 56 +#define ICON_Contact 57 +#define ICON_StockConfiguraton 58 +#define ICON_MaxSpeedX 59 +#define ICON_MaxSpeedY 60 +#define ICON_MaxSpeedZ 61 +#define ICON_MaxSpeedE 62 +#define ICON_MaxAccX 63 +#define ICON_MaxAccY 64 +#define ICON_MaxAccZ 65 +#define ICON_MaxAccE 66 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 +#define ICON_StepX 71 +#define ICON_StepY 72 +#define ICON_StepZ 73 +#define ICON_StepE 74 +#define ICON_Setspeed 75 +#define ICON_SetZOffset 76 +#define ICON_Rectangle 77 +#define ICON_BLTouch 78 +#define ICON_TempTooLow 79 +#define ICON_AutoLeveling 80 +#define ICON_TempTooHigh 81 +#define ICON_NoTips_C 82 +#define ICON_NoTips_E 83 +#define ICON_Continue_C 84 +#define ICON_Continue_E 85 +#define ICON_Cancel_C 86 +#define ICON_Cancel_E 87 +#define ICON_Confirm_C 88 +#define ICON_Confirm_E 89 +#define ICON_Info_0 90 +#define ICON_Info_1 91 + +#define ICON_AdvSet ICON_Language +#define ICON_HomeOff ICON_AdvSet +#define ICON_HomeOffX ICON_StepX +#define ICON_HomeOffY ICON_StepY +#define ICON_HomeOffZ ICON_StepZ +#define ICON_ProbeOff ICON_AdvSet +#define ICON_ProbeOffX ICON_StepX +#define ICON_ProbeOffY ICON_StepY +#define ICON_PIDNozzle ICON_SetEndTemp +#define ICON_PIDbed ICON_SetBedTemp + +/** + * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: + * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 + * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 + */ +#define font6x12 0x00 +#define font8x16 0x01 +#define font10x20 0x02 +#define font12x24 0x03 +#define font14x28 0x04 +#define font16x32 0x05 +#define font20x40 0x06 +#define font24x48 0x07 +#define font28x56 0x08 +#define font32x64 0x09 + +#define DWIN_FONT_MENU font10x20 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 +#define DWIN_FONT_ALERT font14x28 + +// Color +#define Color_White 0xFFFF +#define Color_Yellow 0xFF0F +#define Color_Error_Red 0xB000 // Error! +#define Color_Bg_Red 0xF00F // Red background color +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color + /*-------------------------------------- System variable function --------------------------------------*/ // Handshake (1: Success, 0: Fail) @@ -68,10 +225,11 @@ void DWIN_UpdateLCD(void); void DWIN_Frame_Clear(const uint16_t color); // Draw a point +// color: point color // width: point width 0x01-0x0F // height: point height 0x01-0x0F // x,y: upper left point -void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y); +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); // Draw a line // color: Line segment color @@ -125,20 +283,18 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, /*---------------------------------------- Text related functions ----------------------------------------*/ // Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment // bShow: true=display background color; false=don't display background color // size: Font size // color: Character color // bColor: Background color // x/y: Upper-left coordinate of the string // *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); class __FlashStringHelper; -inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, (char *)title); +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(bShow, size, color, bColor, x, y, (char *)title); } // Draw a positive integer diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp similarity index 99% rename from Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp rename to Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp index 97e516e70a..4fc10393b9 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp @@ -21,7 +21,7 @@ */ /***************************************************************************** - * @file rotary_encoder.cpp + * @file lcd/e3v2/creality/rotary_encoder.cpp * @author LEO / Creality3D * @date 2019/07/06 * @version 2.0.1 diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h similarity index 98% rename from Marlin/src/lcd/dwin/e3v2/rotary_encoder.h rename to Marlin/src/lcd/e3v2/creality/rotary_encoder.h index 7de80dfe01..f73577b3b0 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h @@ -22,7 +22,7 @@ #pragma once /***************************************************************************** - * @file rotary_encoder.h + * @file lcd/e3v2/creality/rotary_encoder.h * @author LEO / Creality3D * @date 2019/07/06 * @version 2.0.1 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h index 05ab8bf80f..b73424fc5a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.h @@ -44,8 +44,8 @@ class LockScreen : public BaseScreen, public CachedScreen { static void enable(); static void disable(); - static void set_hash(uint16_t pass) {passcode = pass;}; - static uint16_t get_hash() {return passcode;}; + static void set_hash(uint16_t pass) { passcode = pass; } + static uint16_t get_hash() { return passcode; } static void onEntry(); static void onRedraw(draw_mode_t); diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/fontutils.cpp index 65c8c06409..90fcb2ae7c 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/fontutils.cpp @@ -149,7 +149,7 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t static inline uint8_t utf8_strlen_cb(const char *pstart, read_byte_cb_t cb_read_byte) { uint8_t cnt = 0; uint8_t *p = (uint8_t *)pstart; - for (;;) { + if (p) for (;;) { const uint8_t b = cb_read_byte(p); if (!b) break; if (utf8_is_start_byte_of_char(b)) cnt++; diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index 105a66085f..8bfd72e9f5 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -76,8 +76,10 @@ #define INFO_FONT_HEIGHT (INFO_FONT_ASCENT + INFO_FONT_DESCENT) #define INFO_FONT_WIDTH 6 + // Graphical LCD uses the menu font size for cursor positioning #define LCD_COL_X(col) (( (col)) * (MENU_FONT_WIDTH)) - #define LCD_ROW_Y(row) ((1 + (row)) * (MENU_FONT_HEIGHT)) + #define LCD_ROW_Y(row) ((1 + (row)) * (MENU_LINE_HEIGHT)) + #define LCD_COL_X_RJ(len) (LCD_WIDTH - LCD_COL_X(len)) #else @@ -94,13 +96,17 @@ #define LCD_PIXEL_WIDTH LCD_WIDTH #define LCD_PIXEL_HEIGHT LCD_HEIGHT + // Character LCD uses direct cursor positioning #define LCD_COL_X(col) (col) #define LCD_ROW_Y(row) (row) + #define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) #endif -#define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) -#define LCD_BOTTOM_ROW (LCD_PIXEL_HEIGHT - 1) +#ifndef MENU_LINE_HEIGHT + #define MENU_LINE_HEIGHT MENU_FONT_HEIGHT +#endif + #define SETCURSOR(col, row) lcd_moveto(LCD_COL_X(col), LCD_ROW_Y(row)) #define SETCURSOR_RJ(len, row) lcd_moveto(LCD_COL_X_RJ(len), LCD_ROW_Y(row)) #define SETCURSOR_X(col) SETCURSOR(col, _lcdLineNr) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 346082986d..1e38a20250 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -47,7 +47,7 @@ MarlinUI ui; #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "dwin/e3v2/dwin.h" + #include "e3v2/creality/dwin.h" #endif #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL @@ -65,15 +65,8 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_STATUS_MESSAGE - #if HAS_WIRED_LCD - #if ENABLED(STATUS_MESSAGE_SCROLLING) - uint8_t MarlinUI::status_scroll_offset; // = 0 - constexpr uint8_t MAX_MESSAGE_LENGTH = _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)); - #else - constexpr uint8_t MAX_MESSAGE_LENGTH = MAX_LANG_CHARSIZE * (LCD_WIDTH); - #endif - #else - constexpr uint8_t MAX_MESSAGE_LENGTH = 63; + #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) + uint8_t MarlinUI::status_scroll_offset; // = 0 #endif char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; uint8_t MarlinUI::alert_level; // = 0 diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 4f11ded53f..dfa49b0fa2 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -296,6 +296,17 @@ public: #endif #if HAS_STATUS_MESSAGE + + #if HAS_WIRED_LCD + #if ENABLED(STATUS_MESSAGE_SCROLLING) + #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) + #else + #define MAX_MESSAGE_LENGTH (MAX_LANG_CHARSIZE * (LCD_WIDTH)) + #endif + #else + #define MAX_MESSAGE_LENGTH 63 + #endif + static char status_message[]; static uint8_t alert_level; // Higher levels block lower levels diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index e0c694673e..82f25ea6f3 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -187,7 +187,7 @@ static void _lcd_level_bed_corners_get_next_position() { } --cy; - y -= MENU_FONT_HEIGHT; + y -= MENU_LINE_HEIGHT; // Display the Last Z value if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f8ccc0c067..20b070e712 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -46,7 +46,7 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/e3v2/dwin.h" + #include "../lcd/e3v2/creality/dwin.h" #endif #if ENABLED(EXTENSIBLE_UI) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 61b2b72bb6..d7aca6cdc7 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -32,7 +32,7 @@ #include "../lcd/marlinui.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/e3v2/dwin.h" + #include "../lcd/e3v2/creality/dwin.h" #endif #include "../module/planner.h" // for synchronize diff --git a/ini/features.ini b/ini/features.ini index e397ea31e9..e663d80802 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -44,8 +44,8 @@ HAS_SPI_TFT = src_filter=+ SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/master.zip SPI_EEPROM = src_filter=+ +DWIN_CREALITY_LCD = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ -DWIN_CREALITY_LCD = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ HAS_TOUCH_BUTTONS = src_filter=+ HAS_LCD_MENU = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 1fb9ba55e6..3938b9f8b1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -48,7 +48,7 @@ extra_scripts = post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py lib_deps = default_src_filter = + - - + - - - - - - - + - - - - - - - - - - - - From 0085ebce4d36165278922e5c31636262f46d0889 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 1 Aug 2021 01:06:23 +0000 Subject: [PATCH 0489/2168] [cron] Bump distribution date (2021-08-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 25cd5410ad..3e1c22e8a6 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-07-31" +//#define STRING_DISTRIBUTION_DATE "2021-08-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d2999cde5e..ee17e8d71c 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 "2021-07-31" + #define STRING_DISTRIBUTION_DATE "2021-08-01" #endif /** From b8cc0667bb7c5a67b2267cd86422b2485f364ac6 Mon Sep 17 00:00:00 2001 From: Malderin <52313714+Malderin@users.noreply.github.com> Date: Sun, 1 Aug 2021 06:00:18 +0300 Subject: [PATCH 0490/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20custom=20menus?= =?UTF-8?q?=20on=20MKS=20UI=20(#22470)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_more.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp index d6f1c9ccca..e89e2f3e8a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -61,22 +61,22 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_GCODE: lv_clear_more(); lv_draw_gcode(true); break; #if HAS_USER_ITEM(1) - case ID_CUSTOM_1: queue.inject_P(PSTR(USER_GCODE_1)); break; + case ID_CUSTOM_1: queue.inject_P(PSTR(MAIN_MENU_ITEM_1_GCODE)); break; #endif #if HAS_USER_ITEM(2) - case ID_CUSTOM_2: queue.inject_P(PSTR(USER_GCODE_2)); break; + case ID_CUSTOM_2: queue.inject_P(PSTR(MAIN_MENU_ITEM_2_GCODE)); break; #endif #if HAS_USER_ITEM(3) - case ID_CUSTOM_3: queue.inject_P(PSTR(USER_GCODE_3)); break; + case ID_CUSTOM_3: queue.inject_P(PSTR(MAIN_MENU_ITEM_3_GCODE)); break; #endif #if HAS_USER_ITEM(4) - case ID_CUSTOM_4: queue.inject_P(PSTR(USER_GCODE_4)); break; + case ID_CUSTOM_4: queue.inject_P(PSTR(MAIN_MENU_ITEM_4_GCODE)); break; #endif #if HAS_USER_ITEM(5) - case ID_CUSTOM_5: queue.inject_P(PSTR(USER_GCODE_5)); break; + case ID_CUSTOM_5: queue.inject_P(PSTR(MAIN_MENU_ITEM_5_GCODE)); break; #endif #if HAS_USER_ITEM(6) - case ID_CUSTOM_6: queue.inject_P(PSTR(USER_GCODE_6)); break; + case ID_CUSTOM_6: queue.inject_P(PSTR(MAIN_MENU_ITEM_6_GCODE)); break; #endif case ID_M_RETURN: lv_clear_more(); From 381a23773b5be40cf221c42b3139e7ee5f07687b Mon Sep 17 00:00:00 2001 From: ldursw <37294448+ldursw@users.noreply.github.com> Date: Sun, 1 Aug 2021 00:42:26 -0300 Subject: [PATCH 0491/2168] =?UTF-8?q?=F0=9F=94=A8=20Fix=20(RRF=20E3)=20RX/?= =?UTF-8?q?TX=20buffer=20size=20override=20(#22475)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/stm32_serialbuffer.py | 65 ++++++++++++++----- ini/stm32f4.ini | 5 +- 2 files changed, 50 insertions(+), 20 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py index fecce47db3..c3779289e0 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -3,26 +3,57 @@ # Import("env") -# Marlin has `RX_BUFFER_SIZE` and `TX_BUFFER_SIZE` to configure the -# buffer size for receiving and transmitting data respectively. -# Stm32duino uses another set of defines for the same purpose, -# so we get the values from the Marlin configuration and set -# them in `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE`. -# It is not possible to change the values at runtime, they must -# be set with build flags. +# Marlin uses the `RX_BUFFER_SIZE` \ `TX_BUFFER_SIZE` options to +# configure buffer sizes for receiving \ transmitting serial data. +# Stm32duino uses another set of defines for the same purpose, so this +# script gets the values from the configuration and uses them to define +# `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE` as global build +# flags so they are available for use by the platform. # # The script will set the value as the default one (64 bytes) # or the user-configured one, whichever is higher. # -# Marlin has 128 and 32 as default values for RX_BUFFER_SIZE and -# TX_BUFFER_SIZE respectively. We use the highest value. +# Marlin's default buffer sizes are 128 for RX and 32 for TX. +# The highest value is taken (128/64). +# +# If MF_*_BUFFER_SIZE, SERIAL_*_BUFFER_SIZE, USART_*_BUF_SIZE, are +# defined, the first of these values will be used as the minimum. +build_flags = env.ParseFlags(env.get('BUILD_FLAGS'))["CPPDEFINES"] mf = env["MARLIN_FEATURES"] -rxBuf = str(max(128, int(mf["RX_BUFFER_SIZE"]) if "RX_BUFFER_SIZE" in mf else 0)) -txBuf = str(max(64, int(mf["TX_BUFFER_SIZE"]) if "TX_BUFFER_SIZE" in mf else 0)) -build_flags = env.get('BUILD_FLAGS') -build_flags.append("-DSERIAL_RX_BUFFER_SIZE=" + rxBuf) -build_flags.append("-DSERIAL_TX_BUFFER_SIZE=" + txBuf) -build_flags.append("-DUSART_RX_BUF_SIZE=" + rxBuf) -build_flags.append("-DUSART_TX_BUF_SIZE=" + txBuf) -env.Replace(BUILD_FLAGS=build_flags) +# Get a build flag's value or None +def getBuildFlagValue(name): + for flag in build_flags: + if isinstance(flag, list) and flag[0] == name: + return flag[1] + + return None + +# Get an overriding buffer size for RX or TX from the build flags +def getInternalSize(side): + return getBuildFlagValue(f"MF_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"SERIAL_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"USART_{side}_BUF_SIZE") + +# Get the largest defined buffer size for RX or TX +def getBufferSize(side, default): + # Get a build flag value or fall back to the given default + internal = int(getInternalSize(side) or default) + flag = side + "_BUFFER_SIZE" + # Return the largest value + return max(int(mf[flag]), internal) if flag in mf else internal + +# Add a build flag if it's not already defined +def tryAddFlag(name, value): + if getBuildFlagValue(name) is None: + env.Append(BUILD_FLAGS=[f"-D{name}={value}"]) + +# Get the largest defined buffer sizes for RX or TX, using defaults for undefined +rxBuf = getBufferSize("RX", 128) +txBuf = getBufferSize("TX", 64) + +# Provide serial buffer sizes to the stm32duino platform +tryAddFlag("SERIAL_RX_BUFFER_SIZE", rxBuf) +tryAddFlag("SERIAL_TX_BUFFER_SIZE", txBuf) +tryAddFlag("USART_RX_BUF_SIZE", rxBuf) +tryAddFlag("USART_TX_BUF_SIZE", txBuf) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 2d3b5a0f32..d2332630a1 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -152,11 +152,10 @@ extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_BIGTREE_E3_RRF board_build.offset = 0x8000 -extra_scripts = ${common.extra_scripts} build_flags = ${stm32_variant.build_flags} -DSTM32F407_5VX - -DSERIAL_RX_BUFFER_SIZE=255 - -DSERIAL_TX_BUFFER_SIZE=255 + -DMF_RX_BUFFER_SIZE=255 + -DMF_TX_BUFFER_SIZE=255 # # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) From a90c8b762c8b8ca06093d6e62f4355e8a5726115 Mon Sep 17 00:00:00 2001 From: Grayson Date: Sat, 31 Jul 2021 22:55:22 -0500 Subject: [PATCH 0492/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20G38=20with=20pro?= =?UTF-8?q?be=20on=20Z=5FMIN=20(#22452)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 4 ++-- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/module/endstops.cpp | 34 ++++++++++++++---------------- 3 files changed, 19 insertions(+), 21 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 0ebe8e265a..1025a8153b 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -771,7 +771,7 @@ #endif /** - * Set flags for enabled probes + * Set a flag for any type of bed probe, including the paper-test */ #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 @@ -913,7 +913,7 @@ #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) #define USES_Z_MIN_PROBE_PIN 1 #endif - #if Z_HOME_TO_MIN && (!USES_Z_MIN_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && TERN1(USES_Z_MIN_PROBE_PIN, ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index da17d18af1..26f28f4833 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2166,7 +2166,7 @@ #if PIN_EXISTS(Z4_MAX) #define HAS_Z4_MAX 1 #endif -#if BOTH(HAS_BED_PROBE, USES_Z_MIN_PROBE_PIN) && PIN_EXISTS(Z_MIN_PROBE) +#if HAS_BED_PROBE && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 39aefd21d8..25c26aa7b5 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -596,14 +596,15 @@ void _O2 Endstops::report_states() { // endstop ISR or the Stepper ISR. #if BOTH(DELTA, SENSORLESS_PROBING) - #define _ENDSTOP(AXIS, MINMAX) AXIS ##_MAX - #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_MAX_PIN - #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_MAX_ENDSTOP_INVERTING + #define __ENDSTOP(AXIS, ...) AXIS ##_MAX + #define _ENDSTOP_PIN(AXIS, ...) AXIS ##_MAX_PIN + #define _ENDSTOP_INVERTING(AXIS, ...) AXIS ##_MAX_ENDSTOP_INVERTING #else - #define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX + #define __ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX #define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN #define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING #endif +#define _ENDSTOP(AXIS, MINMAX) __ENDSTOP(AXIS, MINMAX) // Check endstops - Could be called from Temperature ISR! void Endstops::update() { @@ -615,9 +616,10 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) - // If G38 command is active check Z_MIN_PROBE for ALL movement - if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); + #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #define HAS_G38_PROBE 1 + // For G38 moves check the probe's pin for ALL movement + if (G38_move) UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); #endif // With Dual X, endstops are only checked in the homing direction for the active extruder @@ -746,7 +748,7 @@ void Endstops::update() { COPY_LIVE_STATE(Z_MAX, Z4_MAX); #endif #endif - #elif !USES_Z_MIN_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN + #elif TERN1(USES_Z_MIN_PROBE_PIN, Z_MAX_PIN != Z_MIN_PROBE_PIN) // If this pin isn't the bed probe it's the Z endstop UPDATE_ENDSTOP_BIT(Z, MAX); #endif @@ -930,15 +932,11 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif - #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) - #if ENABLED(G38_PROBE_AWAY) - #define _G38_OPEN_STATE (G38_move >= 4) - #else - #define _G38_OPEN_STATE LOW - #endif - // If G38 command is active check Z_MIN_PROBE for ALL movement - if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE)) != _G38_OPEN_STATE) { - if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, TERN(X_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(X_AXIS); } + #if HAS_G38_PROBE + #define _G38_OPEN_STATE TERN(G38_PROBE_AWAY, (G38_move >= 4), LOW) + // For G38 moves check the probe's pin for ALL movement + if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN))) != _G38_OPEN_STATE) { + if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, TERN(X_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(X_AXIS); } #if HAS_Y_AXIS else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, TERN(Y_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Y_AXIS); } #endif @@ -1043,7 +1041,7 @@ void Endstops::update() { #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) #if ENABLED(Z_MULTI_ENDSTOPS) PROCESS_ENDSTOP_Z(MAX); - #elif !USES_Z_MIN_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX + #elif TERN1(USES_Z_MIN_PROBE_PIN, Z_MAX_PIN != Z_MIN_PROBE_PIN) // No probe or probe is Z_MIN || Probe is not Z_MAX PROCESS_ENDSTOP(Z, MAX); #endif #if CORE_DIAG(XZ, X, MIN) From ab96ada2e240e7861c6dc5a1cbff4bdab66f2b26 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 Jul 2021 23:27:10 -0500 Subject: [PATCH 0493/2168] =?UTF-8?q?=F0=9F=8E=A8=20Adjust=20settings.cpp?= =?UTF-8?q?=20indent?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 25 ++++++++++++------------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index cc4d69f581..33e6b15f9a 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1331,12 +1331,12 @@ void MarlinSettings::postprocess() { // Extensible UI User Data // #if ENABLED(EXTENSIBLE_UI) - { - char extui_data[ExtUI::eeprom_data_size] = { 0 }; - ExtUI::onStoreSettings(extui_data); - _FIELD_TEST(extui_data); - EEPROM_WRITE(extui_data); - } + { + char extui_data[ExtUI::eeprom_data_size] = { 0 }; + ExtUI::onStoreSettings(extui_data); + _FIELD_TEST(extui_data); + EEPROM_WRITE(extui_data); + } #endif // @@ -2200,13 +2200,12 @@ void MarlinSettings::postprocess() { // Extensible UI User Data // #if ENABLED(EXTENSIBLE_UI) - // This is a significant hardware change; don't reserve EEPROM space when not present - { - const char extui_data[ExtUI::eeprom_data_size] = { 0 }; - _FIELD_TEST(extui_data); - EEPROM_READ(extui_data); - if (!validating) ExtUI::onLoadSettings(extui_data); - } + { // This is a significant hardware change; don't reserve EEPROM space when not present + const char extui_data[ExtUI::eeprom_data_size] = { 0 }; + _FIELD_TEST(extui_data); + EEPROM_READ(extui_data); + if (!validating) ExtUI::onLoadSettings(extui_data); + } #endif // From 7110c4562e69f4a1ca992d8fae4a5fe948494d3d Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 1 Aug 2021 19:09:29 +1200 Subject: [PATCH 0494/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20sprintf=5FP=20co?= =?UTF-8?q?mpile=20error=20(Maple)=20(#22479)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 57ecc4bb65..5c108d0709 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -559,7 +559,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo #endif #if ENABLED(PIDTEMPBED) case VP_PID_AUTOTUNE_BED: - sprintf_P(buf, PSTR("M303 E-1 C5 S70 U1")); + strcpy_P(buf, PSTR("M303 E-1 C5 S70 U1")); break; #endif } From 1e33c1a2a78392e9182442db043384b0f96cca20 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 1 Aug 2021 14:28:53 -0500 Subject: [PATCH 0495/2168] M256 LCD brightness (#22478) --- Marlin/src/gcode/gcode.cpp | 4 +++ Marlin/src/gcode/gcode.h | 5 +++ Marlin/src/gcode/lcd/M256.cpp | 37 +++++++++++++++++++++ Marlin/src/gcode/lcd/M73.cpp | 4 +-- Marlin/src/lcd/marlinui.cpp | 11 +++++++ Marlin/src/lcd/marlinui.h | 16 +++++++++ Marlin/src/module/settings.cpp | 45 ++++++++++++++++++++------ Marlin/src/module/stepper/trinamic.cpp | 2 +- ini/features.ini | 1 + platformio.ini | 2 +- 10 files changed, 114 insertions(+), 13 deletions(-) create mode 100644 Marlin/src/gcode/lcd/M256.cpp diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 12fd231ca8..7933c3141a 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -729,6 +729,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 250: M250(); break; // M250: Set LCD contrast #endif + #if HAS_LCD_BRIGHTNESS + case 256: M256(); break; // M256: Set LCD brightness + #endif + #if ENABLED(EXPERIMENTAL_I2CBUS) case 260: M260(); break; // M260: Send data to an i2c slave case 261: M261(); break; // M261: Request data from an i2c slave diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 769b496f22..ccbeda6474 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -191,6 +191,7 @@ * M226 - Wait until a pin is in a given state: "M226 P S" (Requires DIRECT_PIN_CONTROL) * M240 - Trigger a camera to take a photograph. (Requires PHOTO_GCODE) * M250 - Set LCD contrast: "M250 C" (0-63). (Requires LCD support) + * M256 - Set LCD brightness: "M256 B" (0-255). (Requires an LCD with brightness control) * M260 - i2c Send Data (Requires EXPERIMENTAL_I2CBUS) * M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS) * M280 - Set servo position absolute: "M280 P S". (Requires servos) @@ -820,6 +821,10 @@ private: static void M250(); #endif + #if HAS_LCD_BRIGHTNESS + static void M256(); + #endif + #if ENABLED(EXPERIMENTAL_I2CBUS) static void M260(); static void M261(); diff --git a/Marlin/src/gcode/lcd/M256.cpp b/Marlin/src/gcode/lcd/M256.cpp new file mode 100644 index 0000000000..e292acc4ed --- /dev/null +++ b/Marlin/src/gcode/lcd/M256.cpp @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#include "../../inc/MarlinConfig.h" + +#if HAS_LCD_BRIGHTNESS + +#include "../gcode.h" +#include "../../lcd/marlinui.h" + +/** + * M256: Set the LCD brightness + */ +void GcodeSuite::M256() { + if (parser.seenval('B')) ui.set_brightness(parser.value_int()); + SERIAL_ECHOLNPAIR("LCD Brightness: ", ui.brightness); +} + +#endif // HAS_LCD_BRIGHTNESS diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index 5b135bdff8..e94a2825f7 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -35,13 +35,13 @@ * M73 P25 ; Set progress to 25% */ void GcodeSuite::M73() { - if (parser.seen('P')) + if (parser.seenval('P')) ui.set_progress((PROGRESS_SCALE) > 1 ? parser.value_float() * (PROGRESS_SCALE) : parser.value_byte() ); #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - if (parser.seen('R')) ui.set_remaining_time(60 * parser.value_ulong()); + if (parser.seenval('R')) ui.set_remaining_time(60 * parser.value_ulong()); #endif } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1e38a20250..cf8d7343c6 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -91,6 +91,17 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif +#if HAS_LCD_BRIGHTNESS + uint8_t MarlinUI::brightness = DEFAULT_LCD_BRIGHTNESS; + bool MarlinUI::backlight = true; + + void MarlinUI::set_brightness(const uint8_t value) { + backlight = !!value; + if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); + // Set brightness on enabled LCD here + } +#endif + #if ENABLED(SOUND_MENU_ITEM) bool MarlinUI::buzzer_enabled = true; #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index dfa49b0fa2..9930796a01 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -239,6 +239,22 @@ public: static void media_changed(const uint8_t old_stat, const uint8_t stat); #endif + #if HAS_LCD_BRIGHTNESS + #ifndef MIN_LCD_BRIGHTNESS + #define MIN_LCD_BRIGHTNESS 1 + #endif + #ifndef MAX_LCD_BRIGHTNESS + #define MAX_LCD_BRIGHTNESS 255 + #endif + #ifndef DEFAULT_LCD_BRIGHTNESS + #define DEFAULT_LCD_BRIGHTNESS MAX_LCD_BRIGHTNESS + #endif + static uint8_t brightness; + static bool backlight; + static void set_brightness(const uint8_t value); + FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } + #endif + #if ENABLED(DWIN_CREALITY_LCD) static void refresh(); #else diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 33e6b15f9a..b30c82260f 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -36,7 +36,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V83" +#define EEPROM_VERSION "V84" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -353,6 +353,11 @@ typedef struct SettingsDataStruct { // int16_t lcd_contrast; // M250 C + // + // HAS_LCD_BRIGHTNESS + // + uint8_t lcd_brightness; // M256 B + // // Controller fan settings // @@ -999,17 +1004,19 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(lcd_contrast); - - const int16_t lcd_contrast = - #if HAS_LCD_CONTRAST - ui.contrast - #else - 127 - #endif - ; + const int16_t lcd_contrast = TERN(HAS_LCD_CONTRAST, ui.contrast, 127); EEPROM_WRITE(lcd_contrast); } + // + // LCD Brightness + // + { + _FIELD_TEST(lcd_brightness); + const uint8_t lcd_brightness = TERN(HAS_LCD_BRIGHTNESS, ui.brightness, 255); + EEPROM_WRITE(lcd_brightness); + } + // // Controller Fan // @@ -1846,6 +1853,16 @@ void MarlinSettings::postprocess() { } } + // + // LCD Brightness + // + { + _FIELD_TEST(lcd_brightness); + uint8_t lcd_brightness; + EEPROM_READ(lcd_brightness); + TERN_(HAS_LCD_BRIGHTNESS, if (!validating) ui.set_brightness(lcd_brightness)); + } + // // Controller Fan // @@ -2829,6 +2846,11 @@ void MarlinSettings::reset() { // TERN_(HAS_LCD_CONTRAST, ui.set_contrast(DEFAULT_LCD_CONTRAST)); + // + // LCD Brightness + // + TERN_(HAS_LCD_BRIGHTNESS, ui.set_brightness(DEFAULT_LCD_BRIGHTNESS)); + // // Controller Fan // @@ -3406,6 +3428,11 @@ void MarlinSettings::reset() { CONFIG_ECHO_MSG(" M250 C", ui.contrast); #endif + #if HAS_LCD_BRIGHTNESS + CONFIG_ECHO_HEADING("LCD Brightness:"); + CONFIG_ECHO_MSG(" M256 B", ui.brightness); + #endif + TERN_(CONTROLLER_FAN_EDITABLE, M710_report(forReplay)); #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index a5d7e5ad6b..f9ed43acbf 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -1008,7 +1008,7 @@ void reset_trinamic_drivers() { TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2), TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4), TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K), - TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) + TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) }; constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; } diff --git a/ini/features.ini b/ini/features.ini index e663d80802..250540797d 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -189,6 +189,7 @@ HAS_GCODE_M876 = src_filter=+ HAS_RESUME_CONTINUE = src_filter=+ HAS_STATUS_MESSAGE = src_filter=+ HAS_LCD_CONTRAST = src_filter=+ +HAS_LCD_BRIGHTNESS = src_filter=+ HAS_BUZZER = src_filter=+ LCD_SET_PROGRESS_MANUALLY = src_filter=+ TOUCH_SCREEN_CALIBRATION = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 3938b9f8b1..db4d12ea7f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -206,7 +206,7 @@ default_src_filter = + - - + - - - - - + - - - - - From 5a72a39706d4fc4bbcb2093d51963f2a2720847c Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 1 Aug 2021 21:43:31 +0200 Subject: [PATCH 0496/2168] =?UTF-8?q?=F0=9F=94=A8=20Offset/encrypt/rename?= =?UTF-8?q?=20for=20Maple=20STM32F1=20(#22477)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/STM32F103VE_longer.py | 22 ------------------- ini/stm32-common.ini | 2 +- ini/stm32f1-maple.ini | 3 ++- 3 files changed, 3 insertions(+), 24 deletions(-) delete mode 100644 buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py diff --git a/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py b/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py deleted file mode 100644 index c98059729f..0000000000 --- a/buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py +++ /dev/null @@ -1,22 +0,0 @@ -# -# buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py -# Customizations for env:STM32F103VE_longer -# -import os,marlin - -# Rename ${PROGNAME}.bin and save it as 'project.bin' (No encryption on the Longer3D) -def encrypt(source, target, env): - firmware = open(target[0].path, "rb") - renamed = open(target[0].dir.path + '/project.bin', "wb") - length = os.path.getsize(target[0].path) - position = 0 - try: - while position < length: - byte = firmware.read(1) - renamed.write(byte) - position += 1 - finally: - firmware.close() - renamed.close() - -marlin.add_post_action(encrypt); diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 4ae068939e..08b0f70b4d 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -29,7 +29,7 @@ extra_scripts = ${common.extra_scripts} extends = common_stm32 extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py - buildroot/share/PlatformIO/scripts/offset_and_rename.py + buildroot/share/PlatformIO/scripts/offset_and_rename.py # # USB Flash Drive mix-ins for STM32 diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 2a9ba83494..0258fb3b7c 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -36,6 +36,7 @@ platform_packages = tool-stm32duino extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py + buildroot/share/PlatformIO/scripts/offset_and_rename.py # # STM32F103RC @@ -178,10 +179,10 @@ platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE board_build.address = 0x08010000 +board_build.rename = project.bin board_build.ldscript = STM32F103VE_longer.ld extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py build_flags = ${common_stm32f1.build_flags} -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 build_unflags = ${common_stm32f1.build_unflags} From 1e4470484ad08ec1e2744650d52df56c409db353 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 2 Aug 2021 00:58:08 +0000 Subject: [PATCH 0497/2168] [cron] Bump distribution date (2021-08-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 3e1c22e8a6..01daff2d82 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-01" +//#define STRING_DISTRIBUTION_DATE "2021-08-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ee17e8d71c..2cb2a8fa11 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 "2021-08-01" + #define STRING_DISTRIBUTION_DATE "2021-08-02" #endif /** From 0eda34e07d6b15ac889d21d84457401683c0345f Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Mon, 2 Aug 2021 07:13:57 +0200 Subject: [PATCH 0498/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=206=20li?= =?UTF-8?q?near=20axes=20(#22482)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/serial.h | 1 + Marlin/src/inc/Conditionals_post.h | 26 ++++++++++++++++++++++++-- Marlin/src/lcd/menu/menu_motion.cpp | 6 +++--- Marlin/src/module/endstops.cpp | 12 ++++++------ Marlin/src/module/endstops.h | 9 +++++++++ 5 files changed, 43 insertions(+), 11 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 7ceb70c22c..7f96a30d6f 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -37,6 +37,7 @@ extern const char NUL_STR[], SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], SP_P_STR[], SP_T_STR[], X_STR[], Y_STR[], Z_STR[], E_STR[], + I_STR[], J_STR[], K_STR[], X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], I_LBL[], J_LBL[], K_LBL[]; diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 26f28f4833..532602ed44 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1784,6 +1784,15 @@ #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) #define Z4_SENSORLESS 1 #endif + #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) + #define I_SENSORLESS 1 + #endif + #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) + #define J_SENSORLESS 1 + #endif + #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) + #define K_SENSORLESS 1 + #endif #if AXIS_HAS_STEALTHCHOP(X) #define X_HAS_STEALTHCHOP 1 @@ -1845,8 +1854,21 @@ #if ENABLED(SPI_ENDSTOPS) #define X_SPI_SENSORLESS X_SENSORLESS - #define Y_SPI_SENSORLESS Y_SENSORLESS - #define Z_SPI_SENSORLESS Z_SENSORLESS + #if HAS_Y_AXIS + #define Y_SPI_SENSORLESS Y_SENSORLESS + #endif + #if HAS_Z_AXIS + #define Z_SPI_SENSORLESS Z_SENSORLESS + #endif + #if LINEAR_AXES >= 4 + #define I_SPI_SENSORLESS I_SENSORLESS + #endif + #if LINEAR_AXES >= 5 + #define J_SPI_SENSORLESS J_SENSORLESS + #endif + #if LINEAR_AXES >= 6 + #define K_SPI_SENSORLESS K_SENSORLESS + #endif #endif #ifndef X_INTERPOLATE #define X_INTERPOLATE INTERPOLATE diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 45e751e29a..3e7977bac6 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -357,13 +357,13 @@ void menu_motion() { GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); #endif #if LINEAR_AXES >= 4 - GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" I_STR)); + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); #endif #if LINEAR_AXES >= 5 - GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" J_STR)); + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); #endif #if LINEAR_AXES >= 6 - GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" K_STR)); + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); #endif #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 25c26aa7b5..523e133713 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -754,7 +754,7 @@ void Endstops::update() { #endif #endif - #if HAS_I_MIN + #if HAS_I_MIN && !I_SPI_SENSORLESS #if ENABLED(I_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(I, MIN); #if HAS_I2_MIN @@ -767,7 +767,7 @@ void Endstops::update() { #endif #endif - #if HAS_I_MAX + #if HAS_I_MAX && !I_SPI_SENSORLESS #if ENABLED(I_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(I, MAX); #if HAS_I2_MAX @@ -780,7 +780,7 @@ void Endstops::update() { #endif #endif - #if HAS_J_MIN + #if HAS_J_MIN && !J_SPI_SENSORLESS #if ENABLED(J_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(J, MIN); #if HAS_J2_MIN @@ -793,7 +793,7 @@ void Endstops::update() { #endif #endif - #if HAS_J_MAX + #if HAS_J_MAX && !J_SPI_SENSORLESS #if ENABLED(J_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(J, MAX); #if HAS_J2_MAX @@ -806,7 +806,7 @@ void Endstops::update() { #endif #endif - #if HAS_K_MIN + #if HAS_K_MIN && !K_SPI_SENSORLESS #if ENABLED(K_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(K, MIN); #if HAS_K2_MIN @@ -819,7 +819,7 @@ void Endstops::update() { #endif #endif - #if HAS_K_MAX + #if HAS_K_MAX && !K_SPI_SENSORLESS #if ENABLED(K_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(K, MAX); #if HAS_K2_MAX diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index f4532ca1a0..a90eb1503d 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -84,6 +84,15 @@ enum EndstopEnum : char { #if HAS_Z_MIN || HAS_Z_MAX || HOMING_Z_WITH_PROBE , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) #endif + #if HAS_I_MIN || HAS_I_MAX + , I_ENDSTOP = TERN(I_HOME_TO_MAX, I_MAX, I_MIN) + #endif + #if HAS_J_MIN || HAS_J_MAX + , J_ENDSTOP = TERN(J_HOME_TO_MAX, J_MAX, J_MIN) + #endif + #if HAS_K_MIN || HAS_K_MAX + , K_ENDSTOP = TERN(K_HOME_TO_MAX, K_MAX, K_MIN) + #endif }; #undef __ES_ITEM From 0060dbc49e32cd5015b0bf2e42c2667e07eb7b72 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 2 Aug 2021 17:08:35 -0500 Subject: [PATCH 0499/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20up=20endstop=20f?= =?UTF-8?q?lags=20(#22487)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 71 ++++++++++++++++-------------- Marlin/src/module/endstops.h | 30 +++++-------- buildroot/tests/teensy35 | 2 +- buildroot/tests/teensy41 | 2 +- 4 files changed, 51 insertions(+), 54 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 532602ed44..e25229c198 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2122,72 +2122,79 @@ #define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_) #define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M)) -#if _HAS_STOP(X,MIN) +#if BOTH(X_HOME_TO_MIN, USE_XMIN_PLUG) && _HAS_STOP(X,MIN) #define HAS_X_MIN 1 #endif -#if _HAS_STOP(X,MAX) +#if (BOTH(X_HOME_TO_MAX, USE_XMAX_PLUG) || ENABLED(DUAL_X_CARRIAGE)) && _HAS_STOP(X,MAX) #define HAS_X_MAX 1 #endif -#if HAS_Y_AXIS && _HAS_STOP(Y,MIN) +#if ALL(HAS_Y_AXIS, Y_HOME_TO_MIN, USE_YMIN_PLUG) && _HAS_STOP(Y,MIN) #define HAS_Y_MIN 1 #endif -#if HAS_Y_AXIS && _HAS_STOP(Y,MAX) +#if ALL(HAS_Y_AXIS, Y_HOME_TO_MAX, USE_YMAX_PLUG) && _HAS_STOP(Y,MAX) #define HAS_Y_MAX 1 #endif #if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN) #define HAS_Z_MIN 1 #endif -#if BOTH(HAS_Z_AXIS, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX) +#if ALL(HAS_Z_AXIS, Z_HOME_TO_MAX, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif -#if _HAS_STOP(I,MIN) +#if LINEAR_AXES >= 4 && BOTH(I_HOME_TO_MIN, USE_IMIN_PLUG) && _HAS_STOP(I,MIN) #define HAS_I_MIN 1 #endif -#if _HAS_STOP(I,MAX) +#if LINEAR_AXES >= 4 && BOTH(I_HOME_TO_MAX, USE_IMAX_PLUG) && _HAS_STOP(I,MAX) #define HAS_I_MAX 1 #endif -#if _HAS_STOP(J,MIN) +#if LINEAR_AXES >= 5 && BOTH(J_HOME_TO_MIN, USE_JMIN_PLUG) && _HAS_STOP(J,MIN) #define HAS_J_MIN 1 #endif -#if _HAS_STOP(J,MAX) +#if LINEAR_AXES >= 5 && BOTH(J_HOME_TO_MAX, USE_JMAX_PLUG) && _HAS_STOP(J,MAX) #define HAS_J_MAX 1 #endif -#if _HAS_STOP(K,MIN) +#if LINEAR_AXES >= 6 && BOTH(K_HOME_TO_MIN, USE_KMIN_PLUG) && _HAS_STOP(K,MIN) #define HAS_K_MIN 1 #endif -#if _HAS_STOP(K,MAX) +#if LINEAR_AXES >= 6 && BOTH(K_HOME_TO_MAX, USE_KMAX_PLUG) && _HAS_STOP(K,MAX) #define HAS_K_MAX 1 #endif -#if PIN_EXISTS(X2_MIN) +#if BOTH(X_HOME_TO_MIN, X_DUAL_ENDSTOPS) && PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif -#if PIN_EXISTS(X2_MAX) +#if BOTH(X_HOME_TO_MAX, X_DUAL_ENDSTOPS) && PIN_EXISTS(X2_MAX) #define HAS_X2_MAX 1 #endif -#if PIN_EXISTS(Y2_MIN) +#if BOTH(Y_HOME_TO_MIN, Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y2_MIN) #define HAS_Y2_MIN 1 #endif -#if PIN_EXISTS(Y2_MAX) +#if BOTH(Y_HOME_TO_MAX, Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y2_MAX) #define HAS_Y2_MAX 1 #endif -#if PIN_EXISTS(Z2_MIN) - #define HAS_Z2_MIN 1 -#endif -#if PIN_EXISTS(Z2_MAX) - #define HAS_Z2_MAX 1 -#endif -#if PIN_EXISTS(Z3_MIN) - #define HAS_Z3_MIN 1 -#endif -#if PIN_EXISTS(Z3_MAX) - #define HAS_Z3_MAX 1 -#endif -#if PIN_EXISTS(Z4_MIN) - #define HAS_Z4_MIN 1 -#endif -#if PIN_EXISTS(Z4_MAX) - #define HAS_Z4_MAX 1 +#if ENABLED(Z_MULTI_ENDSTOPS) + #if Z_HOME_TO_MIN && PIN_EXISTS(Z2_MIN) + #define HAS_Z2_MIN 1 + #endif + #if Z_HOME_TO_MAX && PIN_EXISTS(Z2_MAX) + #define HAS_Z2_MAX 1 + #endif + #if NUM_Z_STEPPER_DRIVERS >= 3 + #if Z_HOME_TO_MIN && PIN_EXISTS(Z3_MIN) + #define HAS_Z3_MIN 1 + #endif + #if Z_HOME_TO_MAX && PIN_EXISTS(Z3_MAX) + #define HAS_Z3_MAX 1 + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + #if Z_HOME_TO_MIN && PIN_EXISTS(Z4_MIN) + #define HAS_Z4_MIN 1 + #endif + #if Z_HOME_TO_MAX && PIN_EXISTS(Z4_MAX) + #define HAS_Z4_MAX 1 + #endif + #endif + #endif #endif + #if HAS_BED_PROBE && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index a90eb1503d..e688d3a788 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -47,26 +47,16 @@ enum EndstopEnum : char { _ES_ITEM(HAS_K_MAX, K_MAX) // Extra Endstops for XYZ - #if ENABLED(X_DUAL_ENDSTOPS) - _ES_ITEM(HAS_X_MIN, X2_MIN) - _ES_ITEM(HAS_X_MAX, X2_MAX) - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - _ES_ITEM(HAS_Y_MIN, Y2_MIN) - _ES_ITEM(HAS_Y_MAX, Y2_MAX) - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - _ES_ITEM(HAS_Z_MIN, Z2_MIN) - _ES_ITEM(HAS_Z_MAX, Z2_MAX) - #if NUM_Z_STEPPER_DRIVERS >= 3 - _ES_ITEM(HAS_Z_MIN, Z3_MIN) - _ES_ITEM(HAS_Z_MAX, Z3_MAX) - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - _ES_ITEM(HAS_Z_MIN, Z4_MIN) - _ES_ITEM(HAS_Z_MAX, Z4_MAX) - #endif - #endif + _ES_ITEM(HAS_X2_MIN, X2_MIN) + _ES_ITEM(HAS_X2_MAX, X2_MAX) + _ES_ITEM(HAS_Y2_MIN, Y2_MIN) + _ES_ITEM(HAS_Y2_MAX, Y2_MAX) + _ES_ITEM(HAS_Z2_MIN, Z2_MIN) + _ES_ITEM(HAS_Z2_MAX, Z2_MAX) + _ES_ITEM(HAS_Z3_MIN, Z3_MIN) + _ES_ITEM(HAS_Z3_MAX, Z3_MAX) + _ES_ITEM(HAS_Z4_MIN, Z4_MIN) + _ES_ITEM(HAS_Z4_MAX, Z4_MAX) // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(USES_Z_MIN_PROBE_PIN, = Z_MIN)) diff --git a/buildroot/tests/teensy35 b/buildroot/tests/teensy35 index 3352c05525..4bfa64f1db 100755 --- a/buildroot/tests/teensy35 +++ b/buildroot/tests/teensy35 @@ -100,7 +100,7 @@ exec_test $1 $2 "Teensy 3.5/3.6 COREXZ | BACKLASH" "$3" # Enable Dual Z with Dual Z endstops # restore_configs -opt_set MOTHERBOARD BOARD_TEENSY35_36 NUM_Z_STEPPER_DRIVERS 2 Z2_MAX_PIN 2 +opt_set MOTHERBOARD BOARD_TEENSY35_36 NUM_Z_STEPPER_DRIVERS 2 Z2_MIN_PIN 2 opt_enable Z_MULTI_ENDSTOPS USE_XMAX_PLUG pins_set ramps/RAMPS X_MAX_PIN -1 exec_test $1 $2 "Dual Z with Dual Z endstops" "$3" diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index 55e7e6eae2..017b81b3c1 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -103,7 +103,7 @@ exec_test $1 $2 "Teensy 4.0/4.1 COREXZ" "$3" # Enable Dual Z with Dual Z endstops # restore_configs -opt_set MOTHERBOARD BOARD_TEENSY41 NUM_Z_STEPPER_DRIVERS 2 Z2_MAX_PIN 2 +opt_set MOTHERBOARD BOARD_TEENSY41 NUM_Z_STEPPER_DRIVERS 2 Z2_MIN_PIN 2 opt_enable Z_MULTI_ENDSTOPS USE_XMAX_PLUG pins_set ramps/RAMPS X_MAX_PIN -1 exec_test $1 $2 "Dual Z with Dual Z endstops" "$3" From 444992c12fa8c6fb6b8fd3f759173259d7875345 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 3 Aug 2021 01:02:55 +0000 Subject: [PATCH 0500/2168] [cron] Bump distribution date (2021-08-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 01daff2d82..22151ed234 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-02" +//#define STRING_DISTRIBUTION_DATE "2021-08-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2cb2a8fa11..a090c0c5ed 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 "2021-08-02" + #define STRING_DISTRIBUTION_DATE "2021-08-03" #endif /** From 6a25e4e56f0863e3abee50cad35e3ef89ed270df Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 3 Aug 2021 18:29:20 -0500 Subject: [PATCH 0501/2168] =?UTF-8?q?=F0=9F=90=9B=20Allow=20SKR=20Pro=20CO?= =?UTF-8?q?NTROLLER=5FFAN=5FPIN=20override?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22411 --- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 231dd9f594..eb3ce730a6 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -300,7 +300,7 @@ #define E0_AUTO_FAN_PIN FAN1_PIN #endif -#if ENABLED(USE_CONTROLLER_FAN) && HOTENDS < 2 +#if !defined(CONTROLLER_FAN_PIN) && ENABLED(USE_CONTROLLER_FAN) && HOTENDS < 2 #define CONTROLLER_FAN_PIN PE6 // Fan2 #else #define FAN2_PIN PE6 // Fan2 From afca6e745932d295b88d37fa9bd4274e22705b0b Mon Sep 17 00:00:00 2001 From: luzpaz Date: Tue, 3 Aug 2021 20:02:34 -0400 Subject: [PATCH 0502/2168] =?UTF-8?q?=F0=9F=90=9B=20Spellcheck=20comments?= =?UTF-8?q?=20(#22496)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit codespell -q 3 --builtin=clear,rare,informal,code -S ./Marlin/src/lcd/language -L alo,amin,endcode,stdio,uint --- Marlin/Configuration.h | 2 +- Marlin/Configuration_adv.h | 2 +- Marlin/Makefile | 2 +- Marlin/src/HAL/AVR/fastio.h | 2 +- Marlin/src/HAL/DUE/HAL_SPI.cpp | 2 +- Marlin/src/HAL/DUE/usb/arduino_due_x.h | 2 +- Marlin/src/HAL/DUE/usb/udd.h | 6 +-- Marlin/src/HAL/DUE/usb/udi_cdc.c | 4 +- Marlin/src/HAL/DUE/usb/udi_cdc_conf.h | 2 +- Marlin/src/HAL/DUE/usb/udi_msc.c | 10 ++-- Marlin/src/HAL/DUE/usb/uotghs_device_due.c | 46 +++++++++---------- Marlin/src/HAL/DUE/usb/usb_protocol_msc.h | 2 +- Marlin/src/HAL/LINUX/hardware/Heater.cpp | 2 +- Marlin/src/HAL/LINUX/include/pinmapping.h | 2 +- Marlin/src/HAL/SAMD51/HAL.cpp | 2 +- Marlin/src/HAL/SAMD51/fastio.h | 2 +- Marlin/src/HAL/SAMD51/timers.cpp | 2 +- Marlin/src/HAL/STM32/HAL_MinSerial.cpp | 2 +- Marlin/src/HAL/STM32/Servo.cpp | 2 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 2 +- Marlin/src/HAL/STM32/msc_sd.cpp | 4 +- Marlin/src/HAL/STM32F1/HAL.cpp | 2 +- Marlin/src/HAL/STM32F1/SPI.cpp | 4 +- Marlin/src/HAL/STM32F1/onboard_sd.h | 6 +-- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 2 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 2 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 2 +- Marlin/src/HAL/shared/backtrace/unwarm.h | 2 +- Marlin/src/HAL/shared/backtrace/unwarmbytab.h | 2 +- Marlin/src/HAL/shared/backtrace/unwarmmem.cpp | 2 +- Marlin/src/HAL/shared/backtrace/unwarmmem.h | 2 +- Marlin/src/HAL/shared/backtrace/unwinder.cpp | 2 +- Marlin/src/HAL/shared/backtrace/unwinder.h | 2 +- .../src/HAL/shared/backtrace/unwmemaccess.h | 2 +- .../shared/cpu_exception/exception_arm.cpp | 2 +- Marlin/src/core/macros.h | 2 +- Marlin/src/core/serial_hook.h | 2 +- Marlin/src/feature/bedlevel/hilbert_curve.cpp | 2 +- Marlin/src/feature/dac/dac_mcp4728.cpp | 6 +-- Marlin/src/feature/encoder_i2c.cpp | 2 +- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 2 +- Marlin/src/gcode/config/M43.cpp | 4 +- Marlin/src/gcode/feature/L6470/M906.cpp | 2 +- Marlin/src/gcode/feature/L6470/M916-918.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 2 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 6 +-- .../lcd/dogm/status_screen_lite_ST7920.cpp | 2 +- .../lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 6 +-- Marlin/src/lcd/extui/dgus/DGUSDisplay.h | 2 +- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 2 +- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.h | 2 +- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/fysetc/DGUSScreenHandler.h | 2 +- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 2 +- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.h | 2 +- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 2 +- .../extui/dgus/hiprecy/DGUSScreenHandler.h | 2 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 2 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 2 +- .../lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 2 +- .../lcd/extui/dgus/origin/DGUSDisplayDef.h | 2 +- .../extui/dgus/origin/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/origin/DGUSScreenHandler.h | 2 +- .../archim2-flash/flash_storage.cpp | 2 +- .../ftdi_eve_lib/basic/commands.cpp | 2 +- .../ftdi_eve_lib/basic/commands.h | 2 +- .../ftdi_eve_lib/extended/command_processor.h | 4 +- .../ftdi_eve_lib/extended/event_loop.cpp | 2 +- .../ftdi_eve_lib/extended/poly_ui.h | 2 +- .../ftdi_eve_lib/extended/polygon.h | 2 +- .../ftdi_eve_lib/extended/screen_types.h | 2 +- .../ftdi_eve_lib/extended/tiny_timer.h | 2 +- .../ftdi_eve_lib/scripts/svg2cpp.py | 2 +- .../src/lcd/extui/mks_ui/SPIFlashStorage.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 2 +- .../lcd/extui/mks_ui/printer_operation.cpp | 2 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/lcd/tft/canvas.cpp | 2 +- Marlin/src/libs/MAX31865.cpp | 4 +- Marlin/src/libs/MAX31865.h | 2 +- Marlin/src/libs/W25Qxx.cpp | 4 +- Marlin/src/libs/buzzer.h | 2 +- Marlin/src/libs/duration_t.h | 4 +- Marlin/src/module/endstops.cpp | 6 +-- Marlin/src/module/planner.h | 2 +- Marlin/src/module/stepper/trinamic.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/module/thermistor/thermistor_61.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 2 +- Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h | 2 +- Marlin/src/pins/sam/pins_ADSK.h | 10 ++-- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 2 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 2 +- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 2 +- Marlin/src/sd/disk_io_driver.h | 2 +- .../src/sd/usb_flashdrive/lib-uhs2/UsbCore.h | 2 +- .../usb_flashdrive/lib-uhs2/confdescparser.h | 2 +- .../lib-uhs3/UHS_host/UHS_UsbCore.h | 2 +- .../lib-uhs3/UHS_host/UHS_macros.h | 2 +- .../MARLIN_BIGTREE_BTT002/ldscript.ld | 2 +- .../MARLIN_BIGTREE_E3_RRF/ldscript.ld | 2 +- .../MARLIN_BIGTREE_GTR_V1/ldscript.ld | 2 +- .../variants/MARLIN_BIGTREE_GTR_V1/variant.h | 2 +- .../MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld | 2 +- .../MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld | 2 +- .../MARLIN_BIGTREE_SKR_PRO_11/variant.h | 2 +- .../variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld | 2 +- .../variants/MARLIN_F103Rx/ldscript.ld | 2 +- .../variants/MARLIN_F103Vx/ldscript.ld | 2 +- .../variants/MARLIN_F103Zx/ldscript.ld | 2 +- .../variants/MARLIN_F407VE/ldscript.ld | 2 +- .../variants/MARLIN_F446VE/ldscript.ld | 2 +- .../variants/MARLIN_F4x7Vx/ldscript.ld | 2 +- .../variants/MARLIN_FLY_F407ZG/ldscript.ld | 2 +- .../MARLIN_FYSETC_CHEETAH_V20/ldscript.ld | 2 +- .../MARLIN_FYSETC_CHEETAH_V20/variant.h | 2 +- .../variants/MARLIN_FYSETC_S6/ldscript.ld | 2 +- .../variants/MARLIN_LERDGE/ldscript.ld | 2 +- .../variants/MARLIN_STEVAL_F401VE/ldscript.ld | 2 +- .../marlin_CHITU_F103/wirish/boards.cpp | 2 +- .../marlin_MEEB_3DP/wirish/boards.cpp | 2 +- .../scripts/createTemperatureLookupMarlin.py | 2 +- buildroot/share/scripts/g29_auto.py | 2 +- buildroot/tests/mega2560 | 2 +- 135 files changed, 186 insertions(+), 186 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 1b4d630681..239ee220b2 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1109,7 +1109,7 @@ #endif // Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J -// When the pin is defined you can use M672 to set/reset the probe sensivity. +// When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) #define SMART_EFFECTOR_MOD_PIN -1 // Connect a GPIO pin to the Smart Effector MOD pin diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 67c875e81f..054a14161c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3912,7 +3912,7 @@ */ #define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks. - // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. + // Use a rolling average to identify persistent errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE #endif // I2C_POSITION_ENCODERS diff --git a/Marlin/Makefile b/Marlin/Makefile index 5ff1830822..d09e5828f5 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -110,7 +110,7 @@ LIQUID_TWI2 ?= 0 WIRE ?= 0 # This defines if Tone is needed (i.e SPEAKER is defined in Configuration.h) -# Disabling this (and SPEAKER) saves approximatively 350 bytes of memory. +# Disabling this (and SPEAKER) saves approximately 350 bytes of memory. TONE ?= 1 # This defines if U8GLIB is needed (may require RELOC_WORKAROUND) diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index cf704179c8..f77d4f666c 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -284,7 +284,7 @@ enum ClockSource2 : char { * PWM availability macros */ -// Determine which harware PWMs are already in use +// Determine which hardware PWMs are already in use #define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN || P == COOLER_AUTO_FAN_PIN) #if PIN_EXISTS(CONTROLLER_FAN) #define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN) diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 758640285b..d3d76e94e5 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -437,7 +437,7 @@ } while (--todo); } - // Pointers to generic functions for block tranfers + // Pointers to generic functions for block transfers static pfnSpiTxBlock spiTxBlock = (pfnSpiTxBlock)spiTxBlockX; static pfnSpiRxBlock spiRxBlock = (pfnSpiRxBlock)spiRxBlockX; diff --git a/Marlin/src/HAL/DUE/usb/arduino_due_x.h b/Marlin/src/HAL/DUE/usb/arduino_due_x.h index d3b333fb34..e7b6f3dcb3 100644 --- a/Marlin/src/HAL/DUE/usb/arduino_due_x.h +++ b/Marlin/src/HAL/DUE/usb/arduino_due_x.h @@ -71,7 +71,7 @@ /* ------------------------------------------------------------------------ */ /** - * \page arduino_due_x_board_info "Arduino Due/X - Board informations" + * \page arduino_due_x_board_info "Arduino Due/X - Board information" * This page lists several definition related to the board description. * */ diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 7ec8c03dee..461d98513b 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -90,7 +90,7 @@ typedef struct { //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) uint8_t *payload; - //! Size of buffer to send or fill, and content the number of byte transfered + //! Size of buffer to send or fill, and content the number of byte transferred uint16_t payload_size; //! Callback called after reception of ZLP from setup request @@ -132,7 +132,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is complete * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param n number of data transfered + * \param n number of data transferred */ typedef void (*udd_callback_trans_t) (udd_ep_status_t status, iram_size_t nb_transfered, udd_ep_id_t ep); @@ -303,7 +303,7 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * The driver uses a specific DMA USB to transfer data * from internal RAM to endpoint, if this one is available. * When the transfer is finished or aborted (stall, reset, ...), the \a callback is called. - * The \a callback returns the transfer status and eventually the number of byte transfered. + * The \a callback returns the transfer status and eventually the number of byte transferred. * Note: The control endpoint is not authorized. * * \param ep The ID of the endpoint to use diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c index cbe23dbb68..89debe57f1 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.c @@ -162,7 +162,7 @@ static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep); * * \param status UDD_EP_TRANSFER_OK, if transfer finished * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param n number of data transfered + * \param n number of data transferred */ static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep); @@ -200,7 +200,7 @@ static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_ * * \param status UDD_EP_TRANSFER_OK, if transfer finished * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param n number of data transfered + * \param n number of data transferred */ static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep); diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h b/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h index d406a87743..e61b8cbaad 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h @@ -106,7 +106,7 @@ extern "C" { */ //@{ # if UDI_CDC_PORT_NB > 2 -# error USBB, UDP, UDPHS and UOTGHS interfaces have not enought endpoints. +# error USBB, UDP, UDPHS and UOTGHS interfaces have not enough endpoints. # endif #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index b7c3bb5ea0..dd34048772 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -173,7 +173,7 @@ static void udi_msc_cbw_wait(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is finished * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param nb_received number of data transfered + * \param nb_received number of data transferred */ static void udi_msc_cbw_received(udd_ep_status_t status, iram_size_t nb_received, udd_ep_id_t ep); @@ -211,7 +211,7 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size); * * \param status UDD_EP_TRANSFER_OK, if transfer finish * \param status UDD_EP_TRANSFER_ABORT, if transfer aborted - * \param nb_sent number of data transfered + * \param nb_sent number of data transferred */ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); @@ -244,7 +244,7 @@ void udi_msc_csw_send(void); * * \param status UDD_EP_TRANSFER_OK, if transfer is finished * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted - * \param nb_sent number of data transfered + * \param nb_sent number of data transferred */ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); @@ -463,7 +463,7 @@ uint8_t udi_msc_getsetting(void) static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) - return; // Don't re-stall endpoint if error reseted by setup + return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); // If stall cleared then re-stall it. Only Setup MSC Reset can clear it udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); @@ -472,7 +472,7 @@ static void udi_msc_cbw_invalid(void) static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) - return; // Don't re-stall endpoint if error reseted by setup + return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); // If stall cleared then re-stall it. Only Setup MSC Reset can clear it udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c index e13232a39c..c7e8f8d991 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c @@ -325,7 +325,7 @@ static void udd_sleep_mode(bool b_idle) /** * \name Control endpoint low level management routine. * - * This function performs control endpoint mangement. + * This function performs control endpoint management. * It handle the SETUP/DATA/HANDSHAKE phases of a control transaction. */ //@{ @@ -397,9 +397,9 @@ static void udd_ctrl_endofrequest(void); /** * \brief Main interrupt routine for control endpoint * - * This switchs control endpoint events to correct sub function. + * This switches control endpoint events to correct sub function. * - * \return \c 1 if an event about control endpoint is occured, otherwise \c 0. + * \return \c 1 if an event about control endpoint is occurred, otherwise \c 0. */ static bool udd_ctrl_interrupt(void); @@ -410,7 +410,7 @@ static bool udd_ctrl_interrupt(void); * \name Management of bulk/interrupt/isochronous endpoints * * The UDD manages the data transfer on endpoints: - * - Start data tranfer on endpoint with USB Device DMA + * - Start data transfer on endpoint with USB Device DMA * - Send a ZLP packet if requested * - Call callback registered to signal end of transfer * The transfer abort and stall feature are supported. @@ -431,7 +431,7 @@ typedef struct { uint8_t *buf; //! Size of buffer to send or fill iram_size_t buf_size; - //!< Size of data transfered + //!< Size of data transferred iram_size_t buf_cnt; //!< Size of data loaded (or prepared for DMA) last time iram_size_t buf_load; @@ -486,7 +486,7 @@ static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_n #ifdef UDD_EP_DMA_SUPPORTED /** - * \brief Start the next transfer if necessary or complet the job associated. + * \brief Start the next transfer if necessary or complete the job associated. * * \param ep endpoint number without direction flag */ @@ -496,9 +496,9 @@ static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_n /** * \brief Main interrupt routine for bulk/interrupt/isochronous endpoints * - * This switchs endpoint events to correct sub function. + * This switches endpoint events to correct sub function. * - * \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occured, otherwise \c 0. + * \return \c 1 if an event about bulk/interrupt/isochronous endpoints has occurred, otherwise \c 0. */ static bool udd_ep_interrupt(void); @@ -520,7 +520,7 @@ static bool udd_ep_interrupt(void); * * Note: * Here, the global interrupt mask is not clear when an USB interrupt is enabled - * because this one can not be occured during the USB ISR (=during INTX is masked). + * because this one can not be occurred during the USB ISR (=during INTX is masked). * See Technical reference $3.8.3 Masking interrupt requests in peripheral modules. */ #ifdef UHD_ENABLE @@ -787,7 +787,7 @@ void udd_attach(void) udd_sleep_mode(true); otg_unfreeze_clock(); - // This section of clock check can be improved with a chek of + // This section of clock check can be improved with a check of // USB clock source via sysclk() // Check USB clock because the source can be a PLL while (!Is_otg_clock_usable()); @@ -803,7 +803,7 @@ void udd_attach(void) #ifdef USB_DEVICE_HS_SUPPORT udd_enable_msof_interrupt(); #endif - // Reset following interupts flag + // Reset following interrupts flag udd_ack_reset(); udd_ack_sof(); udd_ack_msof(); @@ -902,7 +902,7 @@ bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, } dbg_print("alloc(%x, %d) ", ep, MaxEndpointSize); - // Bank choise + // Bank choice switch (bmAttributes & USB_EP_TYPE_MASK) { case USB_EP_TYPE_ISOCHRONOUS: nb_bank = UDD_ISOCHRONOUS_NB_BANK(ep); @@ -1228,7 +1228,7 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, if (Is_udd_endpoint_stall_requested(ep) || ptr_job->stall_requested) { - // Endpoint halted then registes the callback + // Endpoint halted then registers the callback ptr_job->busy = true; ptr_job->call_nohalt = callback; } else { @@ -1386,7 +1386,7 @@ static void udd_ctrl_setup_received(void) // Decode setup request if (udc_process_setup() == false) { - // Setup request unknow then stall it + // Setup request unknown then stall it udd_ctrl_stall_data(); udd_ack_setup_received(0); return; @@ -1447,7 +1447,7 @@ static void udd_ctrl_in_sent(void) udd_ctrl_prev_payload_buf_cnt += udd_ctrl_payload_buf_cnt; if ((udd_g_ctrlreq.req.wLength == udd_ctrl_prev_payload_buf_cnt) || b_shortpacket) { - // All data requested are transfered or a short packet has been sent + // All data requested are transferred or a short packet has been sent // then it is the end of data phase. // Generate an OUT ZLP for handshake phase. udd_ctrl_send_zlp_out(); @@ -1516,7 +1516,7 @@ static void udd_ctrl_out_received(void) // End of SETUP request: // - Data IN Phase aborted, // - or last Data IN Phase hidden by ZLP OUT sending quiclky, - // - or ZLP OUT received normaly. + // - or ZLP OUT received normally. udd_ctrl_endofrequest(); } else { // Protocol error during SETUP request @@ -1544,7 +1544,7 @@ static void udd_ctrl_out_received(void) (udd_ctrl_prev_payload_buf_cnt + udd_ctrl_payload_buf_cnt))) { // End of reception because it is a short packet - // Before send ZLP, call intermediat calback + // Before send ZLP, call intermediate callback // in case of data receiv generate a stall udd_g_ctrlreq.payload_size = udd_ctrl_payload_buf_cnt; if (NULL != udd_g_ctrlreq.over_under_run) { @@ -1565,7 +1565,7 @@ static void udd_ctrl_out_received(void) if (udd_g_ctrlreq.payload_size == udd_ctrl_payload_buf_cnt) { // Overrun then request a new payload buffer if (!udd_g_ctrlreq.over_under_run) { - // No callback availabled to request a new payload buffer + // No callback available to request a new payload buffer udd_ctrl_stall_data(); // Ack reception of OUT to replace NAK by a STALL udd_ack_out_received(0); @@ -1805,7 +1805,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep) // transfer size of UDD_ENDPOINT_MAX_TRANS Bytes next_trans = UDD_ENDPOINT_MAX_TRANS; - // Set 0 to tranfer the maximum + // Set 0 to transfer the maximum udd_dma_ctrl = UOTGHS_DEVDMACONTROL_BUFF_LENGTH(0); } else { udd_dma_ctrl = UOTGHS_DEVDMACONTROL_BUFF_LENGTH(next_trans); @@ -1850,7 +1850,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep) } cpu_irq_restore(flags); - // Here a ZLP has been recieved + // Here a ZLP has been received // and the DMA transfer must be not started. // It is the end of transfer ptr_job->buf_size = ptr_job->buf_cnt; @@ -1991,13 +1991,13 @@ static bool udd_ep_interrupt(void) } dbg_print("dma%x: ", ep); udd_disable_endpoint_dma_interrupt(ep); - // Save number of data no transfered + // Save number of data no transferred nb_remaining = (udd_endpoint_dma_get_status(ep) & UOTGHS_DEVDMASTATUS_BUFF_COUNT_Msk) >> UOTGHS_DEVDMASTATUS_BUFF_COUNT_Pos; if (nb_remaining) { // Transfer no complete (short packet or ZLP) then: - // Update number of data transfered + // Update number of data transferred ptr_job->buf_cnt -= nb_remaining; // Set transfer complete to stop the transfer ptr_job->buf_size = ptr_job->buf_cnt; @@ -2056,7 +2056,7 @@ static bool udd_ep_interrupt(void) udd_disable_endpoint_interrupt(ep); Assert(ptr_job->stall_requested); - // A stall has been requested during backgound transfer + // A stall has been requested during background transfer ptr_job->stall_requested = false; udd_disable_endpoint_bank_autoswitch(ep); udd_enable_stall_handshake(ep); diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index 0fef308046..e1e59237d8 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -130,7 +130,7 @@ struct usb_msc_cbw { struct usb_msc_csw { le32_t dCSWSignature; //!< Must contain 'USBS' le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transfered + le32_t dCSWDataResidue; //!< Number of bytes not transferred uint8_t bCSWStatus; //!< Status code }; diff --git a/Marlin/src/HAL/LINUX/hardware/Heater.cpp b/Marlin/src/HAL/LINUX/hardware/Heater.cpp index 70df816182..44f11986c9 100644 --- a/Marlin/src/HAL/LINUX/hardware/Heater.cpp +++ b/Marlin/src/HAL/LINUX/hardware/Heater.cpp @@ -54,7 +54,7 @@ void Heater::update() { } void Heater::interrupt(GpioEvent ev) { - // ununsed + // unused } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h index 3751ae0027..cfac5e3b48 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.h +++ b/Marlin/src/HAL/LINUX/include/pinmapping.h @@ -55,7 +55,7 @@ constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); // Test whether the pin is PWM constexpr bool PWM_PIN(const pin_t p) { return false; } -// Test whether the pin is interruptable +// Test whether the pin is interruptible constexpr bool INTERRUPT_PIN(const pin_t p) { return false; } // Get the pin number at the given index diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 5aa23cdaeb..8baad31bc7 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -98,7 +98,7 @@ // Struct must be 32 bits aligned because of DMA accesses but fields needs to be 8 bits packed typedef struct __attribute__((aligned(4), packed)) { ADC_INPUTCTRL_Type INPUTCTRL; - } HAL_DMA_DAC_Registers; // DMA transfered registers + } HAL_DMA_DAC_Registers; // DMA transferred registers #endif diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index a95b7cac0c..79aede5790 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -131,7 +131,7 @@ */ #define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48) - // Return fullfilled ADCx->INPUTCTRL.reg + // Return fulfilled ADCx->INPUTCTRL.reg #define PIN_TO_INPUTCTRL(P) ( (PIN_TO_AIN(P) == 0) ? ADC_INPUTCTRL_MUXPOS_AIN0 \ : (PIN_TO_AIN(P) == 1) ? ADC_INPUTCTRL_MUXPOS_AIN1 \ : (PIN_TO_AIN(P) == 2) ? ADC_INPUTCTRL_MUXPOS_AIN2 \ diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 5c55d32407..7a535299db 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -107,7 +107,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt // TCn clock setup - const uint8_t clockID = GCLK_CLKCTRL_IDs[TCC_INST_NUM + timer_num]; // TC clock are preceeded by TCC ones + const uint8_t clockID = GCLK_CLKCTRL_IDs[TCC_INST_NUM + timer_num]; // TC clock are preceded by TCC ones GCLK->PCHCTRL[clockID].bit.CHEN = false; SYNC(GCLK->PCHCTRL[clockID].bit.CHEN); GCLK->PCHCTRL[clockID].reg = GCLK_PCHCTRL_GEN_GCLK0 | GCLK_PCHCTRL_CHEN; // 120MHz startup code programmed diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp index 44fb93337d..c780a50c57 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -123,7 +123,7 @@ static void TX(char c) { } regs->DR = c; #else - // Let's hope a mystical guru will fix this, one day by writting interrupt-free USB CDC ACM code (or, at least, by polling the registers since interrupt will be queued but will never trigger) + // Let's hope a mystical guru will fix this, one day by writing interrupt-free USB CDC ACM code (or, at least, by polling the registers since interrupt will be queued but will never trigger) // For now, it's completely lost to oblivion. #endif } diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index c0a64c5ea9..54b1fbe670 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -37,7 +37,7 @@ static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM // This allows all timer interrupt priorities to be managed from a single location in the HAL. static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO); -// This must be called after the STM32 Servo class has intialized the timer. +// This must be called after the STM32 Servo class has initialized the timer. // It may only be needed after the first call to attach(), but it is possible // that is is necessary after every detach() call. To be safe this is currently // called after every call to attach(). diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 05e0d4c420..0c37abfcbb 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -121,7 +121,7 @@ bool PersistentStore::access_start() { address += sizeof(uint32_t); } if (current_slot == -1) { - // We didn't find anything, so we'll just intialize to empty + // We didn't find anything, so we'll just initialize to empty for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8; current_slot = EEPROM_SLOTS; } diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index 70a719d665..f95f75c5fc 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -60,7 +60,7 @@ public: return true; } - // multi block optmization + // multi block optimization sd2card->writeStart(blkAddr, blkLen); while (blkLen--) { watchdog_refresh(); @@ -80,7 +80,7 @@ public: return true; } - // multi block optmization + // multi block optimization sd2card->readStart(blkAddr); while (blkLen--) { watchdog_refresh(); diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index dcfdc88555..73014945a1 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -253,7 +253,7 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + (PriorityGroupTmp << 8)); /* Insert write key & priority group */ SCB->AIRCR = reg_value; } diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index c0a35b88d1..8bfa3d236a 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -363,8 +363,8 @@ uint16_t SPIClass::transfer16(uint16_t data) const { /** * Roger Clark and Victor Perez, 2015 * Performs a DMA SPI transfer with at least a receive buffer. - * If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer. - * On exit TX buffer is not modified, and RX buffer cotains the received data. + * If a TX buffer is not provided, FF is sent over and over for the length of the transfer. + * On exit TX buffer is not modified, and RX buffer contains the received data. * Still in progress. */ void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) { diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h index 1c0a1c5b84..f228d068c9 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.h +++ b/Marlin/src/HAL/STM32F1/onboard_sd.h @@ -7,8 +7,8 @@ #pragma once #define _DISKIO_WRITE 1 /* 1: Enable disk_write function */ -#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl fucntion */ -#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control fucntion */ +#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl function */ +#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control function */ typedef unsigned char BYTE; typedef unsigned short WORD; @@ -56,7 +56,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count); #define STA_NODISK 0x02 /* No medium in the drive */ #define STA_PROTECT 0x04 /* Write protected */ -/* Command code for disk_ioctrl fucntion */ +/* Command code for disk_ioctrl function */ /* Generic command (Used by FatFs) */ #define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */ diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 38a0fc7fa1..c89d55a134 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -166,7 +166,7 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha case STEP_TIMER_NUM: // NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded // and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value - // will result in exactly the same effect, ie trigerring an interrupt, and on top, set counter to 0 + // will result in exactly the same effect, ie triggering an interrupt, and on top, set counter to 0 timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up break; case TEMP_TIMER_NUM: diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index b6f01e6c0e..ff84e91f79 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -65,7 +65,7 @@ void spiInit(uint8_t spiRate) { case SPI_EIGHTH_SPEED: clock = 1250000; break; case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; - default: clock = 4000000; // Default from the SPI libarary + default: clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 28bca65af5..e63ab1c0e3 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -65,7 +65,7 @@ void spiInit(uint8_t spiRate) { case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; default: - clock = 4000000; // Default from the SPI libarary + clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 7e202d724e..610765ad49 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -82,7 +82,7 @@ void spiInit(uint8_t spiRate) { case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_6: clock = 312500; break; default: - clock = 4000000; // Default from the SPI libarary + clock = 4000000; // Default from the SPI library } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); SPI.begin(); diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.h b/Marlin/src/HAL/shared/backtrace/unwarm.h index 86dc98c073..edae90650e 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.h +++ b/Marlin/src/HAL/shared/backtrace/unwarm.h @@ -4,7 +4,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. *************************************************************************** diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.h b/Marlin/src/HAL/shared/backtrace/unwarmbytab.h index e2f80db2a5..53aeca2594 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.h +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.h @@ -5,7 +5,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. *************************************************************************** diff --git a/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp b/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp index a40d8540ec..24023200e1 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmmem.cpp @@ -5,7 +5,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. *************************************************************************** diff --git a/Marlin/src/HAL/shared/backtrace/unwarmmem.h b/Marlin/src/HAL/shared/backtrace/unwarmmem.h index 1340bbdf0a..eb4579a761 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmmem.h +++ b/Marlin/src/HAL/shared/backtrace/unwarmmem.h @@ -5,7 +5,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. *************************************************************************** diff --git a/Marlin/src/HAL/shared/backtrace/unwinder.cpp b/Marlin/src/HAL/shared/backtrace/unwinder.cpp index 0f88e2a7f7..aedfa2404d 100644 --- a/Marlin/src/HAL/shared/backtrace/unwinder.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwinder.cpp @@ -28,7 +28,7 @@ extern "C" const UnwTabEntry __exidx_end[]; // Detect if unwind information is present or not static int HasUnwindTableInfo() { - // > 16 because there are default entries we can't supress + // > 16 because there are default entries we can't suppress return ((char*)(&__exidx_end) - (char*)(&__exidx_start)) > 16 ? 1 : 0; } diff --git a/Marlin/src/HAL/shared/backtrace/unwinder.h b/Marlin/src/HAL/shared/backtrace/unwinder.h index 8692c7a1aa..9280e2f36e 100644 --- a/Marlin/src/HAL/shared/backtrace/unwinder.h +++ b/Marlin/src/HAL/shared/backtrace/unwinder.h @@ -5,7 +5,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. **************************************************************************/ diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.h b/Marlin/src/HAL/shared/backtrace/unwmemaccess.h index 562ab3f05d..b911e343dc 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.h +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.h @@ -5,7 +5,7 @@ * This program is PUBLIC DOMAIN. * This means that there is no copyright and anyone is able to take a copy * for free and use it as they wish, with or without modifications, and in - * any context, commerically or otherwise. The only limitation is that I + * any context, commercially or otherwise. The only limitation is that I * don't guarantee that the software is fit for any purpose or accept any * liability for its use or misuse - this software is without warranty. *************************************************************************** diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index 124f0b7c43..9a1b4caf8d 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -345,7 +345,7 @@ void hook_cpu_exceptions() { // We failed to find a valid vector table size, let's abort hooking up if (vec_size == VECTOR_TABLE_SENTINEL) return; // Poor method that's wasting RAM here, but allocating with malloc and alignment would be worst - // 128 bytes alignement is required for writing the VTOR register + // 128 bytes alignment is required for writing the VTOR register alignas(128) static unsigned long vectable[VECTOR_TABLE_SENTINEL]; SERIAL_ECHOPGM("Detected vector table size: "); diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index abcd7b9480..86368bf5e7 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -399,7 +399,7 @@ template struct first_type_of { typedef T type; }; template struct first_type_of { typedef T type; }; } - // C++11 solution using SFINAE to detect the existance of a member in a class at compile time. + // C++11 solution using SFINAE to detect the existence of a member in a class at compile time. // It creates a HasMember structure containing 'value' set to true if the member exists #define HAS_MEMBER_IMPL(Member) \ namespace Private { \ diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index d56cb55a66..2019b389e4 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -109,7 +109,7 @@ struct ConditionalSerial : public SerialBase< ConditionalSerial > { ConditionalSerial(bool & conditionVariable, SerialT & out, const bool e) : BaseClassT(e), condition(conditionVariable), out(out) {} }; -// A simple foward class that taking a reference to an existing serial instance (likely created in their respective framework) +// A simple forward class that taking a reference to an existing serial instance (likely created in their respective framework) template struct ForwardSerial : public SerialBase< ForwardSerial > { typedef SerialBase< ForwardSerial > BaseClassT; diff --git a/Marlin/src/feature/bedlevel/hilbert_curve.cpp b/Marlin/src/feature/bedlevel/hilbert_curve.cpp index e4bc3aa618..7474123e3f 100644 --- a/Marlin/src/feature/bedlevel/hilbert_curve.cpp +++ b/Marlin/src/feature/bedlevel/hilbert_curve.cpp @@ -35,7 +35,7 @@ constexpr uint8_t dim = _BV(ord); static inline bool eval_candidate(int8_t x, int8_t y, hilbert_curve::callback_ptr func, void *data) { // The print bed likely has fewer points than the full Hilbert - // curve, so cull unecessary points + // curve, so cull unnecessary points return x < (GRID_MAX_POINTS_X) && y < (GRID_MAX_POINTS_Y) ? func(x, y, data) : false; } diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 1278d1bec8..6f5a9ee691 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -81,7 +81,7 @@ uint8_t MCP4728::eepromWrite() { } /** - * Write Voltage reference setting to all input regiters + * Write Voltage reference setting to all input registers */ uint8_t MCP4728::setVref_all(const uint8_t value) { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); @@ -89,7 +89,7 @@ uint8_t MCP4728::setVref_all(const uint8_t value) { return Wire.endTransmission(); } /** - * Write Gain setting to all input regiters + * Write Gain setting to all input registers */ uint8_t MCP4728::setGain_all(const uint8_t value) { Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS)); @@ -129,7 +129,7 @@ void MCP4728::setDrvPct(xyze_uint_t &pct) { } /** - * FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1 + * FastWrite input register values - All DAC output update. refer to DATASHEET 5.6.1 * DAC Input and PowerDown bits update. * No EEPROM update */ diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index c6881591b6..283092e344 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -94,7 +94,7 @@ void I2CPositionEncoder::update() { SERIAL_ECHOLNPAIR("Untrusted encoder module on ", AS_CHAR(axis_codes[encoderAxis]), " axis has been fault-free for set duration, reinstating error correction."); - //the encoder likely lost its place when the error occured, so we'll reset and use the printer's + //the encoder likely lost its place when the error occurred, so we'll reset and use the printer's //idea of where it the axis is to re-initialize const float pos = planner.get_axis_position_mm(encoderAxis); int32_t positionInTicks = pos * get_ticks_unit(); diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index d5266179c7..2d1b9443bf 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -47,7 +47,7 @@ * Compensation values are deltas to first probe measurement at bed temp. = 60°C. * - The hotend will not be heated at any time. * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend - * so the hotend fan would not cool my probe constantly. Alternativly you could just + * so the hotend fan would not cool my probe constantly. Alternatively you could just * make sure the fan is not running while running the calibration process. * * Probe calibration: diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 4009721a57..84757e7403 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -288,8 +288,8 @@ inline void servo_probe_test() { * S - Start Pin number. If not given, will default to 0 * L - End Pin number. If not given, will default to last pin defined for this board * I - Flag to ignore Marlin's pin protection. Use with caution!!!! - * R - Repeat pulses on each pin this number of times before continueing to next pin - * W - Wait time (in miliseconds) between pulses. If not given will default to 500 + * R - Repeat pulses on each pin this number of times before continuing to next pin + * W - Wait time (in milliseconds) between pulses. If not given will default to 500 * * M43 S - Servo probe test * P - Probe index (optional - defaults to 0 diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index dddf7f8aee..b1beed068a 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -212,7 +212,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { * L6474 - current in mA (4A max) * All others - 0-255 * - * Sets KVAL_HOLD wich affects the current being driven through the stepper. + * Sets KVAL_HOLD which affects the current being driven through the stepper. * * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx * that affects the effective voltage seen by the stepper. diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp index 8a1ea48306..3dd21ef985 100644 --- a/Marlin/src/gcode/feature/L6470/M916-918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp @@ -177,7 +177,7 @@ void GcodeSuite::M916() { if ((status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD))) DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Thermal warning/shutdown has occurred"); else if (status_composite) - DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occured"); + DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occurred"); else DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Unable to get to thermal warning/shutdown"); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 1025a8153b..137b9fce3e 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -220,7 +220,7 @@ #define LCD_PROGRESS_BAR #endif #if ENABLED(TFTGLCD_PANEL_I2C) - #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave addres + #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave address #endif #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) #define STD_ENCODER_PULSES_PER_STEP 2 diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 0c87c3dc3f..f4d765e2d3 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -1321,7 +1321,7 @@ void MarlinUI::draw_status_screen() { y_map_pixels = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y); // Directions fit nicely right_edge = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X) + 1; // Find location of right edge within the character cell - bottom_line = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 1; // Find location of bottome line within the character cell + bottom_line = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 1; // Find location of bottom line within the character cell n_rows = bottom_line / (HD44780_CHAR_HEIGHT) + 1; n_cols = right_edge / (HD44780_CHAR_WIDTH) + 1; diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 5991fc3b8b..712e76e86f 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -98,7 +98,7 @@ TFTGLCD lcd; #define COLOR_EDIT '#' #define COLOR_ERROR '!' -#ifdef CONVERT_TO_EXT_ASCII //use standart pseudographic symbols in ASCII table +#ifdef CONVERT_TO_EXT_ASCII //use standard pseudographic symbols in ASCII table #define LR 179 //vertical line #define TRC 191 //top right corner #define BLC 192 //bottom left corner @@ -401,7 +401,7 @@ static void center_text_P(PGM_P pstart, uint8_t y) { // uint8_t indent = (LCD_WIDTH - 8) / 2; // symbols 217 (bottom right corner) and 218 (top left corner) are using for letters in some languages - // and they should be moved to begining ASCII table as spetial symbols + // and they should be moved to beginning ASCII table as special symbols lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str_P(PSTR("------")); lcd.write(TRC); lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str_P(PSTR("Marlin")); lcd.write(LR); lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str_P(PSTR("------")); lcd.write(BRC); @@ -733,7 +733,7 @@ Equal to 20x10 text LCD | | | HE BED FAN | | ttc ttc % | ttc - current temperature -| tts tts %%% | tts - setted temperature, %%% - percent for FAN +| tts tts %%% | tts - set temperature, %%% - percent for FAN | ICO ICO ICO ICO | ICO - icon 48x48, placed in 2 text lines | ICO ICO ICO ICO | ICO diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index c76857b6bb..be112c8d54 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -447,7 +447,7 @@ void ST7920_Lite_Status_Screen::draw_static_elements() { * data buffer (DDRAM) to be used in conjunction with the graphics * bitmap buffer (CGRAM). The contents of the graphics buffer is * XORed with the data from the character generator. This allows - * us to make the progess bar out of graphical data (the bar) and + * us to make the progress bar out of graphical data (the bar) and * text data (the percentage). */ void ST7920_Lite_Status_Screen::draw_progress_bar(const uint8_t value) { 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 aa5f990898..fde6e41792 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -73,7 +73,7 @@ static const uint8_t u8g_dev_st7920_128x64_HAL_init_seq[] PROGMEM = { 0x038, // 8 Bit interface (DL=1), basic instruction set (RE=0) 0x00C, // display on, cursor & blink off; 0x08: all off 0x006, // Entry mode: Cursor move to right, DDRAM address counter (AC) plus 1, no shift - 0x002, // disable scroll, enable CGRAM adress + 0x002, // disable scroll, enable CGRAM address 0x001, // clear RAM, needs 1.6 ms U8G_ESC_DLY(100), // delay 100 ms diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 14d394db72..0ecb138bd5 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -208,7 +208,7 @@ void ChironTFT::ConfirmationRequest(const char * const msg) { case AC_printer_resuming_from_power_outage: case AC_printer_printing: case AC_printer_paused: { - // Heater timout, send acknowledgement + // Heater timeout, send acknowledgement if (strcmp_P(msg, MARLIN_msg_heater_timeout) == 0) { pause_state = AC_paused_heater_timed_out; SendtoTFTLN(AC_msg_paused); // enable continue button @@ -248,7 +248,7 @@ void ChironTFT::StatusChange(const char * const msg) { printer_state = AC_printer_idle; msg_matched = true; } - // If probing fails dont save the mesh raise the probe above the bad point + // If probing fails don't save the mesh raise the probe above the bad point if (strcmp_P(msg, MARLIN_msg_probing_failed) == 0) { PlayTune(BEEPER_PIN, BeepBeepBeeep, 1); injectCommands_P(PSTR("G1 Z50 F500")); @@ -622,7 +622,7 @@ void ChironTFT::PanelAction(uint8_t req) { break; case 14: { // A14 Start Printing - // Allows printer to restart the job if we dont want to recover + // Allows printer to restart the job if we don't want to recover if (printer_state == AC_printer_resuming_from_power_outage) { injectCommands_P(PSTR("M1000 C")); // Cancel recovery printer_state = AC_printer_idle; diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h index ed8178449d..e486a00145 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -93,7 +93,7 @@ public: // Helper for users of this class to estimate if an interaction would be blocking. static size_t GetFreeTxBuffer(); - // Checks two things: Can we confirm the presence of the display and has we initiliazed it. + // Checks two things: Can we confirm the presence of the display and has we initialized it. // (both boils down that the display answered to our chatting) static inline bool isInitialized() { return Initialized; } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 39cb6e2bef..d73a7ea552 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -466,7 +466,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), #endif - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h index 79aee9a576..2543d20b76 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h @@ -282,7 +282,7 @@ constexpr uint16_t VP_BED_PID_P = 0x3710; constexpr uint16_t VP_BED_PID_I = 0x3712; constexpr uint16_t VP_BED_PID_D = 0x3714; -// Wating screen status +// Waiting screen status constexpr uint16_t VP_WAITING_STATUS = 0x3800; // SPs for certain variables... diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 0012a0e5e0..ae6a31fb05 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -161,7 +161,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } #endif char axiscode; - unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, dont hardcode. + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. switch (var.VP) { default: return; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index d8e25a8f77..ee0af013a8 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -36,7 +36,7 @@ public: static bool loop(); // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen - // The bools specifing whether the strings are in RAM or FLASH. + // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index f1f4308d22..bdcff47ae8 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -465,7 +465,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), #endif - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h index 0c3a6aa352..e958155381 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h @@ -278,7 +278,7 @@ constexpr uint16_t VP_BED_PID_P = 0x3710; constexpr uint16_t VP_BED_PID_I = 0x3712; constexpr uint16_t VP_BED_PID_D = 0x3714; -// Wating screen status +// Waiting screen status constexpr uint16_t VP_WAITING_STATUS = 0x3800; // SPs for certain variables... diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index 2100febc32..c67ec73f61 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -161,7 +161,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } #endif char axiscode; - unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, dont hardcode. + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. switch (var.VP) { default: return; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index d8e25a8f77..ee0af013a8 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -36,7 +36,7 @@ public: static bool loop(); // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen - // The bools specifing whether the strings are in RAM or FLASH. + // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index c60d6e8bc4..9ecfb57397 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -785,7 +785,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), #endif - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index 5c9ff02bfe..c78e35e75b 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -266,7 +266,7 @@ constexpr uint16_t VP_MOVE_OPTION = 0x3500; // constexpr uint16_t VP_BED_PID_I = 0x3712; // constexpr uint16_t VP_BED_PID_D = 0x3714; -// Wating screen status +// Waiting screen status constexpr uint16_t VP_WAITING_STATUS = 0x3800; // SPs for certain variables... diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 0c022d3e88..8c806f0ecd 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -762,7 +762,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; char axiscode; - unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, dont hardcode. + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. switch (var.VP) { // switch X Y Z or Home default: return; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 7d5263c6b8..8d5d9066f4 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -36,7 +36,7 @@ public: static bool loop(); // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen - // The bools specifing whether the strings are in RAM or FLASH. + // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index 39d89fc174..2f5e2787d6 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -267,7 +267,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), #endif - // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. + // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h index 06f0dcf001..f5fb986bde 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -268,7 +268,7 @@ constexpr uint16_t VP_BED_PID_P = 0x3710; constexpr uint16_t VP_BED_PID_I = 0x3712; constexpr uint16_t VP_BED_PID_D = 0x3714; -// Wating screen status +// Waiting screen status constexpr uint16_t VP_WAITING_STATUS = 0x3800; // SPs for certain variables... diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index 827d74967a..b0759c63af 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -161,7 +161,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } #endif char axiscode; - unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, dont hardcode. + unsigned int speed = 1500; // FIXME: get default feedrate for manual moves, don't hardcode. switch (var.VP) { default: return; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index d8e25a8f77..ee0af013a8 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -36,7 +36,7 @@ public: static bool loop(); // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen - // The bools specifing whether the strings are in RAM or FLASH. + // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index 1d4711c0e2..a28318335c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -206,7 +206,7 @@ bool UIFlashStorage::is_present = false; /* In order to provide some degree of wear leveling, each data write to the * SPI Flash chip is appended to data that was already written before, until - * the data storage area is completely filled. New data is written preceeded + * the data storage area is completely filled. New data is written preceded * with a 32-bit delimiter 'LULZ', so that we can distinguish written and * unwritten data: * diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 48d60a37ac..a10fdc3ede 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1079,7 +1079,7 @@ void CLCD::CommandFifo::str(progmem_str data) { void CLCD::init() { spi_init(); // Set Up I/O Lines for SPI and FT800/810 Control - ftdi_reset(); // Power down/up the FT8xx with the apropriate delays + ftdi_reset(); // Power down/up the FT8xx with the appropriate delays host_cmd(Use_Crystal ? CLKEXT : CLKINT, 0); host_cmd(FTDI::ACTIVE, 0); // Activate the System Clock diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index 5ce628fd36..9fc5195fd4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h @@ -70,7 +70,7 @@ * * CommandFifo::fgcolor Set Graphic Item Foreground Color * * CommandFifo::bgcolor Set Graphic Item Background Color * - * CommandFifo::begin() Begin Drawing a Primative * + * CommandFifo::begin() Begin Drawing a Primitive * * CommandFifo::mem_copy() Copy a Block of Memory * * CommandFifo::append() Append Commands to Current DL * * CommandFifo::gradient_color() Set 3D Button Highlight Color * diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 9a83e9ee09..309c1927c8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -65,7 +65,7 @@ class CommandProcessor : public CLCD::CommandFifo { uint8_t _style = 0; protected: - // Returns the cannonical thickness of a widget (i.e. the height of a toggle element) + // Returns the canonical thickness of a widget (i.e. the height of a toggle element) uint16_t widget_thickness() { CLCD::FontMetrics fm(_font); return fm.height * 20.0/16; @@ -251,7 +251,7 @@ class CommandProcessor : public CLCD::CommandFifo { return toggle(x, y, w, h, text, state, options); } - // Contrained drawing routines. These constrain the widget inside a box for easier layout. + // Constrained drawing routines. These constrain the widget inside a box for easier layout. // The FORCEDINLINE ensures that the code is inlined so that all the math is done at compile time. FORCEDINLINE CommandProcessor& track_linear(int16_t x, int16_t y, int16_t w, int16_t h, int16_t tag) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index ac8f49a055..7fccb309f5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -108,7 +108,7 @@ namespace FTDI { * - Dispatches onTouchStart and onTouchEnd events to the active screen. * - Handles auto-repetition by sending onTouchHeld to the active screen periodically. * - Plays touch feedback "click" sounds when appropriate. - * - Performs debouncing to supress spurious touch events. + * - Performs debouncing to suppress spurious touch events. */ void EventLoop::process_events() { // If the LCD is processing commands, don't check diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h index 2e74ec3a47..809e729a8f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/poly_ui.h @@ -272,7 +272,7 @@ class GenericPolyUI { if (clip) { // Clipping reduces the number of pixels that are // filled, allowing more complex shapes to be drawn - // in the alloted time. + // in the allotted time. bounds(r, x, y, w, h); cmd.cmd(SAVE_CONTEXT()); cmd.cmd(SCISSOR_XY(x, y)); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h index 6aa52f09c9..3dc80bb3bb 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h @@ -41,7 +41,7 @@ * ... * p.end_fill(); * - * Based on the example from "Applicaton Note AN_334, FT801 Polygon Application": + * Based on the example from "Application Note AN_334, FT801 Polygon Application": * * https://brtchip.com/wp-content/uploads/Support/Documentation/Application_Notes/ICs/EVE/AN_334-FT801_Polygon_Application.pdf */ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h index 94d6d4e26c..486c4fe562 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h @@ -152,7 +152,7 @@ class UIScreen { #define AT_SCREEN(screen) (current_screen.getType() == current_screen.lookupScreen(screen::onRedraw)) #define IS_PARENT_SCREEN(screen) (current_screen.peek() == current_screen.lookupScreen(screen::onRedraw)) -/************************** CACHED VS UNCHACHED SCREENS ***************************/ +/************************** CACHED VS UNCACHED SCREENS ***************************/ class UncachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h index f64d033d52..576567cf4d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h @@ -28,7 +28,7 @@ /* tiny_interval_t downsamples a 32-bit millis() value into a 8-bit value which can record periods of - a few seconds with a rougly 1/16th of second + a few seconds with a roughly 1/16th of second resolution. This allows us to measure small intervals without needing to use four-byte counters. */ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py index aa702ca4b4..cfc2625453 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py @@ -164,7 +164,7 @@ class Parser: def process_svg_path_data_cmd(self, id, cmd, a, b): """Converts the various types of moves into L or M commands - and dispatches to process_svg_path_L_or_M for futher processing.""" + and dispatches to process_svg_path_L_or_M for further processing.""" if cmd == "Z" or cmd == "z": self.process_svg_path_L_or_M("L", self.initial_x, self.initial_y) elif cmd == "H": diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 5f5608472c..6f3d6bbb6b 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -204,7 +204,7 @@ void SPIFlashStorage::flushPage() { return; } - // Part of the m_pageData was compressed, so ajust the pointers, freeing what was processed, shift the buffer + // Part of the m_pageData was compressed, so adjust the pointers, freeing what was processed, shift the buffer // TODO: To avoid this copy, use a circular buffer memmove(m_pageData, m_pageData + inputProcessed, m_pageDataUsed - inputProcessed); m_pageDataUsed -= inputProcessed; diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h index f2ce8e44ba..4683ff9351 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h @@ -55,7 +55,7 @@ * * When reading, it loads a full page from SPI Flash at once and * keeps it in a private SRAM buffer. Data is loaded as needed to - * fullfill requests. Sequential reads are optimal. + * fulfill requests. Sequential reads are optimal. * * SPIFlashStorage.beginRead(myStartAddress); * while (there is data to read) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index aae6e62a66..7dfbea5bae 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -237,7 +237,7 @@ void update_spi_flash() { uint8_t command_buf[512]; W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command befor erase spi flash + //read back the gcode command before erase spi flash W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); @@ -248,7 +248,7 @@ void update_gcode_command(int addr,uint8_t *s) { uint8_t command_buf[512]; W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command befor erase spi flash + //read back the gcode command before erase spi flash W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 68344e770c..0a5f5cd550 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -503,7 +503,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { disp_assets_update_progress("Reading files..."); dir_t d; while (dir.readDir(&d, card.longFilename) > 0) { - // If we dont get a long name, but gets a short one, try it + // If we don't get a long name, but gets a short one, try it if (card.longFilename[0] == 0 && d.name[0] != 0) dosName2LongName((const char*)d.name, card.longFilename); if (card.longFilename[0] == 0) continue; diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 5e359c4091..1bb17bb4f2 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -54,7 +54,7 @@ void printer_state_polling() { gcode.process_subcommands_now_P(PSTR("M25")); - //save the positon + //save the position uiCfg.current_x_position_bak = current_position.x; uiCfg.current_y_position_bak = current_position.y; uiCfg.current_z_position_bak = current_position.z; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp index 39d8562676..37fd2a81dc 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -198,7 +198,7 @@ void WifiSerial::flush() { // nop, the interrupt handler will free up space for us } // If we get here, nothing is queued anymore (DRIE is disabled) and - // the hardware finished tranmission (TXC is set). + // the hardware finished transmission (TXC is set). } bool WifiSerial::isHalfDuplex() const { return _serial.pin_rx == NC; } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index cf8d7343c6..f4938722e3 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -716,7 +716,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; * This is used to achieve more rapid stepping on kinematic machines. * * Currently used by the _lcd_move_xyz function in menu_motion.cpp - * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. + * and the ubl_map_move_to_xy function in menu_ubl.cpp. */ void ManualMove::task() { diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index 3c2cda4fd5..e8b89bad70 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -50,7 +50,7 @@ bool CANVAS::ToScreen() { } void CANVAS::SetBackground(uint16_t color) { - /* TODO: test and optimize perfomance */ + /* TODO: test and optimize performance */ /* uint32_t count = (endLine - startLine) * width; uint16_t *pixel = buffer; diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 590dea5ca5..909adb3807 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -257,7 +257,7 @@ void MAX31865::oneShot() { // From the datasheet: // Note that a single conversion requires approximately 52ms in 60Hz filter // mode or 62.5ms in 50Hz filter mode to complete. 1-Shot is a self-clearing bit. - // TODO: switch this out depeding on the filter mode. + // TODO: switch this out depending on the filter mode. DELAY_US(65000); // 65ms } @@ -301,7 +301,7 @@ uint16_t MAX31865::readRaw() { } /** - * Calulate and return the resistance value of the connected RTD. + * Calculate and return the resistance value of the connected RTD. * * @param refResistor The value of the matching reference resistor, usually 430 or 4300 * @return The raw RTD resistance value, NOT temperature! diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 2ab78ecbe8..5d50e870ec 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -72,7 +72,7 @@ #define MAX31865_FAULT_OVUV 0x04 // D2 // http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf -// constants for calulating temperature from the measured RTD resistance. +// constants for calculating temperature from the measured RTD resistance. #define RTD_Z1 -0.0039083 #define RTD_Z2 0.00001758480889 #define RTD_Z3 -0.0000000231 diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index fd7804cb27..56581ed46e 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -157,8 +157,8 @@ void W25QXXFlash::SPI_FLASH_WriteEnable(void) { /******************************************************************************* * Function Name : SPI_FLASH_WaitForWriteEnd * Description : Polls the status of the Write In Progress (WIP) flag in the -* FLASH's status register and loop until write opertaion -* has completed. +* FLASH's status register and loop until write operation has +* completed. * Input : None * Output : None * Return : None diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index b86fe998fa..21b69002ff 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -56,7 +56,7 @@ static CircularQueue buffer; /** - * @brief Inverts the sate of a digital PIN + * @brief Inverts the state of a digital PIN * @details This will invert the current state of an digital IO pin. */ FORCE_INLINE static void invert() { TOGGLE(BEEPER_PIN); } diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 148aa23211..4d722a296c 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -113,7 +113,7 @@ struct duration_t { /** * @brief Formats the duration as a string - * @details String will be formated using a "full" representation of duration + * @details String will be formatted using a "full" representation of duration * * @param buffer The array pointed to must be able to accommodate 22 bytes * (21 for the string, 1 more for the terminating nul) @@ -143,7 +143,7 @@ struct duration_t { /** * @brief Formats the duration as a string - * @details String will be formated using a "digital" representation of duration + * @details String will be formatted using a "digital" representation of duration * * @param buffer The array pointed to must be able to accommodate 10 bytes * diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 523e133713..0f4716ed87 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -884,7 +884,7 @@ void Endstops::update() { const byte dual_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1); \ if (dual_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || dual_hit == 0b11) \ planner.endstop_triggered(_AXIS(A)); \ } \ @@ -894,7 +894,7 @@ void Endstops::update() { const byte triple_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(A##3, MINMAX)) << 2); \ if (triple_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || triple_hit == 0b111) \ planner.endstop_triggered(_AXIS(A)); \ } \ @@ -904,7 +904,7 @@ void Endstops::update() { const byte quad_hit = TEST_ENDSTOP(_ENDSTOP(A, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(A##2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(A##3, MINMAX)) << 2) | (TEST_ENDSTOP(_ENDSTOP(A##4, MINMAX)) << 3); \ if (quad_hit) { \ _ENDSTOP_HIT(A, MINMAX); \ - /* if not performing home or if both endstops were trigged during homing... */ \ + /* if not performing home or if both endstops were triggered during homing... */ \ if (!stepper.separate_multi_axis || quad_hit == 0b1111) \ planner.endstop_triggered(_AXIS(A)); \ } \ diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 9b104615f6..5e3922c897 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -857,7 +857,7 @@ class Planner { static void quick_resume(); #endif - // Called when an endstop is triggered. Causes the machine to stop inmediately + // Called when an endstop is triggered. Causes the machine to stop immediately static void endstop_triggered(const AxisEnum axis); // Triggered position of an axis in mm (not core-savvy) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index f9ed43acbf..fd63027974 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -955,7 +955,7 @@ void reset_trinamic_drivers() { // TMC Slave Address Conflict Detection // // Conflict detection is performed in the following way. Similar methods are used for -// hardware and software serial, but the implementations are indepenent. +// hardware and software serial, but the implementations are independent. // // 1. Populate a data structure with UART parameters and addresses for all possible axis. // If an axis is not in use, populate it with recognizable placeholder data. diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 20b070e712..1e91511f5a 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1522,7 +1522,7 @@ void Temperature::manage_heater() { #endif #if ENABLED(PIDTEMPCHAMBER) - // PIDTEMPCHAMBER doens't support a CHAMBER_VENT yet. + // PIDTEMPCHAMBER doesn't support a CHAMBER_VENT yet. temp_chamber.soft_pwm_amount = WITHIN(temp_chamber.celsius, CHAMBER_MINTEMP, CHAMBER_MAXTEMP) ? (int)get_pid_output_chamber() >> 1 : 0; #else if (ELAPSED(ms, next_chamber_check_ms)) { diff --git a/Marlin/src/module/thermistor/thermistor_61.h b/Marlin/src/module/thermistor/thermistor_61.h index deeec356a1..2916bffd3b 100644 --- a/Marlin/src/module/thermistor/thermistor_61.h +++ b/Marlin/src/module/thermistor/thermistor_61.h @@ -31,7 +31,7 @@ // B Value 3950K at 25/50 deg. C // B Value Tolerance + / - 1% constexpr temp_entry_t temptable_61[] PROGMEM = { - { OV( 2.00), 420 }, // Guestimate to ensure we dont lose a reading and drop temps to -50 when over + { OV( 2.00), 420 }, // Guestimate to ensure we don't lose a reading and drop temps to -50 when over { OV( 12.07), 350 }, { OV( 12.79), 345 }, { OV( 13.59), 340 }, 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 9066b24390..c6a44123a0 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -140,7 +140,7 @@ // 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. - // The UART-based devices require 2 pis per deriver (one of which must be interrupt capable). + // The UART-based devices require 2 pis per driver (one of which must be interrupt capable). // The same SPI pins can be shared with the display/SD card reader, meaning SPI-based devices are // probably a good choice for this board. // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index b262212b7e..42c6f4d029 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -265,7 +265,7 @@ #elif HAS_ADC_BUTTONS - #error "ADC BUTTONS do not work unmodifed on SKR 1.3, The ADC ports cannot take more than 3.3v." + #error "ADC BUTTONS do not work unmodified on SKR 1.3, The ADC ports cannot take more than 3.3v." #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI 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 73b4d3e63d..43e954a4f1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -494,7 +494,7 @@ #endif // HAS_WIRED_LCD #if HAS_ADC_BUTTONS - #error "ADC BUTTONS do not work unmodifed on SKR 1.4, The ADC ports cannot take more than 3.3v." + #error "ADC BUTTONS do not work unmodified on SKR 1.4, The ADC ports cannot take more than 3.3v." #endif // diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index cbf6ca2d3c..1ec1131b45 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -25,7 +25,7 @@ #define BOARD_INFO_NAME "GMARSH X6 REV1" -// Ignore temp readings during develpment. +// Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index de8db60847..b884fcbfc7 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -138,7 +138,7 @@ #define HEATER_BED_PIN 8 #define FAN_PIN 9 -#define FAN1_PIN 5 // Normall this would be a servo pin +#define FAN1_PIN 5 // Normally this would be a servo pin // XXX Runout support unknown? //#define NUM_RUNOUT_SENSORS 0 diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 6fe0520f81..425d6d45af 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -47,10 +47,10 @@ A stepper for E0 extruder Vcc (now "5V" on the board but actual 3.3V because of jumper)) (Hold)&(GND) - Bed thermistor (also require pullup resistor 4.7K between "Hold" and Vcc (now "5V" on the board but actual 3.3V because of jumper)) -(CoolEn) - 3.3v signal to controll extruder heater MOSFET +(CoolEn) - 3.3v signal to control extruder heater MOSFET (Resume) - 3.3v signal to control heatbed MOSFET -(SDA) - 3.3v signal to controll extruder fan -(SCL) - 3.3v signal to controll extruder cooling fan +(SDA) - 3.3v signal to control extruder fan +(SCL) - 3.3v signal to control extruder cooling fan */ /* CNC Shield pinout @@ -137,7 +137,7 @@ A stepper for E0 extruder * The 2004 LCD should be powered with 5V. * The next LCD pins RS,D4,D5,D6,D7 have internal pull-ups to 5V and as result the 5V will be on these pins. * Luckily these internal pull-ups have really high resistance and adding 33K pull-down resistors will create - * simple voltage divider that will bring the voltage down just slightly bellow 3.3V. + * simple voltage divider that will bring the voltage down just slightly below 3.3V. * * This LCD also has buttons that connected to the same ADC pin with different voltage divider combinations. * On the LCD panel there is internal pull-up resistor of the 4.7K connected to 5V. @@ -175,7 +175,7 @@ A stepper for E0 extruder #define ADC_BUTTONS_VALUE_SCALE (5.0/AREF_VOLTS) // The LCD module pullup voltage is 5.0V but ADC reference voltage is 3.3V - #define ADC_BUTTONS_R_PULLDOWN 4.7 // Moves voltage down to be bellow 3.3V instead of 5V + #define ADC_BUTTONS_R_PULLDOWN 4.7 // Moves voltage down to be below 3.3V instead of 5V // the resistors values will be scaled because of 4.7K pulldown parallel resistor #define _ADC_BUTTONS_R_SCALED(R) ((R) * (ADC_BUTTONS_R_PULLDOWN) / ((R) + ADC_BUTTONS_R_PULLDOWN)) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 939edc6052..b7fd7222c8 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -235,7 +235,7 @@ // // Onboard SD card // -// detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled +// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI3 #define SD_SS_PIN -1 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 6795b92892..882b9601ac 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -229,7 +229,7 @@ // // Onboard SD card // -// detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled +// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI3 #define SD_SS_PIN -1 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 0b9512a1cb..aa65eaa799 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -212,7 +212,7 @@ // Onboard SD card // NOT compatible with LCD // -// detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled +// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD #if USE_NEW_SPI_API #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) diff --git a/Marlin/src/sd/disk_io_driver.h b/Marlin/src/sd/disk_io_driver.h index 73c12efcfa..02e2b3c739 100644 --- a/Marlin/src/sd/disk_io_driver.h +++ b/Marlin/src/sd/disk_io_driver.h @@ -24,7 +24,7 @@ #include /** - * DiskIO Interace + * DiskIO Interface * * Interface for low level disk io */ diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h index 5c76ffb758..2b6e1be522 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h @@ -114,7 +114,7 @@ typedef MAX3421e MAX3421E; // Official Arduinos (UNO, Duemilanove, Mega #define USB_NUMDEVICES 16 //number of USB devices //#define HUB_MAX_HUBS 7 // maximum number of hubs that can be attached to the host controller -#define HUB_PORT_RESET_DELAY 20 // hub port reset delay 10 ms recomended, can be up to 20 ms +#define HUB_PORT_RESET_DELAY 20 // hub port reset delay 10 ms recommended, can be up to 20 ms /* USB state machine states */ #define USB_STATE_MASK 0xF0 diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h index 9ed35fff65..19d3756535 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/confdescparser.h @@ -57,7 +57,7 @@ class ConfigDescParser : public USBReadParser { uint8_t dscrLen; // Descriptor length uint8_t dscrType; // Descriptor type - bool isGoodInterface; // Apropriate interface flag + bool isGoodInterface; // Appropriate interface flag uint8_t confValue; // Configuration value uint8_t protoValue; // Protocol value uint8_t ifaceNumber; // Interface number diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h index 1591f3b74b..58d7ba200c 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h @@ -248,7 +248,7 @@ e-mail : support@circuitsathome.com #define UHS_HOST_TRANSFER_MAX_MS 10000 // USB transfer timeout in ms, per section 9.2.6.1 of USB 2.0 spec #define UHS_HOST_TRANSFER_RETRY_MAXIMUM 3 // 3 retry limit for a transfer #define UHS_HOST_DEBOUNCE_DELAY_MS 500 // settle delay in milliseconds -#define UHS_HUB_RESET_DELAY_MS 20 // hub port reset delay, 10ms recomended, but can be up to 20ms +#define UHS_HUB_RESET_DELAY_MS 20 // hub port reset delay, 10ms recommended, but can be up to 20ms // // We only provide the minimum needed information for enumeration. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h index fb2e8b3871..bb2a87cf03 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h @@ -150,7 +150,7 @@ e-mail : support@circuitsathome.com // HANDY MACROS //////////////////////////////////////////////////////////////////////////////// -// Atmoically set/clear single bits using bitbands. +// Atomically set/clear single bits using bitbands. // Believe it or not, this boils down to a constant, // and is less code than using |= &= operators. // Bonus, it makes code easier to read too. diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld index 0c060d1751..6af296a521 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld index 0c060d1751..6af296a521 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld index 0c060d1751..6af296a521 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h index 2da195c6cf..732e0c51f1 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h @@ -280,7 +280,7 @@ extern "C" { #define PIN_SERIAL_TX PA9 // Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number -// Used when user instanciate a hardware Serial using its peripheral name. +// Used when user instantiate a hardware Serial using its peripheral name. // Example: HardwareSerial mySerial(USART3); // will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. #define PIN_SERIAL1_RX PA10 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld index 5ced01158f..ca21498cd2 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld @@ -150,7 +150,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld index 0c060d1751..6af296a521 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h index 1ba0a18d6a..f9091a4f91 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h @@ -280,7 +280,7 @@ extern "C" { #define PIN_SERIAL_TX PA9 // Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number -// Used when user instanciate a hardware Serial using its peripheral name. +// Used when user instantiate a hardware Serial using its peripheral name. // Example: HardwareSerial mySerial(USART3); // will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. #define PIN_SERIAL1_RX PA10 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld index 5e01911d82..006c87a17a 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/ldscript.ld @@ -173,7 +173,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld index f8eb971a6c..cd7503b3a5 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld @@ -162,7 +162,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld index c9197c8b45..a65b07d61c 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Vx/ldscript.ld @@ -162,7 +162,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld index 09088b622c..cc4b323f76 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/ldscript.ld @@ -162,7 +162,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld index efe2db5cd4..68b6597322 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld index 503472806e..a375232d59 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F446VE/ldscript.ld @@ -149,7 +149,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld index aa685e8111..8b38135a2a 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld @@ -167,7 +167,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld index 40abfe19b5..d644d49beb 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/ldscript.ld @@ -169,7 +169,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld index 2dbc5177ac..9565cd89c6 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/ldscript.ld @@ -150,7 +150,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h index d0fb0d9db0..bcd5aa378e 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h @@ -112,7 +112,7 @@ extern "C" { #define PIN_SERIAL_RX PA10 #define PIN_SERIAL_TX PA9 -// Used when user instanciate a hardware Serial using its peripheral name. +// Used when user instantiate a hardware Serial using its peripheral name. // Example: HardwareSerial mySerial(USART3); // will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. #define PIN_SERIAL1_RX PA10 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld index fee7418b04..900ef06391 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/ldscript.ld @@ -150,7 +150,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld index f36ebcdea1..ef151075b7 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/ldscript.ld @@ -149,7 +149,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld index f20a047c65..c5788dbebe 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/ldscript.ld @@ -148,7 +148,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp index 2210e9844c..f22cf354e2 100644 --- a/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp +++ b/buildroot/share/PlatformIO/variants/marlin_CHITU_F103/wirish/boards.cpp @@ -156,7 +156,7 @@ static void setup_nvic(void) { nvic_init((uint32)VECT_TAB_ADDR, 0); -/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater +/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect parameter #ifdef VECT_TAB_FLASH nvic_init(USER_ADDR_ROM, 0); #elif defined VECT_TAB_RAM diff --git a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp index 12321229de..77dcbcf848 100644 --- a/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp +++ b/buildroot/share/PlatformIO/variants/marlin_MEEB_3DP/wirish/boards.cpp @@ -156,7 +156,7 @@ static void setup_nvic(void) { nvic_init((uint32)VECT_TAB_ADDR, 0); -/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater +/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect parameter #ifdef VECT_TAB_FLASH nvic_init(USER_ADDR_ROM, 0); #elif defined VECT_TAB_RAM diff --git a/buildroot/share/scripts/createTemperatureLookupMarlin.py b/buildroot/share/scripts/createTemperatureLookupMarlin.py index b3343de1a0..02981f1015 100755 --- a/buildroot/share/scripts/createTemperatureLookupMarlin.py +++ b/buildroot/share/scripts/createTemperatureLookupMarlin.py @@ -73,7 +73,7 @@ class Thermistor: return r def temp(self, adc): - "Convert ADC reading into a temperature in Celcius" + "Convert ADC reading into a temperature in Celsius" l = log(self.resist(adc)) Tinv = self.c1 + self.c2*l + self.c3* l**3 # inverse temperature return (1/Tinv) - ZERO # temperature diff --git a/buildroot/share/scripts/g29_auto.py b/buildroot/share/scripts/g29_auto.py index ffcb0d9f31..ca36346dd9 100755 --- a/buildroot/share/scripts/g29_auto.py +++ b/buildroot/share/scripts/g29_auto.py @@ -119,7 +119,7 @@ def z_parse(gcode, start_at_line=0, end_at_line=0): # last_z = z last_i = i if 0 < end_at_line <= i or temp_line >= min_g1: - # print('break at line {} at heigth {}'.format(i, z)) + # print('break at line {} at height {}'.format(i, z)) break line_between_z = line_between_z[1:] diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index edae6d24ae..0af5513294 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -127,7 +127,7 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # # REPRAPWORLD_KEYPAD # -# Cant find configuration details to get it to compile +# Can't find configuration details to get it to compile #restore_configs #opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP #exec_test $1 $2 "Stuff" "$3" From 092b5942c1cc569a85e0d0e4a1f50b20a5485d63 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Tue, 3 Aug 2021 18:06:16 -0600 Subject: [PATCH 0503/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FTDI=20Eve=20Tou?= =?UTF-8?q?ch=20UI=20(#22500)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/command_processor.h | 4 +- .../ftdi_eve_lib/extended/text_box.cpp | 12 ++--- .../ftdi_eve_lib/extended/text_ellipsis.cpp | 40 +++++++------- .../generic/dialog_box_base_class.cpp | 8 +-- .../generic/dialog_box_base_class.h | 1 - .../generic/interface_settings_screen.cpp | 2 +- .../generic/interface_sounds_screen.cpp | 54 ++++--------------- .../generic/interface_sounds_screen.h | 2 - .../generic/spinner_dialog_box.cpp | 48 ++++++++++++++--- .../generic/spinner_dialog_box.h | 4 +- 10 files changed, 83 insertions(+), 92 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 309c1927c8..7504a1387d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -232,13 +232,11 @@ class CommandProcessor : public CLCD::CommandFifo { FORCEDINLINE CommandProcessor& toggle(int16_t x, int16_t y, int16_t w, int16_t h, T text, bool state, uint16_t options = FTDI::OPT_3D) { CLCD::FontMetrics fm(_font); const int16_t widget_h = fm.height * 20.0 / 16; - //const int16_t outer_bar_r = widget_h / 2; - //const int16_t knob_r = outer_bar_r - 1.5; // The y coordinate of the toggle is the baseline of the text, // so we must introduce a fudge factor based on the line height to // actually center the control. const int16_t fudge_y = fm.height * 5 / 16; - CLCD::CommandFifo::toggle(x + h / 2, y + (h - widget_h) / 2 + fudge_y, w - h, _font, options, state); + CLCD::CommandFifo::toggle(x + widget_h, y + (h - widget_h) / 2 + fudge_y, w - widget_h, _font, options, state); CLCD::CommandFifo::str(text); return *this; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 0701e7d682..544c5fed05 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -67,12 +67,12 @@ namespace FTDI { width = height = 0; for (;;) { const uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); - if (line_end == line_start) break; width = max(width, line_width); height += utf8_fm.get_height(); + if (*line_end == '\n' || *line_end == ' ') line_end++; + if (*line_end == '\0') break; + if (line_end == line_start) break; line_start = line_end; - if (*line_start == '\n' || *line_start == ' ') line_start++; - if (*line_start == '\0') break; } } @@ -109,7 +109,6 @@ namespace FTDI { const char *line_start = str, *line_end; for (;;) { find_line_break(utf8_fm, clcd_fm, w, line_start, line_end, use_utf8); - if (line_end == line_start) break; const size_t line_len = line_end - line_start; if (line_len) { @@ -125,9 +124,10 @@ namespace FTDI { } y += utf8_fm.get_height(); + if (*line_end == '\n' || *line_end == ' ') line_end++; + if (*line_end == '\0') break; + if (line_end == line_start) break; line_start = line_end; - if (*line_start == '\n' || *line_start == ' ') line_start++; - if (*line_start == '\0') break; } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index 6a58dd2e49..4262dd1155 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -29,30 +29,30 @@ namespace FTDI { * Helper function for drawing text with ellipses. The str buffer may be modified and should have space for up to two extra characters. */ static void _draw_text_with_ellipsis(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, char *str, uint16_t options, uint8_t font) { - FontMetrics fm(font); - const int16_t ellipsisWidth = fm.get_char_width('.') * 3; + #if ENABLED(TOUCH_UI_USE_UTF8) + const bool use_utf8 = has_utf8_chars(str); + #define CHAR_WIDTH(c) use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c] + #else + #define CHAR_WIDTH(c) utf8_fm.get_char_width(c) + constexpr bool use_utf8 = false; + #endif + FontMetrics utf8_fm(font); + CLCD::FontMetrics clcd_fm; + clcd_fm.load(font); + const int16_t ellipsisWidth = utf8_fm.get_char_width('.') * 3; // Compute the total line length, as well as // the location in the string where it can // split and still allow the ellipsis to fit. int16_t lineWidth = 0; - char *breakPoint = str; - #ifdef TOUCH_UI_USE_UTF8 - char *tstr = str; - while (*tstr) { - breakPoint = tstr; - const utf8_char_t c = get_utf8_char_and_inc(tstr); - lineWidth += fm.get_char_width(c); - if (lineWidth + ellipsisWidth < w) - break; - } - #else - for (char *c = str; *c; c++) { - lineWidth += fm.get_char_width(*c); - if (lineWidth + ellipsisWidth < w) - breakPoint = c; - } - #endif + char *breakPoint = str; + char *next = str; + while (*next) { + const utf8_char_t c = get_utf8_char_and_inc(next); + lineWidth += CHAR_WIDTH(c); + if (lineWidth + ellipsisWidth < w) + breakPoint = next; + } if (lineWidth > w) { *breakPoint = '\0'; @@ -61,7 +61,7 @@ namespace FTDI { cmd.apply_text_alignment(x, y, w, h, options); #if ENABLED(TOUCH_UI_USE_UTF8) - if (has_utf8_chars(str)) { + if (use_utf8) { draw_utf8_text(cmd, x, y, str, font_size_t::from_romfont(font), options); } else #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index 500551e862..1811779297 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -39,7 +39,7 @@ void DialogBoxBaseClass::drawMessage(T message, int16_t font) { .cmd(CLEAR(true,true,true)) .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,3), message, OPT_CENTER, font ? font : font_large); + draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,6), message, OPT_CENTER, font ? font : font_large); cmd.colors(normal_btn); } @@ -69,12 +69,6 @@ void DialogBoxBaseClass::drawButton(T label) { template void DialogBoxBaseClass::drawButton(const char *); template void DialogBoxBaseClass::drawButton(progmem_str); -void DialogBoxBaseClass::drawSpinner() { - CommandProcessor cmd; - cmd.cmd(COLOR_RGB(bg_text_enabled)) - .spinner(BTN_POS(1,4), BTN_SIZE(2,3)).execute(); -} - bool DialogBoxBaseClass::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); return true; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h index d48f3a03b3..c876409928 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h @@ -31,7 +31,6 @@ class DialogBoxBaseClass : public BaseScreen { template static void drawButton(T); static void drawYesNoButtons(uint8_t default_btn = 0); static void drawOkayButton(); - static void drawSpinner(); static void onRedraw(draw_mode_t) {}; public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp index ebefea2dcd..5b160c80df 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_settings_screen.cpp @@ -104,8 +104,8 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { #endif #undef EDGE_R #define EDGE_R 0 - #if ENABLED(TOUCH_UI_PORTRAIT) .colors(normal_btn) + #if ENABLED(TOUCH_UI_PORTRAIT) .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp index b951844196..889fd60684 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.cpp @@ -74,8 +74,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { #undef EDGE_R #define EDGE_R 30 .font(font_small) - .tag(0).text (BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) - .text (BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_CLICK_SOUNDS), OPT_RIGHTX | OPT_CENTERY) + .tag(0).text (BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_CLICK_SOUNDS), OPT_RIGHTX | OPT_CENTERY) .text (BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_STARTING), OPT_RIGHTX | OPT_CENTERY) .text (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_FINISHED), OPT_RIGHTX | OPT_CENTERY) .text (BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_PRINT_ERROR), OPT_RIGHTX | OPT_CENTERY); @@ -89,18 +88,16 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { constexpr uint8_t w = 1; #endif - cmd.font(font_medium) - .colors(ui_slider) + cmd.font(font_small) #define EDGE_R 30 - .tag(2).slider (BTN_POS(3,2), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .colors(ui_toggle) - .tag(3).toggle2 (BTN_POS(3,3), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::touch_sounds_enabled()) + .tag(2).toggle2 (BTN_POS(3,3), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::touch_sounds_enabled()) #undef EDGE_R .colors(normal_btn) #define EDGE_R 0 - .tag(4).button (BTN_POS(3,5), BTN_SIZE(2,1), getSoundSelection(PRINTING_STARTED)) - .tag(5).button (BTN_POS(3,6), BTN_SIZE(2,1), getSoundSelection(PRINTING_FINISHED)) - .tag(6).button (BTN_POS(3,7), BTN_SIZE(2,1), getSoundSelection(PRINTING_FAILED)) + .tag(3).button (BTN_POS(3,5), BTN_SIZE(2,1), getSoundSelection(PRINTING_STARTED)) + .tag(4).button (BTN_POS(3,6), BTN_SIZE(2,1), getSoundSelection(PRINTING_FINISHED)) + .tag(5).button (BTN_POS(3,7), BTN_SIZE(2,1), getSoundSelection(PRINTING_FAILED)) .colors(action_btn) .tag(1).button (BTN_POS(1,9), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); } @@ -114,10 +111,10 @@ void InterfaceSoundsScreen::onEntry() { bool InterfaceSoundsScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); return true; - case 3: UIData::enable_touch_sounds(!UIData::touch_sounds_enabled()); break; - case 4: toggleSoundSelection(PRINTING_STARTED); break; - case 5: toggleSoundSelection(PRINTING_FINISHED); break; - case 6: toggleSoundSelection(PRINTING_FAILED); break; + case 2: UIData::enable_touch_sounds(!UIData::touch_sounds_enabled()); break; + case 3: toggleSoundSelection(PRINTING_STARTED); break; + case 4: toggleSoundSelection(PRINTING_FINISHED); break; + case 5: toggleSoundSelection(PRINTING_FAILED); break; default: return false; } @@ -125,35 +122,4 @@ bool InterfaceSoundsScreen::onTouchEnd(uint8_t tag) { return true; } -bool InterfaceSoundsScreen::onTouchStart(uint8_t tag) { - CommandProcessor cmd; - #undef EDGE_R - #define EDGE_R 30 - switch (tag) { - case 2: cmd.track_linear(BTN_POS(3,2), BTN_SIZE(2,1), 2).execute(); break; - default: break; - } - return true; -} - -void InterfaceSoundsScreen::onIdle() { - if (refresh_timer.elapsed(TOUCH_UPDATE_INTERVAL)) { - refresh_timer.start(); - - uint16_t value; - CommandProcessor cmd; - switch (cmd.track_tag(value)) { - case 2: - screen_data.InterfaceSettingsScreen.volume = value >> 8; - SoundPlayer::set_volume(screen_data.InterfaceSettingsScreen.volume); - SaveSettingsDialogBox::settingsChanged(); - break; - default: - return; - } - onRefresh(); - } - BaseScreen::onIdle(); -} - #endif // FTDI_INTERFACE_SOUNDS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h index 046d7390fe..258fc77c26 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/interface_sounds_screen.h @@ -51,7 +51,5 @@ class InterfaceSoundsScreen : public BaseScreen, public CachedScreen { +class SpinnerDialogBox : public BaseScreen { public: static void onEntry(); + static void onExit(); static void onRedraw(draw_mode_t); + static void onRefresh(); static void onIdle(); static void show(progmem_str); From 8d454fd6f1241e23f70f7b5fc3fa668d20ee8a20 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 4 Aug 2021 01:04:15 +0000 Subject: [PATCH 0504/2168] [cron] Bump distribution date (2021-08-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 22151ed234..32fee40e25 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-03" +//#define STRING_DISTRIBUTION_DATE "2021-08-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a090c0c5ed..22a5f8e6e9 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 "2021-08-03" + #define STRING_DISTRIBUTION_DATE "2021-08-04" #endif /** From 53a5cd0c380851ceab9545c652d67d3d688cf693 Mon Sep 17 00:00:00 2001 From: Bob Anthony <42719046+bob-anthony@users.noreply.github.com> Date: Tue, 3 Aug 2021 23:45:08 -0500 Subject: [PATCH 0505/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20extra=20E=20move?= =?UTF-8?q?=20in=20toolchange=20with=20...=5FNO=5FRETURN=20(#22504)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/tool_change.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 5b478caa1a..6d69b8722d 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -954,11 +954,11 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #if ENABLED(TOOLCHANGE_PARK) if (ok) { #if ENABLED(TOOLCHANGE_NO_RETURN) - destination.set(current_position.x, current_position.y); - prepare_internal_move_to_destination(planner.settings.max_feedrate_mm_s[Z_AXIS]); - #else - prepare_internal_move_to_destination(MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE)); + const float temp = destination.z; + destination = current_position; + destination.z = temp.z; #endif + prepare_internal_move_to_destination(TERN(TOOLCHANGE_NO_RETURN, planner.settings.max_feedrate_mm_s[Z_AXIS], MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE))); } #endif From 0e065579aa81e1b285b12c5d8a8f579698ce47e7 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Wed, 4 Aug 2021 08:14:54 +0200 Subject: [PATCH 0506/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Longer3D=20STM32?= =?UTF-8?q?=20boot,=20add=20Maple=20test=20(#22473)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 3 +- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 9 +- .../MARLIN_F103VE_LONGER/PeripheralPins.c | 289 +++++++++++++++ .../MARLIN_F103VE_LONGER/PinNamesVar.h | 32 ++ .../MARLIN_F103VE_LONGER/hal_conf_custom.h | 348 ++++++++++++++++++ .../variants/MARLIN_F103VE_LONGER/ldscript.ld | 189 ++++++++++ .../variants/MARLIN_F103VE_LONGER/variant.cpp | 249 +++++++++++++ .../variants/MARLIN_F103VE_LONGER/variant.h | 175 +++++++++ ini/stm32f1.ini | 14 +- 9 files changed, 1299 insertions(+), 9 deletions(-) create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 5429f3eb95..e45bf42f29 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -61,7 +61,7 @@ jobs: - STM32F103RC_fysetc - STM32F103RC_meeb - jgaurora_a5s_a1 - - STM32F103VE_longer + - STM32F103VE_longer_maple #- mks_robin_maple - mks_robin_lite - mks_robin_pro @@ -75,6 +75,7 @@ jobs: - STM32F103RE_btt - STM32F103RE_btt_USB - STM32F103RET6_creality + - STM32F103VE_longer - STM32F407VE_black - STM32F401VE_STEVAL - BIGTREE_BTT002 diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index f9ec42b68e..bdf215fa8e 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -99,12 +99,19 @@ // Avoid nozzle heat and fan start before serial init #define BOARD_OPENDRAIN_MOSFETS -#define BOARD_PREINIT() { \ +#define BOARD_INIT_OD_PINS() { \ OUT_WRITE_OD(HEATER_0_PIN, 0); \ OUT_WRITE_OD(HEATER_BED_PIN, 0); \ OUT_WRITE_OD(FAN_PIN, 0); \ } +#ifdef MAPLE_STM32F1 + // Only Maple Framework allow that early + #define BOARD_PREINIT BOARD_INIT_OD_PINS +#else + #define BOARD_INIT BOARD_INIT_OD_PINS +#endif + // // PWM for a servo probe // Other servo devices are not supported on this board! diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c new file mode 100644 index 0000000000..ba4046d5f9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c @@ -0,0 +1,289 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F103V(F-G)Tx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Note: Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 +//{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 +//{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 +//{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 +//{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { +//{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 +//{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_I2C_SCL[] = { + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, AFIO_NONE)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { +#if 0 + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 1, 0)}, // TIM2_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM5_CH1 +#endif + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM2_CH2 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 2, 0)}, // TIM2_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM5_CH2 +#endif + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM2_CH3 + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 +#endif +#ifdef STM32F103xG + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 +#endif + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 +#else + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 +#endif +#if defined(STM32F103xG) + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 +#endif + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xG) + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 +#endif + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N +#if defined(STM32F103xG) + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 +#endif + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM1_CH3 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM1_CH4 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 3, 0)}, // TIM3_CH3 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM8_CH2N +#endif + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM8_CH3N +#endif + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 2, 0)}, // TIM2_CH2 + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_PARTIAL, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 +#if defined(STM32F103xG) + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 +#endif + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 +#if defined(STM32F103xG) + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 +#endif + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N +#if defined(STM32F103xG) + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 +#endif + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N +#if defined(STM32F103xG) + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 +#endif + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 +#endif + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 2, 0)}, // TIM3_CH2 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM8_CH2 +#endif + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 3, 0)}, // TIM3_CH3 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 4, 0)}, // TIM3_CH4 +#if defined(STM32F103xE) || defined(STM32F103xG) + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM8_CH4 +#endif + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 4, 0)}, // TIM4_CH4 +#if defined(STM32F103xG) + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM9_ENABLE, 1, 0)}, // TIM9_CH1 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM9_ENABLE, 2, 0)}, // TIM9_CH2 +#endif + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 4, 0)}, // TIM1_CH4 +#endif // if 0 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, +//{PB_11, USART3, STM_PIN_DATA(STM_MODE_INPUT, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RTS[] = { + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_CTS[] = { + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SSEL[] = { +//{PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, +//{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, + {NC, NP, 0} +}; + +//*** No CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_CAN_TD[] = { + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB[] = { + {PA_11, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DM + {PA_12, USB, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, AFIO_NONE)}, // USB_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_FS *** + +//*** No USB_OTG_HS *** + +//*** SD *** + +#if defined(STM32F103xE) || defined(STM32F103xG) +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { +//{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D4 +//{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D5 +//{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D6 +//{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, AFIO_NONE)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h new file mode 100644 index 0000000000..9c07918364 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PinNamesVar.h @@ -0,0 +1,32 @@ +/* SYS_WKUP */ +#if defined(PWR_WAKEUP_PIN1) && defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) + #error PA0 is used by thermal sensor, disable low power wake with -DHAL_PWR_MODULE_ONLY + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + #warning USB feature is not required with a CH340 chip + USB_DM = PA_11, + USB_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h new file mode 100644 index 0000000000..e2247addb9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h @@ -0,0 +1,348 @@ +/** + ****************************************************************************** + * @file hal_conf_custom.h for Longer3D STM32F103VE board + * @brief Overrides HAL default configuration file. + ****************************************************************************** + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief Include the default list of modules to be used in the HAL driver + * and manage module deactivation + */ +#include "stm32yyxx_hal_conf.h" + +#ifdef HAL_PWR_MODULE_ENABLED + #undef HAL_PWR_MODULE_ENABLED // only way to disable it +#endif + +#if defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) + #define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) +#endif + +#ifndef HAL_IWDG_MODULE_ENABLED + #define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG +#endif + +#ifdef HAL_PCD_MODULE_ENABLED + #warning No direct STM32 USB pins on Longer3D board + #undef HAL_PCD_MODULE_ENABLED // USB Device +#endif + +#ifdef HAL_HCD_MODULE_ENABLED + #warning No direct STM32 USB pins on Longer3D board + #undef HAL_HCD_MODULE_ENABLED // USB Host +#endif + +#ifndef HAL_USART_MODULE_ENABLED + //#define HAL_USART_MODULE_ENABLED // Useless.... UART_MODULE do it +#endif + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #undef HAL_CAN_LEGACY_MODULE_ENABLED +#endif + +#ifdef HAL_CAN_MODULE_ENABLED + #undef HAL_CAN_MODULE_ENABLED +#endif + +#ifdef HAL_DAC_MODULE_ENABLED + #undef HAL_DAC_MODULE_ENABLED +#endif + +#ifdef HAL_RTC_MODULE_ENABLED + #undef HAL_RTC_MODULE_ENABLED +#endif + +#ifndef HAL_EXTI_MODULE_ENABLED + #define HAL_EXTI_MODULE_ENABLED // for ENDSTOP_INTERRUPTS_FEATURE +#endif + +/** + * @brief List of modules in the framework (first ones enabled by default) + */ +//#define HAL_MODULE_ENABLED +//#define HAL_ADC_MODULE_ENABLED +//#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DMA_MODULE_ENABLED +//#define HAL_FLASH_MODULE_ENABLED +//#define HAL_GPIO_MODULE_ENABLED +//#define HAL_I2C_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED +//#define HAL_PWR_MODULE_ENABLED +//#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +//#define HAL_SPI_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_TIM_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED + +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#ifndef HSE_VALUE + #define HSE_VALUE 8000000U // Value of the External oscillator in Hz (8 MHz) +#endif + +#ifndef HSE_STARTUP_TIMEOUT + #define HSE_STARTUP_TIMEOUT 100U // Time out for HSE start up, in ms +#endif + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#ifndef HSI_VALUE + #define HSI_VALUE 8000000U // Value of the Internal oscillator in Hz +#endif + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#ifndef LSI_VALUE + #define LSI_VALUE 40000U // LSI Typical Value in Hz +#endif /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#ifndef LSE_VALUE + #define LSE_VALUE 32768U // Value of the External Low Speed oscillator in Hz +#endif + +#ifndef LSE_STARTUP_TIMEOUT + #define LSE_STARTUP_TIMEOUT 50U // No 32.7KHz LSE on this board, reduced to avoid delays +#endif + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#ifndef VDD_VALUE + #define VDD_VALUE 3300U // Value of VDD in mv +#endif +#ifndef TICK_INT_PRIORITY + #define TICK_INT_PRIORITY 0x00U // tick interrupt priority +#endif +#ifndef USE_RTOS + #define USE_RTOS 0U +#endif +#ifndef PREFETCH_ENABLE + #define PREFETCH_ENABLE 1U +#endif + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ +#if !defined(USE_SPI_CRC) +#define USE_SPI_CRC 0 +#endif + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f1xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f1xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32f1xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f1xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f1xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f1xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32f1xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f1xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f1xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f1xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f1xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f1xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f1xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f1xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f1xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f1xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f1xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f1xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f1xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f1xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f1xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f1xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f1xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f1xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f1xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f1xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f1xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f1xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f1xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f1xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f1xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32f1xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + + +#define assert_param(expr) ((void)0U) + +#ifdef __cplusplus +} +#endif + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld new file mode 100644 index 0000000000..6bc577236a --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/ldscript.ld @@ -0,0 +1,189 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : Auto-generated by STM32CubeIDE +** +** Abstract : Linker script for STM32F103V(8/B/C/E/F/GTx Device from STM32F1 series +** 64/128/256/512/768/1024Kbytes FLASH +** 20/20/48/64/64/96/96Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed as is without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of "RAM" Ram type memory */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp new file mode 100644 index 0000000000..007ef81065 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.cpp @@ -0,0 +1,249 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, //D0 + PA_1, //D1 + PA_2, //D2 + PA_3, //D3 + PA_4, //D4 + PA_5, //D5 + PA_6, //D6 + PA_7, //D7 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + + PB_0, //D16 + PB_1, //D17 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_11, //D27 + PB_12, //D28 + PB_13, //D29 + PB_14, //D30 + PB_15, //D31 + + PC_0, //D32 + PC_1, //D33 + PC_2, //D34 + PC_3, //D35 + PC_4, //D36 + PC_5, //D37 + PC_6, //D38 + PC_7, //D39 + PC_8, //D40 + PC_9, //D41 + PC_10, //D42 + PC_11, //D43 + PC_12, //D44 + PC_13, //D45 + PC_14, //D46 + PC_15, //D47 + + PD_0, //D48 + PD_1, //D49 + PD_2, //D50 + PD_3, //D51 + PD_4, //D52 + PD_5, //D53 + PD_6, //D54 + PD_7, //D55 + PD_8, //D56 + PD_9, //D57 + PD_10, //D58 + PD_11, //D59 + PD_12, //D60 + PD_13, //D61 + PD_14, //D62 + PD_15, //D63 + + PE_0, //D64 + PE_1, //D65 + PE_2, //D66 + PE_3, //D67 + PE_4, //D68 + PE_5, //D69 + PE_6, //D70 + PE_7, //D71 + PE_8, //D72 + PE_9, //D73 + PE_10, //D74 + PE_11, //D75 + PE_12, //D76 + PE_13, //D77 + PE_14, //D78 + PE_15, //D79 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37, // A15, PC5 +}; + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ +static bool SetSysClock_PLL_HSE(bool bypass) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + bool ret = false; + + // Initializes the CPU, AHB and APB busses clocks + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + if (bypass == false) { + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + } else { + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + } + RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; // 8Mhz x 9 = 72MHz + + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) == HAL_OK) { + // Initializes the CPU, AHB and APB busses clocks + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) == HAL_OK) { + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; // 72/1.5 = 48MHz + #ifndef USBCON + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; + #endif + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) == HAL_OK) { + ret = true; + } + } + } + return ret; +} + +/******************************************************************************/ +/* PLL (clocked by HSI) used as System clock source (64MHz max) */ +/******************************************************************************/ +bool SetSysClock_PLL_HSI(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {}; + bool ret = false; + + // Initializes the CPU, AHB and APB busses clocks + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSEState = RCC_HSE_OFF; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2; // 4 MHz + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL12; // 48 MHz + #ifndef USBCON + // When the HSI is used as a PLL clock input, the maximum + // system clock frequency that can be achieved is 64 MHz. + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16; // 64 MHz, stay close to 72 for delay() + #endif + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) == HAL_OK) { + // Initializes the CPU, AHB and APB busses clocks + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + // FLASH_LATENCY_1 may cause boot loops + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) == HAL_OK) { + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC | RCC_PERIPHCLK_USB; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV4; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL; // requires 48 MHz + #ifndef USBCON + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;// No USB, RTC nor I2S + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; // 2 4 6 8 + #endif + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) == HAL_OK) { + ret = true; + } + } + } + return ret; +} + +void SystemClock_Config(void) +{ + /* + * If HSE_VALUE is not 8MHz and you want use it, then: + * - Redefine HSE_VALUE to the correct HSE_VALUE + * - Redefine SystemClock_Config() with the correct settings + */ +#if HSE_VALUE == 8000000U + // 1- Try to start with HSE and external 8MHz xtal + if (SetSysClock_PLL_HSE(false) == false) { + // 2- If fail try to start with HSE and external clock + if (SetSysClock_PLL_HSE(true) == false) { +#endif + // 3- If fail start with HSI clock + if (SetSysClock_PLL_HSI() == false) { + Error_Handler(); + } +#if HSE_VALUE == 8000000U + } + } +#endif +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h new file mode 100644 index 0000000000..b0f2ddf0c2 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h @@ -0,0 +1,175 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +// STM32F103VET6 | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | +//------------------|-------------|---------------|------------|-----------|----------------------|------------| +#define PA0 0 // | | A0 Nozzle T°c | | | | | +#define PA1 1 // | | A1 Bed T°c | | | | | +#define PA2 2 // | | | USART2_TX | | | | +#define PA3 3 // | | DAC_OUT1** | USART2_RX | | | | +#define PA4 4 // | | DAC_OUT2** | | | SPI1_SS*(wired?) | | +#define PA5 5 // | O | | | | SPI1_SCK EEPROM | | +#define PA6 6 // | I | | | | SPI1_MISO EEPROM | | +#define PA7 7 // | O | | | | SPI1_MOSI EEPROM | | +#define PA8 8 // | Od BED | | | | | | +#define PA9 9 // | | | USART1_TX | | | | +#define PA10 10 // | | | USART1_RX | | | | +#define PA11 11 // | I | | | | | USB_DM | +#define PA12 12 // | I | | | | | USB_DP | +#define PA13 13 // | I | | | | | SWD_SWDIO | +#define PA14 14 // | I | | | | | SWD_SWCLK | +#define PA15 15 // | Od FAN | | | | | | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PB0 16 // | | | | | | | +#define PB1 17 // | | | | | | | +#define PB2 18 // | I+ | | | | | BOOT1 | +#define PB3 19 // | O X_DIR | | | | | | +#define PB4 20 // | O X_STEP | | | | | | +#define PB5 21 // | O X_EN | | | | | | +#define PB6 22 // | O Y_DIR | | | | | | +#define PB7 23 // | O Y_STEP | | | | | | +#define PB8 24 // | O Y_EN | | | | | | +#define PB9 25 // | O Z_DIR | | | | | | +#define PB10 26 // | I+ | | USART3_TX* | TWI2_SCL* | | | +#define PB11 27 // | I+ | | USART3_RX* | TWI2_SDA* | | | +#define PB12 28 // | O TFT | | | | SPI2_SS | TOUCH_CS | +#define PB13 29 // | O TFT | | | | SPI2_SCK | TOUCH_SCK | +#define PB14 30 // | O TFT | | | | SPI2_MISO (bad>MOSI) | TOUCH_MOSI | +#define PB15 31 // | I TFT | | | | SPI2_MOSI (bad>MISO) | TOUCH_MISO | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PC0 32 // | I E_OUT | | | | | | +#define PC1 33 // | I+ X_MIN | | | | | | +#define PC2 34 // | O LED | | | | | | +#define PC3 35 // | I+ | | | | | | +#define PC4 36 // | O TFT | | | | | TFT RESET | +#define PC5 37 // | O CS1 | | | | for SPI1 EEPROM CS | | +#define PC6 38 // | I TFT | | | | | TOUCH_INT | +#define PC7 39 // | | | | | | | +#define PC8 40 // | x SDIO | | | | | SD_D0 | +#define PC9 41 // | x SDIO | | | | | SD_D1 | +#define PC10 42 // | x SDIO | | | | | SD_D2 | +#define PC11 43 // | x SDIO | | | | | SD_D3 | +#define PC12 44 // | O SDIO | | | | | SD_CLK | +#define PC13 45 // | I | | | | | | +#define PC14 46 // | I+ Y_MAX | | | | | | +#define PC15 47 // | I+ Y_MIN | | | | | | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PD0 48 // | O TFT | | | | | OSC_IN D2 | +#define PD1 49 // | O TFT | | | | | OSC_OUT D3 | +#define PD2 50 // | O SDIO | | | | | SD_CMD | +#define PD3 51 // | Od NOZZLE | | | | | | +#define PD4 52 // | O TFT | | | | | FSMC_NOE | +#define PD5 53 // | O TFT | | | | | FSMC_NWE | +#define PD6 54 // | I wired?* | | | | | FSMC_NWAIT*| +#define PD7 55 // | O TFT | | | | | FSMC_NE1/CS| +#define PD8 56 // | O TFT | | | | | FSMC_D13 | +#define PD9 57 // | O TFT | | | | | FSMC_D14 | +#define PD10 58 // | O TFT | | | | | FSMC_D15 | +#define PD11 59 // | O TFT | | | | | FSMC_A16 | +#define PD12 60 // | O TFT | | | | | TFT BL | +#define PD13 61 // | Od PWM* | | | | | SERVO0 | +#define PD14 62 // | O TFT | | | | | FSMC_D00 | +#define PD15 63 // | O TFT | | | | | FSMC_D01 | +// |-------------|---------------|------------|-----------|----------------------|------------| +#define PE0 64 // | O Z_STEP | | | | | | +#define PE1 65 // | O Z_EN | | | | | | +#define PE2 66 // | O E0_DIR | | | | | | +#define PE3 67 // | O E0_STEP | | | | | | +#define PE4 68 // | O E0_EN | | | | | | +#define PE5 69 // | I+ Z_MAX | | | | | | +#define PE6 70 // | I+ Z_MIN | | | | | | +#define PE7 71 // | O TFT | | | | | FSMC_D04 | +#define PE8 72 // | O TFT | | | | | FSMC_D05 | +#define PE9 73 // | O TFT | | | | | FSMC_D06 | +#define PE10 74 // | O TFT | | | | | FSMC_D07 | +#define PE11 75 // | O TFT | | | | | FSMC_D08 | +#define PE12 76 // | O TFT | | | | | FSMC_D09 | +#define PE13 77 // | O TFT | | | | | FSMC_D10 | +#define PE14 78 // | O TFT | | | | | FSMC_D11 | +#define PE15 79 // | O TFT | | | | | FSMC_D12 | +//------------------|-------------|---------------|------------|-----------|----------------------|------------| + +// This must be a literal +#define NUM_DIGITAL_PINS 80 +#define NUM_ANALOG_INPUTS 16 // 2 first are used, but cant be reduced to 2... + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PC2 +#endif + +// On-board user button (not wired) +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// SPI Definition (SPI1 EEPROM) +#define PIN_SPI_SS PC5 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + +// I2C Definition (Unused) +#define PIN_WIRE_SDA PB11 +#define PIN_WIRE_SCL PB10 + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial' instance (linked to CH340 USB port) +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +// Default pin used for 'Serial2' instance (connector exists but unsoldered) +#define PIN_SERIAL2_RX PA3 +#define PIN_SERIAL2_TX PA2 + +// Extra HAL modules +#if defined(STM32F103xE) +//#define HAL_DAC_MODULE_ENABLED (unused or maybe for the eeprom write?) +#define HAL_SD_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +#endif + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #define SERIAL_PORT_MONITOR Serial1 + #define SERIAL_PORT_HARDWARE Serial1 + #define SERIAL_PORT_HARDWARE_OPEN Serial2 +#endif + diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 029763b9ed..1185e8f84d 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -330,19 +330,19 @@ upload_protocol = serial # [env:STM32F103VE_longer] platform = ${common_stm32.platform} +lib_deps = ${common.lib_deps} + https://github.com/tpruvot/STM32_Servo_OpenDrain/archive/2.0.zip extends = stm32_variant board = genericSTM32F103VE -board_build.variant = MARLIN_F103Vx +board_build.variant = MARLIN_F103VE_LONGER board_build.rename = project.bin board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 -build_flags = ${stm32_variant.build_flags} - -DMCU_STM32F103VE -DU20 -DTS_V12 -DLED_BUILTIN=PC2 -UPIN_WIRE_SDA - -UPIN_WIRE_SCL -DPIN_WIRE_SDA=PB11 -DPIN_WIRE_SCL=PB10 - -DHAL_DAC_MODULE_DISABLED -DHAL_I2S_MODULE_DISABLED -build_unflags = ${stm32_variant.build_unflags} - -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED +build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED extra_scripts = ${stm32_variant.extra_scripts} +monitor_speed = 250000 +debug_tool = stlink # # TRIGORILLA PRO (STM32F103ZET6) From 9130f58f3f553584278ec716c617005b9e03cb49 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 4 Aug 2021 16:37:02 -0500 Subject: [PATCH 0507/2168] =?UTF-8?q?=F0=9F=90=9B=20Prevent=20ABL=20G29=20?= =?UTF-8?q?setting=20a=20funky=20feedrate?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #22472 --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 ++ Marlin/src/module/motion.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 29009c6e2d..18e3862128 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -363,6 +363,8 @@ G29_TYPE GcodeSuite::G29() { #if ABL_USES_GRID xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE)); + if (!xy_probe_feedrate_mm_s) xy_probe_feedrate_mm_s = PLANNER_XY_FEEDRATE(); + NOLESS(xy_probe_feedrate_mm_s, planner.settings.min_feedrate_mm_s); const float x_min = probe.min_x(), x_max = probe.max_x(), y_min = probe.min_y(), y_max = probe.max_y(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index eb6dc6597c..838605cd54 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -483,7 +483,7 @@ void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS()); - const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); + const feedRate_t xy_feedrate = fr_mm_s ?: PLANNER_XY_FEEDRATE(); #if HAS_Z_AXIS const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); From c2c7a03706e54d1ce4441a39ca8343755bceac06 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 4 Aug 2021 17:01:42 -0500 Subject: [PATCH 0508/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20report=5Fa=5Fpos?= =?UTF-8?q?ition=20ABC=20criteria?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 0ff909d7cc..b8fdaa5f76 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2825,19 +2825,22 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } -#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) - #define USES_ABC 1 +#if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, IS_SCARA, DELTA) + #define SAYS_A 1 #endif -#if ANY(USES_ABC, MARKFORGED_XY, IS_SCARA) - #define USES_AB 1 +#if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, IS_SCARA, DELTA) + #define SAYS_B 1 +#endif +#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) + #define SAYS_C 1 #endif void Stepper::report_a_position(const xyz_long_t &pos) { SERIAL_ECHOLNPAIR_P( LIST_N(DOUBLE(LINEAR_AXES), - TERN(USES_AB, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, - TERN(USES_AB, PSTR("B:"), SP_Y_LBL), pos.y, - TERN(USES_ABC, PSTR("C:"), SP_Z_LBL), pos.z, + TERN(SAYS_A, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, + TERN(SAYS_B, PSTR("B:"), SP_Y_LBL), pos.y, + TERN(SAYS_C, PSTR("C:"), SP_Z_LBL), pos.z, SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k From b06d2f789b4a36da47869268c297c409c13b8889 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 5 Aug 2021 00:58:49 +0000 Subject: [PATCH 0509/2168] [cron] Bump distribution date (2021-08-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 32fee40e25..b287939d58 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-04" +//#define STRING_DISTRIBUTION_DATE "2021-08-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 22a5f8e6e9..c6add72a50 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 "2021-08-04" + #define STRING_DISTRIBUTION_DATE "2021-08-05" #endif /** From 5cb961e98b6d659a9acad3a88126baa14faec35f Mon Sep 17 00:00:00 2001 From: Vert <45634861+Vertabreak@users.noreply.github.com> Date: Thu, 5 Aug 2021 00:45:49 -0400 Subject: [PATCH 0510/2168] =?UTF-8?q?=E2=9C=A8=20Mixer=20Presets=20(#21562?= =?UTF-8?q?)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/feature/mixing.cpp | 23 +++++++++++++++++++++-- 2 files changed, 22 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 239ee220b2..d01fc98b40 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -342,6 +342,7 @@ #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands //#define GRADIENT_MIX // Support for gradient mixing with M166 and LCD + //#define MIXING_PRESETS // Assign 8 default V-tool presets for 2 or 3 MIXING_STEPPERS #if ENABLED(GRADIENT_MIX) //#define GRADIENT_VTOOL // Add M166 T to use a V-tool index as a Gradient alias #endif diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 4823ac2c60..332a4f3740 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -106,11 +106,32 @@ void Mixer::reset_vtools() { MIXER_STEPPER_LOOP(i) color[t][i] = (i == 0) ? COLOR_A_MASK : 0; #endif + + // MIXING_PRESETS: Set a variety of obvious mixes as presets + #if ENABLED(MIXING_PRESETS) && WITHIN(MIXING_STEPPERS, 2, 3) + #if MIXING_STEPPERS == 2 + if (MIXING_VIRTUAL_TOOLS > 2) { collector[0] = 1; collector[1] = 1; mixer.normalize(2); } // 1:1 + if (MIXING_VIRTUAL_TOOLS > 3) { collector[0] = 3; mixer.normalize(3); } // 3:1 + if (MIXING_VIRTUAL_TOOLS > 4) { collector[0] = 1; collector[1] = 3; mixer.normalize(4); } // 1:3 + if (MIXING_VIRTUAL_TOOLS > 5) { collector[1] = 2; mixer.normalize(5); } // 1:2 + if (MIXING_VIRTUAL_TOOLS > 6) { collector[0] = 2; collector[1] = 1; mixer.normalize(6); } // 2:1 + if (MIXING_VIRTUAL_TOOLS > 7) { collector[0] = 3; collector[1] = 2; mixer.normalize(7); } // 3:2 + #else + if (MIXING_VIRTUAL_TOOLS > 3) { collector[0] = 1; collector[1] = 1; collector[2] = 1; mixer.normalize(3); } // 1:1:1 + if (MIXING_VIRTUAL_TOOLS > 4) { collector[1] = 3; collector[2] = 0; mixer.normalize(4); } // 1:3:0 + if (MIXING_VIRTUAL_TOOLS > 5) { collector[0] = 0; collector[2] = 1; mixer.normalize(5); } // 0:3:1 + if (MIXING_VIRTUAL_TOOLS > 6) { collector[1] = 1; mixer.normalize(6); } // 0:1:1 + if (MIXING_VIRTUAL_TOOLS > 7) { collector[0] = 1; collector[2] = 0; mixer.normalize(7); } // 1:1:0 + #endif + ZERO(collector); + #endif } // called at boot void Mixer::init() { + ZERO(collector); + reset_vtools(); #if HAS_MIXER_SYNC_CHANNEL @@ -119,8 +140,6 @@ void Mixer::init() { color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK; #endif - ZERO(collector); - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) update_mix_from_vtool(); #endif From f35e0b9382c6df1f98a4c3ba34b10a8077432e56 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 5 Aug 2021 06:47:31 +0200 Subject: [PATCH 0511/2168] =?UTF-8?q?=F0=9F=9A=B8=20Prevent=20M42=20uninte?= =?UTF-8?q?nded=20pin=20change=20to=20output=20(#22493)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/control/M42.cpp | 36 ++++++++++++++++++++++++++++---- 1 file changed, 32 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 6ef8455e0b..908260ed25 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -31,6 +31,13 @@ #include "../../module/temperature.h" #endif +#ifdef MAPLE_STM32F1 + // these are enums on the F1... + #define INPUT_PULLDOWN INPUT_PULLDOWN + #define INPUT_ANALOG INPUT_ANALOG + #define OUTPUT_OPEN_DRAIN OUTPUT_OPEN_DRAIN +#endif + void protected_pin_err() { SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); } @@ -55,13 +62,20 @@ void GcodeSuite::M42() { if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); + bool avoidWrite = false; if (parser.seenval('M')) { switch (parser.value_byte()) { - case 0: pinMode(pin, INPUT); break; + case 0: pinMode(pin, INPUT); avoidWrite = true; break; case 1: pinMode(pin, OUTPUT); break; - case 2: pinMode(pin, INPUT_PULLUP); break; + case 2: pinMode(pin, INPUT_PULLUP); avoidWrite = true; break; #ifdef INPUT_PULLDOWN - case 3: pinMode(pin, INPUT_PULLDOWN); break; + case 3: pinMode(pin, INPUT_PULLDOWN); avoidWrite = true; break; + #endif + #ifdef INPUT_ANALOG + case 4: pinMode(pin, INPUT_ANALOG); avoidWrite = true; break; + #endif + #ifdef OUTPUT_OPEN_DRAIN + case 5: pinMode(pin, OUTPUT_OPEN_DRAIN); break; #endif default: SERIAL_ECHOLNPGM("Invalid Pin Mode"); return; } @@ -99,8 +113,22 @@ void GcodeSuite::M42() { } #endif - pinMode(pin, OUTPUT); + if (avoidWrite) { + SERIAL_ECHOLNPGM("?Cannot write to INPUT"); + return; + } + + // An OUTPUT_OPEN_DRAIN should not be changed to normal OUTPUT (STM32) + // Use M42 Px M1/5 S0/1 to set the output type and then set value + #ifndef OUTPUT_OPEN_DRAIN + pinMode(pin, OUTPUT); + #endif extDigitalWrite(pin, pin_status); + + #ifdef ARDUINO_ARCH_STM32 + // A simple I/O will be set to 0 by analogWrite() + if (pin_status <= 1) return; + #endif analogWrite(pin, pin_status); } From b55cf3c9f6f6199d665f9db424b28f7395f158f4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 5 Aug 2021 00:19:21 -0500 Subject: [PATCH 0512/2168] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20BLTouch=20spelli?= =?UTF-8?q?ng?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/tft_Language_en.h | 2 +- Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h | 2 +- Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h index b6eef18368..e1a2a256d9 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h @@ -105,7 +105,7 @@ #define LEVELING_PARA_CONF_TITLE_EN "leveling setting" #define AUTO_LEVELING_ENABLE_EN "Enable auto leveling" -#define BLTOUCH_LEVELING_ENABLE_EN "Enable BLtouch" +#define BLTOUCH_LEVELING_ENABLE_EN "Enable BLTouch" #define PROBE_PORT_EN "Probe connector" #define PROBE_X_OFFSET_EN "Probe X-axis offset" #define PROBE_Y_OFFSET_EN "Probe Y-axis offset" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h index b50761fde0..59de8c7db9 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_s_cn.h @@ -90,7 +90,7 @@ #define LEVELING_PARA_CONF_TITLE_CN "调平参数" #define AUTO_LEVELING_ENABLE_CN "自动调平" -#define BLTOUCH_LEVELING_ENABLE_CN "启动BLtouch" +#define BLTOUCH_LEVELING_ENABLE_CN "启动BLTouch" #define PROBE_PORT_CN "调平探针接口" #define PROBE_X_OFFSET_CN "探针X方向偏移" #define PROBE_Y_OFFSET_CN "探针Y方向偏移" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h index 3f58a9afd2..c9607187ef 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_t_cn.h @@ -90,7 +90,7 @@ #define LEVELING_PARA_CONF_TITLE_T_CN "調平參數" #define AUTO_LEVELING_ENABLE_T_CN "自動調平" -#define BLTOUCH_LEVELING_ENABLE_T_CN "啟動BLtouch" +#define BLTOUCH_LEVELING_ENABLE_T_CN "啟動BLTouch" #define PROBE_PORT_T_CN "調平探針接口" #define PROBE_X_OFFSET_T_CN "探針X方向偏移" #define PROBE_Y_OFFSET_T_CN "探针Y方向偏移" From 03b0a6371dcdee90846c5838a5b59a7e5ce57505 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 5 Aug 2021 15:03:26 -0500 Subject: [PATCH 0513/2168] =?UTF-8?q?=F0=9F=8E=A8=20Simplify=20endstops=20?= =?UTF-8?q?flags=20(#22525)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 73 ++++++++++++++---------------- 1 file changed, 34 insertions(+), 39 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index e25229c198..0f33b4799d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2122,83 +2122,78 @@ #define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_) #define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M)) -#if BOTH(X_HOME_TO_MIN, USE_XMIN_PLUG) && _HAS_STOP(X,MIN) +#if _HAS_STOP(X,MIN) #define HAS_X_MIN 1 #endif -#if (BOTH(X_HOME_TO_MAX, USE_XMAX_PLUG) || ENABLED(DUAL_X_CARRIAGE)) && _HAS_STOP(X,MAX) +#if _HAS_STOP(X,MAX) #define HAS_X_MAX 1 #endif -#if ALL(HAS_Y_AXIS, Y_HOME_TO_MIN, USE_YMIN_PLUG) && _HAS_STOP(Y,MIN) +#if _HAS_STOP(Y,MIN) #define HAS_Y_MIN 1 #endif -#if ALL(HAS_Y_AXIS, Y_HOME_TO_MAX, USE_YMAX_PLUG) && _HAS_STOP(Y,MAX) +#if _HAS_STOP(Y,MAX) #define HAS_Y_MAX 1 #endif -#if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN) +#if _HAS_STOP(Z,MIN) #define HAS_Z_MIN 1 #endif -#if ALL(HAS_Z_AXIS, Z_HOME_TO_MAX, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX) +#if _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif -#if LINEAR_AXES >= 4 && BOTH(I_HOME_TO_MIN, USE_IMIN_PLUG) && _HAS_STOP(I,MIN) +#if _HAS_STOP(I,MIN) #define HAS_I_MIN 1 #endif -#if LINEAR_AXES >= 4 && BOTH(I_HOME_TO_MAX, USE_IMAX_PLUG) && _HAS_STOP(I,MAX) +#if _HAS_STOP(I,MAX) #define HAS_I_MAX 1 #endif -#if LINEAR_AXES >= 5 && BOTH(J_HOME_TO_MIN, USE_JMIN_PLUG) && _HAS_STOP(J,MIN) +#if _HAS_STOP(J,MIN) #define HAS_J_MIN 1 #endif -#if LINEAR_AXES >= 5 && BOTH(J_HOME_TO_MAX, USE_JMAX_PLUG) && _HAS_STOP(J,MAX) +#if _HAS_STOP(J,MAX) #define HAS_J_MAX 1 #endif -#if LINEAR_AXES >= 6 && BOTH(K_HOME_TO_MIN, USE_KMIN_PLUG) && _HAS_STOP(K,MIN) +#if _HAS_STOP(K,MIN) #define HAS_K_MIN 1 #endif -#if LINEAR_AXES >= 6 && BOTH(K_HOME_TO_MAX, USE_KMAX_PLUG) && _HAS_STOP(K,MAX) +#if _HAS_STOP(K,MAX) #define HAS_K_MAX 1 #endif -#if BOTH(X_HOME_TO_MIN, X_DUAL_ENDSTOPS) && PIN_EXISTS(X2_MIN) +#if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif -#if BOTH(X_HOME_TO_MAX, X_DUAL_ENDSTOPS) && PIN_EXISTS(X2_MAX) +#if PIN_EXISTS(X2_MAX) #define HAS_X2_MAX 1 #endif -#if BOTH(Y_HOME_TO_MIN, Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y2_MIN) +#if PIN_EXISTS(Y2_MIN) #define HAS_Y2_MIN 1 #endif -#if BOTH(Y_HOME_TO_MAX, Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y2_MAX) +#if PIN_EXISTS(Y2_MAX) #define HAS_Y2_MAX 1 #endif -#if ENABLED(Z_MULTI_ENDSTOPS) - #if Z_HOME_TO_MIN && PIN_EXISTS(Z2_MIN) - #define HAS_Z2_MIN 1 - #endif - #if Z_HOME_TO_MAX && PIN_EXISTS(Z2_MAX) - #define HAS_Z2_MAX 1 - #endif - #if NUM_Z_STEPPER_DRIVERS >= 3 - #if Z_HOME_TO_MIN && PIN_EXISTS(Z3_MIN) - #define HAS_Z3_MIN 1 - #endif - #if Z_HOME_TO_MAX && PIN_EXISTS(Z3_MAX) - #define HAS_Z3_MAX 1 - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - #if Z_HOME_TO_MIN && PIN_EXISTS(Z4_MIN) - #define HAS_Z4_MIN 1 - #endif - #if Z_HOME_TO_MAX && PIN_EXISTS(Z4_MAX) - #define HAS_Z4_MAX 1 - #endif - #endif - #endif +#if PIN_EXISTS(Z2_MIN) + #define HAS_Z2_MIN 1 +#endif +#if PIN_EXISTS(Z2_MAX) + #define HAS_Z2_MAX 1 +#endif +#if PIN_EXISTS(Z3_MIN) + #define HAS_Z3_MIN 1 +#endif +#if PIN_EXISTS(Z3_MAX) + #define HAS_Z3_MAX 1 +#endif +#if PIN_EXISTS(Z4_MIN) + #define HAS_Z4_MIN 1 +#endif +#if PIN_EXISTS(Z4_MAX) + #define HAS_Z4_MAX 1 #endif #if HAS_BED_PROBE && PIN_EXISTS(Z_MIN_PROBE) #define HAS_Z_MIN_PROBE_PIN 1 #endif +#undef _HAS_STOP #undef IS_PROBE_PIN #undef IS_X2_ENDSTOP #undef IS_Y2_ENDSTOP From ff3db550ee397286c7b9f3bf546c0f4fba161682 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 6 Aug 2021 01:02:27 +0000 Subject: [PATCH 0514/2168] [cron] Bump distribution date (2021-08-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b287939d58..c65e3c3f44 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-05" +//#define STRING_DISTRIBUTION_DATE "2021-08-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c6add72a50..d87990ca67 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 "2021-08-05" + #define STRING_DISTRIBUTION_DATE "2021-08-06" #endif /** From 526b6cdf5b429cf05579bd203a9d72cd057bf0a1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 5 Aug 2021 23:24:20 -0500 Subject: [PATCH 0515/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20fan=20index=20fo?= =?UTF-8?q?r=20Singlenozzle,=20chamber=20fan?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22512 Followup to #19152, #19519 --- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/module/temperature.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 9ced6e4e42..a2fdc9856e 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2002,7 +2002,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if REDUNDANT_TEMP_MATCH(SOURCE, E0) && HAS_HOTEND - #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be E0 if a hotend is used. E0 always uses TEMP_SENSOR_0." #elif REDUNDANT_TEMP_MATCH(SOURCE, COOLER) && HAS_TEMP_COOLER #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be COOLER. TEMP_SENSOR_COOLER is in use." #elif REDUNDANT_TEMP_MATCH(SOURCE, PROBE) && HAS_TEMP_PROBE diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1e91511f5a..52d0dfb56e 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -369,7 +369,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, } #endif - TERN_(SINGLENOZZLE, fan = 0); // Always use fan index 0 with SINGLENOZZLE + TERN_(SINGLENOZZLE, if (fan < EXTRUDERS) fan = 0); // Always fan 0 for SINGLENOZZLE E fan if (fan >= FAN_COUNT) return; @@ -1481,7 +1481,7 @@ void Temperature::manage_heater() { fan_chamber_pwm = CHAMBER_FAN_BASE + _MAX((CHAMBER_FAN_FACTOR) * (temp_chamber.celsius - temp_chamber.target), 0); #endif NOMORE(fan_chamber_pwm, 225); - set_fan_speed(2, fan_chamber_pwm); // TODO: instead of fan 2, set to chamber fan + set_fan_speed(CHAMBER_FAN_INDEX, fan_chamber_pwm); // TODO: instead of fan 2, set to chamber fan #endif #if ENABLED(CHAMBER_VENT) @@ -1512,7 +1512,7 @@ void Temperature::manage_heater() { else if (!flag_chamber_off) { #if ENABLED(CHAMBER_FAN) flag_chamber_off = true; - set_fan_speed(2, 0); + set_fan_speed(CHAMBER_FAN_INDEX, 0); #endif #if ENABLED(CHAMBER_VENT) flag_chamber_excess_heat = false; From 9a8c9d4ed0f1ab26736fda469eefcbdaeeb90969 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 6 Aug 2021 22:51:10 +0200 Subject: [PATCH 0516/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20"'EEPROM'=20unus?= =?UTF-8?q?ed"=20warning=20(#22511)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/eeprom_flash.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 0c37abfcbb..c3efec6062 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -104,6 +104,8 @@ size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { + EEPROM.begin(); // Avoid STM32 EEPROM.h warning (do nothing) + #if ENABLED(FLASH_EEPROM_LEVELING) if (current_slot == -1 || eeprom_data_written) { From e7c33840dca804c5c41ca6ce8888bfa16f8c1a47 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sat, 7 Aug 2021 08:54:02 +1200 Subject: [PATCH 0517/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20'USB=20Fla?= =?UTF-8?q?sh=20MSC'=20environments=20(#22515)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f4.ini | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index d2332630a1..b32efb83a9 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -388,8 +388,9 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} [env:mks_robin_nano_v3_usb_flash_drive_msc] platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3_usb_flash_drive -build_flags = ${env:mks_robin_nano_v3_usb_flash_drive} +build_flags = ${env:mks_robin_nano_v3_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC +build_unflags = -DUSBD_USE_CDC # # This I2C1(PB8:I2C1_SCL PB9:I2C1_SDA) is used by MKS Monster8 @@ -434,5 +435,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flag [env:mks_monster8_usb_flash_drive_msc] platform = ${common_stm32.platform} extends = env:mks_monster8_usb_flash_drive -build_flags = ${env:mks_monster8_usb_flash_drive} +build_flags = ${env:mks_monster8_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC +build_unflags = -DUSBD_USE_CDC From f732cb1a7f499e83f5a43344a54fb19cbbc9dab0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 7 Aug 2021 00:53:48 +0000 Subject: [PATCH 0518/2168] [cron] Bump distribution date (2021-08-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c65e3c3f44..08adb046a0 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-06" +//#define STRING_DISTRIBUTION_DATE "2021-08-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d87990ca67..679ccbe767 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 "2021-08-06" + #define STRING_DISTRIBUTION_DATE "2021-08-07" #endif /** From f4ab0a0c918f4db514e981c18f737e2752a2fc01 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 7 Aug 2021 15:59:00 -0500 Subject: [PATCH 0519/2168] =?UTF-8?q?=F0=9F=94=A7=20Sanity-check=20Mixing?= =?UTF-8?q?=20plus=20Disable=20Inactive=20Extruder?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #22166 --- Marlin/src/inc/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a2fdc9856e..9dfc24b064 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1182,6 +1182,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Please select either MIXING_EXTRUDER or SWITCHING_EXTRUDER, not both." #elif ENABLED(SINGLENOZZLE) #error "MIXING_EXTRUDER is incompatible with SINGLENOZZLE." + #elif ENABLED(DISABLE_INACTIVE_EXTRUDER) + #error "MIXING_EXTRUDER is incompatible with DISABLE_INACTIVE_EXTRUDER." #endif #endif From 22ae09ace498e735c216bbb726f2c3f39d5d714a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 7 Aug 2021 16:06:51 -0500 Subject: [PATCH 0520/2168] =?UTF-8?q?=F0=9F=94=A7=20Sanity-check=20DEFAULT?= =?UTF-8?q?=5FEJERK=20with=20LIN=5FADVANCE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #20649 --- Marlin/src/inc/SanityCheck.h | 11 ++++------- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 3 +-- 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 9dfc24b064..da51f5ca9e 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1210,6 +1210,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS ); #if ENABLED(S_CURVE_ACCELERATION) && DISABLED(EXPERIMENTAL_SCURVE) #error "LIN_ADVANCE and S_CURVE_ACCELERATION may not play well together! Enable EXPERIMENTAL_SCURVE to continue." + #elif ENABLED(DIRECT_STEPPING) + #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." + #elif !HAS_JUNCTION_DEVIATION && defined(DEFAULT_EJERK) + static_assert(DEFAULT_EJERK >= 10, "It is strongly recommended to set DEFAULT_EJERK >= 10 when using LIN_ADVANCE."); #endif #endif @@ -3600,13 +3604,6 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "SAVED_POSITIONS must be an integer from 0 to 256." #endif -/** - * Stepper Chunk support - */ -#if BOTH(DIRECT_STEPPING, LIN_ADVANCE) - #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." -#endif - /** * Touch Screen Calibration */ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index bb4c0e8000..cb3d3242e2 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -126,11 +126,10 @@ #endif #endif - #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if SD_CONNECTION_IS(LCD) && ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) - #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_PINS_FOR_CS." + #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." #endif #if SD_CONNECTION_IS(LCD) From 0f3e938c9b398dafa09ba39d98c4c461e883068e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 8 Aug 2021 00:58:57 +0000 Subject: [PATCH 0521/2168] [cron] Bump distribution date (2021-08-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 08adb046a0..c34cb52361 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-07" +//#define STRING_DISTRIBUTION_DATE "2021-08-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 679ccbe767..ad1dff604c 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 "2021-08-07" + #define STRING_DISTRIBUTION_DATE "2021-08-08" #endif /** From c1a533b45e21c43eda6fedb9679976747bca6845 Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Sat, 7 Aug 2021 22:17:43 -0500 Subject: [PATCH 0522/2168] =?UTF-8?q?=F0=9F=93=8C=20MKS=20pins=20for=20PSU?= =?UTF-8?q?=5FCONTROL=20(#22528)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/lcd/M995.cpp | 4 +- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 12 +++++- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 13 +++++++ Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 13 +++++++ Marlin/src/pins/stm32f1/pins_CHITU3D_common.h | 2 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 5 ++- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 11 +++--- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 19 ++++++++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 27 ++++++++++---- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 26 +++++++++---- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 24 ++++++++++-- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 25 ++++++++++--- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 37 ++++++++++++++----- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 17 ++++++--- 14 files changed, 180 insertions(+), 55 deletions(-) diff --git a/Marlin/src/gcode/lcd/M995.cpp b/Marlin/src/gcode/lcd/M995.cpp index 5e9fddbe8c..d5f825c0c8 100644 --- a/Marlin/src/gcode/lcd/M995.cpp +++ b/Marlin/src/gcode/lcd/M995.cpp @@ -26,7 +26,7 @@ #include "../gcode.h" -#if ENABLED(TFT_LVGL_UI) +#if HAS_TFT_LVGL_UI #include "../../lcd/extui/mks_ui/draw_touch_calibration.h" #else #include "../../lcd/menu/menu.h" @@ -37,7 +37,7 @@ */ void GcodeSuite::M995() { - #if ENABLED(TFT_LVGL_UI) + #if HAS_TFT_LVGL_UI lv_draw_touch_calibration_screen(); #else ui.goto_screen(touch_screen_calibration); diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 71d7ad3037..4c2b606929 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -136,9 +136,17 @@ #endif // -// Misc. Functions +// Power Supply Control // -#define PS_ON_PIN P0_25 // TH3 Connector +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P0_25 // SERVO + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_29 // Z+ + #define KILL_PIN_STATE HIGH + #endif +#endif // // Ethernet pins diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 68e1389841..0c3f44ceb7 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -215,6 +215,19 @@ #define FAN_PIN P2_04 #endif +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P2_00 // SERVO + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_24 // Z+ + #define KILL_PIN_STATE HIGH + #endif +#endif + // // Misc. Functions // diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 1057147498..4020ac23c6 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -226,6 +226,19 @@ // #define LED_PIN P1_18 // Used as a status indicator +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN P2_00 // Suggestion (SERVO) + #endif + #ifndef KILL_PIN + #define KILL_PIN P1_24 // Suggestion (Z+) + #define KILL_PIN_STATE HIGH + #endif +#endif + // // RGB LED // diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h index b638589388..0319afa5e9 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -147,7 +147,7 @@ #define TFT_RS_PIN FSMC_RS_PIN #endif -#if ENABLED(TFT_LVGL_UI) +#if HAS_TFT_LVGL_UI // LVGL #define HAS_SPI_FLASH_FONT 1 #define HAS_GCODE_PREVIEW 1 diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index 31b03f6b07..2dea59ef41 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -195,9 +195,10 @@ // // Misc. Functions // -//#define POWER_LOSS_PIN PA1 // PW_SO #if ENABLED(BACKUP_POWER_SUPPLY) #define POWER_LOSS_PIN PA2 // PW_DET (UPS) MKSPWC +#else + //#define POWER_LOSS_PIN PA1 // PW_SO #endif /** @@ -217,7 +218,7 @@ // #if ENABLED(PSU_CONTROL) #define KILL_PIN PA2 // PW_DET - #define KILL_PIN_INVERTING true + #define KILL_PIN_STATE HIGH //#define PS_ON_PIN PA3 // PW_CN /PW_OFF #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index b32d0aa0b8..7aa308f7b3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -183,12 +183,11 @@ // Misc. Functions // #if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE + #if ENABLED(PSU_CONTROL) // MKSPWC + #define SUICIDE_PIN PB2 // PW_OFF + #define SUICIDE_PIN_INVERTING false + #define KILL_PIN PA2 // PW_DET + #define KILL_PIN_STATE HIGH #endif #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 44c35b9d04..da7ba05795 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -126,6 +126,19 @@ #define FIL_RUNOUT_PIN PB10 // MT_DET +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN PA14 // PW_OFF + #endif + #ifndef KILL_PIN + #define KILL_PIN PB10 // PW_DET + #define KILL_PIN_STATE HIGH + #endif +#endif + /** * _____ _____ _____ * (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) 5V | 1 2 | GND @@ -158,7 +171,7 @@ #elif ENABLED(MKS_MINI_12864_V3) #define DOGLCD_CS PA4 #define DOGLCD_A0 PA5 - #define LCD_PINS_DC DOGLCD_A0 + #define LCD_PINS_DC DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN PA6 #define NEOPIXEL_PIN PA7 @@ -189,8 +202,8 @@ // // SD Card // -#define SPI_DEVICE 2 -#define ONBOARD_SPI_DEVICE 2 +#define SPI_DEVICE 2 +#define ONBOARD_SPI_DEVICE 2 #define SDSS SD_SS_PIN #define SDCARD_CONNECTION ONBOARD #define SD_DETECT_PIN PC10 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 147aec5e9f..368c0a2458 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -127,18 +127,29 @@ //#define TEMP_0_CS_PIN PE5 // TC1 - CS1 //#define TEMP_0_CS_PIN PE6 // TC2 - CS2 +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif + // // Misc. Functions // #if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE - #endif - #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 4b0ba2fdab..cdb9448410 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -191,17 +191,29 @@ //#define TEMP_0_CS_PIN PE5 // TC1 - CS1 //#define TEMP_0_CS_PIN PE6 // TC2 - CS2 +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif + // // Misc. Functions // #if HAS_TFT_LVGL_UI - //#define MKSPWC - #ifdef MKSPWC - #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN - #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE - #define KILL_PIN PA2 // Enable MKSPWC DET PIN - #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE - #endif #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 7ff22cc1ce..2f62563edb 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -179,10 +179,28 @@ //#define TEMP_0_CS_PIN PF11 // TC2 - CS2 #define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PG11 // PW_OFF #define FIL_RUNOUT_PIN PA4 // MT_DET1 -//#define FIL_RUNOUT_PIN PE6 // MT_DET2 -//#define FIL_RUNOUT_PIN PG14 // MT_DET3 +#define FIL_RUNOUT2_PIN PE6 // MT_DET2 +#define FIL_RUNOUT3_PIN PG14 // MT_DET3 + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PG11 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PG11 + #define SUICIDE_PIN_INVERTING false +#endif // // SD Card diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index b7fd7222c8..2db5584109 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -210,10 +210,8 @@ // // Misc. Functions // -#define MT_DET_1 Y_MAX_PIN -#define MT_DET_2 Z_MAX_PIN -#define PW_DET Y_MAX_PIN -#define PW_OFF Z_MAX_PIN +#define MT_DET_1 PC5 // Y+ +#define MT_DET_2 PB12 // Z+ #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN MT_DET_1 @@ -222,8 +220,23 @@ #define FIL_RUNOUT2_PIN MT_DET_2 #endif -#define POWER_LOSS_PIN PW_DET -#define PS_ON_PIN PW_OFF +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #ifndef PS_ON_PIN + #define PS_ON_PIN MT_DET_2 // Z+ + #endif + #ifndef KILL_PIN + #define KILL_PIN MT_DET_1 // Y+ + #define KILL_PIN_STATE HIGH + #endif +#else + #define PW_DET MT_DET_1 + #define PW_OFF MT_DET_2 + #define POWER_LOSS_PIN PW_DET + #define PS_ON_PIN PW_OFF +#endif // Random Info #define USB_SERIAL -1 // USB Serial diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 882b9601ac..eff941b957 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -189,19 +189,36 @@ #define FIL_RUNOUT2_PIN MT_DET_2_PIN #endif -#ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PA13 // PW_DET -#endif -#define PS_ON_PIN PB2 // PW_OFF - // // Enable MKSPWC support // //#define SUICIDE_PIN PB2 -//#define KILL_PIN PA2 -//#define KILL_PIN_INVERTING true - //#define LED_PIN PB2 +//#define KILL_PIN PA2 +//#define KILL_PIN_STATE HIGH + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + #if HAS_TFT_LVGL_UI + #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." + #endif + #ifndef PS_ON_PIN + #define PS_ON_PIN PB2 // SUICIDE + #endif + #ifndef KILL_PIN + #define KILL_PIN PA13 // PW_DET + #define KILL_PIN_STATE HIGH + #endif +#else + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_INVERTING false +#endif + +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PA13 // PW_DET +#endif // Random Info #define USB_SERIAL -1 // USB Serial @@ -222,8 +239,8 @@ // MKS TEST #if ENABLED(MKS_TEST) - #define MKS_TEST_POWER_LOSS_PIN PA13 // PW_DET - #define MKS_TEST_PS_ON_PIN PB2 // PW_OFF + #define MKS_TEST_POWER_LOSS_PIN PA13 // PW_DET + #define MKS_TEST_PS_ON_PIN PB2 // PW_OFF #endif // diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index aa65eaa799..2e47f98e9f 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -195,12 +195,19 @@ // // Misc. Functions // -//#define POWER_LOSS_PIN PA2 // PW_DET //#define PS_ON_PIN PA3 // PW_OFF -//#define SUICIDE_PIN PB2 // Enable MKSPWC support -//#define KILL_PIN PA2 // Enable MKSPWC support -//#define KILL_PIN_INVERTING true // Enable MKSPWC support -//#define LED_PIN PB2 + +// +// Power Supply Control +// +#if ENABLED(PSU_CONTROL) // MKSPWC + //#define SUICIDE_PIN PB2 // LED + //#define KILL_PIN PA2 // PW_DET + //#define KILL_PIN_STATE HIGH +#else + //#define POWER_LOSS_PIN PA2 // PW_DET + //#define LED_PIN PB2 +#endif #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD From 26b1ed7c2a95d14af22ba7f78a62cff551aa34ea Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sat, 7 Aug 2021 21:23:06 -0600 Subject: [PATCH 0523/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FTDI=20Eve=20Tou?= =?UTF-8?q?ch=20UI=20(#22530)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/adjuster_widget.cpp | 2 +- .../lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp | 3 ++- .../lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp index 26be9f4e59..3ef71f573f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp @@ -42,7 +42,7 @@ namespace FTDI { strcat_P(str, (const char*) units); } - cmd.text(VAL_POS, str); + cmd.tag(0).text(VAL_POS, str); } void draw_adjuster(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t tag, float value, progmem_str units, int8_t width, uint8_t precision, draw_mode_t what) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 5712ad0f0b..830a0238fe 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -36,6 +36,7 @@ using namespace Theme; constexpr static SpinnerDialogBoxData &mydata = screen_data.SpinnerDialogBox; void SpinnerDialogBox::onEntry() { + UIScreen::onEntry(); mydata.auto_hide = true; } @@ -98,7 +99,7 @@ void SpinnerDialogBox::enqueueAndWait(progmem_str message, char *commands) { } void SpinnerDialogBox::onIdle() { - if (mydata.auto_hide && !commandsInQueue()) { + if (mydata.auto_hide && !commandsInQueue() && TERN1(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state == GcodeSuite::NOT_BUSY)) { mydata.auto_hide = false; hide(); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h index 9ecc33e5c4..23e31d1a91 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h @@ -29,7 +29,7 @@ struct SpinnerDialogBoxData { bool auto_hide; }; -class SpinnerDialogBox : public BaseScreen { +class SpinnerDialogBox : public UIScreen { public: static void onEntry(); static void onExit(); From a63e0477da38801a4952ae2fae6c44bf35d6fc3f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 8 Aug 2021 01:24:15 -0500 Subject: [PATCH 0524/2168] =?UTF-8?q?=F0=9F=92=9A=20Fix=20tests=20for=20ne?= =?UTF-8?q?w=20sanity-checks?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/mega2560 | 5 +++-- buildroot/tests/rambo | 1 + buildroot/tests/teensy35 | 1 + buildroot/tests/teensy41 | 1 + 4 files changed, 6 insertions(+), 2 deletions(-) diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 0af5513294..723d133081 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -16,7 +16,7 @@ set -e # Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders # use_example_configs AnimationExample -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 \ +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 DEFAULT_EJERK 10 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ @@ -31,7 +31,7 @@ exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." # Add a Sled Z Probe, use UBL Cartesian moves, use Japanese language # use_example_configs AnimationExample -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE jp_kana \ +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE jp_kana DEFAULT_EJERK 10 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES \ @@ -73,6 +73,7 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE +opt_disable DISABLE_INACTIVE_EXTRUDER exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index e755f81cf1..a563bd4ed3 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -123,6 +123,7 @@ opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_PAUSE_M76 ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_USE_Z_ONLY +opt_disable DISABLE_INACTIVE_EXTRUDER exec_test $1 $2 "Rambo | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." "$3" # clean up diff --git a/buildroot/tests/teensy35 b/buildroot/tests/teensy35 index 4bfa64f1db..09e8cee58e 100755 --- a/buildroot/tests/teensy35 +++ b/buildroot/tests/teensy35 @@ -67,6 +67,7 @@ exec_test $1 $2 "PARKING_EXTRUDER with LCD" "$3" restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 MIXING_STEPPERS 2 opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +opt_disable DISABLE_INACTIVE_EXTRUDER exec_test $1 $2 "Mixing Extruder" "$3" # diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index 017b81b3c1..fd89512ea5 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -70,6 +70,7 @@ exec_test $1 $2 "Ethernet, EEPROM, Magnetic Parking Extruder, No LCD" "$3" restore_configs opt_set MOTHERBOARD BOARD_TEENSY41 MIXING_STEPPERS 2 opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL +opt_disable DISABLE_INACTIVE_EXTRUDER exec_test $1 $2 "Mixing Extruder" "$3" # From 8a7673ac1e4df933cfe1a0254af03af4118e66e4 Mon Sep 17 00:00:00 2001 From: luzpaz Date: Sun, 8 Aug 2021 03:26:54 -0400 Subject: [PATCH 0525/2168] =?UTF-8?q?=F0=9F=8E=A8=20Spellcheck=20code=20(#?= =?UTF-8?q?22531)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h | 4 ++-- Marlin/src/HAL/DUE/usb/udd.h | 2 +- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 4 ++-- Marlin/src/feature/binary_stream.h | 4 ++-- Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/wifi_module.h | 2 +- .../src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h | 2 +- Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h | 2 +- 9 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h index d77e4f9523..553fd3c29a 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h @@ -74,7 +74,7 @@ #define SD_MMC_REMOVING 2 -//---- CONTROL FONCTIONS ---- +//---- CONTROL FUNCTIONS ---- //! //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. //!/ @@ -134,7 +134,7 @@ extern bool sd_mmc_spi_wr_protect(void); extern bool sd_mmc_spi_removal(void); -//---- ACCESS DATA FONCTIONS ---- +//---- ACCESS DATA FUNCTIONS ---- #if ACCESS_USB == true // Standard functions for open in read/write mode the device diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 461d98513b..319d8842f7 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -135,7 +135,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * \param n number of data transferred */ typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transfered, udd_ep_id_t ep); + iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 53e5bd83e0..5b0c27e412 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -181,7 +181,7 @@ void LTDC_Config() { hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1); - hltdc_F.Init.TotalHeigh = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1); + hltdc_F.Init.TotalHeight = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1); hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1); /* Configure R,G,B component values for LCD background color : all black background */ @@ -203,7 +203,7 @@ void LTDC_Config() { pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565; /* Start Address configuration : frame buffer is located at SDRAM memory */ - pLayerCfg.FBStartAdress = (uint32_t)(FRAME_BUFFER_ADDRESS); + pLayerCfg.FBStartAddress = (uint32_t)(FRAME_BUFFER_ADDRESS); /* Alpha constant (255 == totally opaque) */ pLayerCfg.Alpha = 255; diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 2ad7f236a1..cef8a3c902 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -148,9 +148,9 @@ public: case FileTransfer::QUERY: SERIAL_ECHOPAIR("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); #if ENABLED(BINARY_STREAM_COMPRESSION) - SERIAL_ECHOLNPAIR(":compresion:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); + SERIAL_ECHOLNPAIR(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); #else - SERIAL_ECHOLNPGM(":compresion:none"); + SERIAL_ECHOLNPGM(":compression:none"); #endif break; case FileTransfer::OPEN: diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h index 49f6ea0900..e2786fd452 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -44,7 +44,7 @@ bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data); void LCD_Clear(uint16_t Color); void tft_set_point(uint16_t x, uint16_t y, uint16_t point); -void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh); +void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t height); void LCD_WriteRAM_Prepare(); void lcd_draw_logo(); void lv_encoder_pin_init(); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 1d136a4075..b53586c756 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -225,7 +225,7 @@ static bool longName2DosName(const char *longName, char *dosName) { else if (status_bits & 0x2) { // DMA transmit complete if (esp_state == TRANSFER_IDLE) - esp_state = TRANSFERING; + esp_state = TRANSFERRING; if (storeRcvData(WIFISERIAL.usart_device->rb->buf, UART_RX_BUFFER_SIZE)) { esp_dma_pre(); @@ -1819,7 +1819,7 @@ void wifi_rcv_handle() { #ifdef __STM32F1__ if (esp_state == TRANSFER_STORE) { if (storeRcvData(WIFISERIAL.wifiRxBuf, UART_RX_BUFFER_SIZE)) { - esp_state = TRANSFERING; + esp_state = TRANSFERRING; esp_dma_pre(); if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); } diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index 709d3d1719..d02716e435 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -137,7 +137,7 @@ typedef enum { typedef enum { TRANSFER_IDLE, - TRANSFERING, + TRANSFERRING, TRANSFER_STORE, } TRANSFER_STATE; extern volatile TRANSFER_STATE esp_state; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h index 3f758e7712..f78a3bb8f0 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h @@ -90,7 +90,7 @@ uint8_t UHS_USB_HOST_BASE::setEpInfoEntry(uint8_t addr, uint8_t iface, uint8_t e } /** - * sets all enpoint addresses to zero. + * sets all endpoint addresses to zero. * Sets all max packet sizes to defaults * Clears all endpoint attributes * Sets bmNakPower to USB_NAK_DEFAULT diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h index 0ac90f0df3..eeaa4f81d9 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h @@ -140,7 +140,7 @@ AJK_IIF(AJK_BITAND(AJK_IS_COMPARABLE(x))(AJK_IS_COMPARABLE(y)) ) \ #define AJK_MAKE_FUNS(AJK_v, AJK_args, AJK_count, AJK_body) AJK_EVAL(AJK_REPEAT(AJK_count, AJK_FUN, AJK_v, AJK_args, AJK_body)) #ifdef AJK_TEST_MACRO_LOGIC -#define BODY(AJKindex) some(C, statement); contaning(a, test[AJKindex]); +#define BODY(AJKindex) some(C, statement); containing(a, test[AJKindex]); #define ZERO_TIMES_TEST 0 #define THREE_TIMES_TEST 3 blank > AJK_MAKE_LIST(VARIABLE_, ZERO_TIMES_TEST) < because zero repeats From 5756f8898e8868704516385bae17e65f367aa140 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 8 Aug 2021 19:45:51 +1200 Subject: [PATCH 0526/2168] =?UTF-8?q?=E2=9C=A8=20Zonestar=20ZM3E2,=20ZM3E4?= =?UTF-8?q?=20V1,=20ZM3E4=20V2=20(#22498)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 9 +- Marlin/src/core/boards.h | 3 + Marlin/src/lcd/tft_io/touch_calibration.cpp | 2 +- Marlin/src/lcd/tft_io/touch_calibration.h | 2 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 +- Marlin/src/pins/pins.h | 6 + .../pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h | 2 +- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 17 +- .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h | 2 +- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 235 ++++++++++++ Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 355 ++++++++++++++++++ Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 328 ++++++++++++++++ Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h | 5 +- .../ldscripts/ZONESTAR_ZM3E_256K.ld | 14 + .../ldscripts/ZONESTAR_ZM3E_512K.ld | 14 + ...F103RC_fysetc => STM32F103RC_fysetc_maple} | 0 buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple | 14 + ...{jgaurora_a5s_a1 => jgaurora_a5s_a1_maple} | 0 .../{mks_robin_lite => mks_robin_lite_maple} | 0 .../{mks_robin_pro => mks_robin_pro_maple} | 0 ini/stm32f1-maple.ini | 43 +++ ini/stm32f1.ini | 40 ++ 28 files changed, 1083 insertions(+), 22 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h create mode 100644 Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h create mode 100644 Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h create mode 100644 buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld create mode 100644 buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld rename buildroot/tests/{STM32F103RC_fysetc => STM32F103RC_fysetc_maple} (100%) create mode 100755 buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple rename buildroot/tests/{jgaurora_a5s_a1 => jgaurora_a5s_a1_maple} (100%) rename buildroot/tests/{mks_robin_lite => mks_robin_lite_maple} (100%) rename buildroot/tests/{mks_robin_pro => mks_robin_pro_maple} (100%) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index e45bf42f29..c6afaffebf 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -58,15 +58,16 @@ jobs: #- STM32F103RC_btt_maple - STM32F103RC_btt_USB_maple - - STM32F103RC_fysetc + - STM32F103RC_fysetc_maple - STM32F103RC_meeb - - jgaurora_a5s_a1 + - jgaurora_a5s_a1_maple - STM32F103VE_longer_maple #- mks_robin_maple - - mks_robin_lite - - mks_robin_pro + - mks_robin_lite_maple + - mks_robin_pro_maple #- mks_robin_nano35_maple #- STM32F103RET6_creality_maple + - STM32F103VE_ZM3E4V2_USB_maple # STM32 (ST) Environments diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index ba3c9f978c..2ed5859199 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -346,6 +346,9 @@ #define BOARD_BEAST 4048 // STM32F103RET6 Libmaple-based controller #define BOARD_MINGDA_MPX_ARM_MINI 4049 // STM32F103ZET6 Mingda MD-16 #define BOARD_GTM32_PRO_VD 4050 // STM32F103VET6 controller +#define BOARD_ZONESTAR_ZM3E2 4051 // Zonestar ZM3E2 (STM32F103RCT6) +#define BOARD_ZONESTAR_ZM3E4 4052 // Zonestar ZM3E4 V1 (STM32F103VCT6) +#define BOARD_ZONESTAR_ZM3E4V2 4053 // Zonestar ZM3E4 V2 (STM32F103VCT6) // // ARM Cortex-M4F diff --git a/Marlin/src/lcd/tft_io/touch_calibration.cpp b/Marlin/src/lcd/tft_io/touch_calibration.cpp index 0f9d25caeb..2a54d2af40 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.cpp +++ b/Marlin/src/lcd/tft_io/touch_calibration.cpp @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * 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 diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index f8cbf99bf0..112fbdca30 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * 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 diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index d648b25efb..cecb44efbe 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -212,7 +212,7 @@ * BEEPER | 5 6 ENT (BTN_ENC) (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) * (SKR_RX1) TX | 7 8 | RX (SKR_TX1) Reset | 7 8 | P0_19 (BTN_EN1) * NC | 9 10 | NC (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) - * ------ ------ + * ------ ------ */ #define BEEPER_PIN EXP1_10_PIN diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b3e1605613..f1c431cf04 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -561,6 +561,12 @@ #include "stm32f1/pins_BEAST.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(MINGDA_MPX_ARM_MINI) #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini +#elif MB(ZONESTAR_ZM3E2) + #include "stm32f1/pins_ZM3E2_V1_0.h" // STM32F1 env:STM32F103RC_ZM3E2_USB env:STM32F103RC_ZM3E2_USB_maple +#elif MB(ZONESTAR_ZM3E4) + #include "stm32f1/pins_ZM3E4_V1_0.h" // STM32F1 env:STM32F103VC_ZM3E4_USB env:STM32F103VC_ZM3E4_USB_maple +#elif MB(ZONESTAR_ZM3E4V2) + #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple // // ARM Cortex-M4F diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h index c51e7f48d9..9dc02c495b 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h @@ -23,7 +23,7 @@ #define SKR_MINI_E3_V2 -#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 +#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 -DTIMER_TONE=4 // Onboard I2C EEPROM #if NO_EEPROM_SELECTED diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index bded0edd3a..98465a8607 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -45,14 +45,19 @@ #endif //#define MCU_STM32F103ZE // not yet required + // Enable EEPROM Emulation for this board, so that we don't overwrite factory data +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM // AT24C64 + //#define FLASH_EEPROM_EMULATION +#endif -//#define I2C_EEPROM // AT24C64 -//#define MARLIN_EEPROM_SIZE 0x8000UL // 64KB - -//#define FLASH_EEPROM_EMULATION -//#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB -//#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) +#if ENABLED(I2C_EEPROM) + //#define MARLIN_EEPROM_SIZE 0x8000UL // 32KB +#elif ENABLED(FLASH_EEPROM_EMULATION) + //#define MARLIN_EEPROM_SIZE 0x1000UL // 4KB + //#define MARLIN_EEPROM_SIZE (EEPROM_START_ADDRESS + (EEPROM_PAGE_SIZE) * 2UL) +#endif // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index 14f2ad981a..3fed0adac3 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin mini (STM32F130VET6) board pin assignments + * MKS Robin mini (STM32F103VET6) board pin assignments */ #if NOT_TARGET(STM32F1, STM32F1xx) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index f912978051..4d798ffe28 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin (STM32F130ZET6) board pin assignments + * MKS Robin (STM32F103ZET6) board pin assignments * https://github.com/makerbase-mks/MKS-Robin/tree/master/MKS%20Robin/Hardware */ diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 7aa308f7b3..2fc99f2971 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments */ #include "env_validate.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index be23394af7..d4a2f59b42 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin mini (STM32F130VET6) board pin assignments + * MKS Robin mini (STM32F103VET6) board pin assignments */ #include "env_validate.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 368c0a2458..2a5c9f7273 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments * https://github.com/makerbase-mks/MKS-Robin-Nano-V1.X/tree/master/hardware */ diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index cdb9448410..31ce016e67 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS Robin nano (STM32F130VET6) board pin assignments + * MKS Robin nano (STM32F103VET6) board pin assignments */ #if NOT_TARGET(__STM32F1__, STM32F1) diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 1de3729dcc..5b59a157f1 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -22,7 +22,7 @@ #pragma once /** - * ANYCUBIC Trigorilla Pro (STM32F130ZET6) board pin assignments. + * ANYCUBIC Trigorilla Pro (STM32F103ZET6) board pin assignments. * It is the same used by the Tronxy X5SA thanks to ftoz1 for sharing it * https://github.com/MarlinFirmware/Marlin/issues/14655 * https://github.com/MarlinFirmware/Marlin/files/3401484/x5sa-main_board-2.pdf diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h new file mode 100644 index 0000000000..bad5db7125 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -0,0 +1,235 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E2 V1.0" + +#define DISABLE_DEBUG +//#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//============================================================================= +// Zonestar ZM3E2 V1.0 (STM32F103RCT6) board pin assignments +//============================================================================= +// PA0 PWR_HOLD | PB0 BEEP | PC0 HEATER_0 +// PA1 FAN_PIN | PB1 KILL | PC1 HEATER_BED +// PA2 TX2 | PB2 LCD_SDA | PC2 TEMP_BED +// PA3 RX2 | PB3 E1_EN | PC3 TEMP_E0 +// PA4 SD_CS | PB4 Z_STOP | PC4 SD_DETECT +// PA5 SD_SCK | PB5 Z_DIR | PC5 BTN_EN2 +// PA6 SD_MISO | PB6 Z_STEP | PC6 FAN1 +// PA7 SD_MOSI | PB7 Z_EN | PC7 FIL_RUNOUT +// PA8 X_DIR | PB8 Y_STEP | PC8 X_EN +// PA9 LCD_RS | PB9 Y_DIR | PC9 X_STEP +// PA10 LCD_SCK | PB10 BTN_ENC | PC10 Z_MIN_PROBE_PIN +// PA11 USB_D- | PB11 BTN_EN1 | PC11 FIL_RUNOUT2 +// PA12 USB_D+ | PB12 LED | PC12 E1_DIR +// PA13 MS1 | PB13 E0_EN | PC13 Y_STOP +// PA14 MS2 | PB14 E0_STEP | PC14 Y_EN +// PA15 PWM | PB15 E0_DIR | PC15 X_STOP +// PD0 NC +// PD1 NC +// PD2 E1_STEP + +//============================================================================= +// EXP1 connector +// MARK I/O ZONESTAR_12864LCD ZONESTAR_12864OLED +// 10 MOSI PB1 KILL SDA +// 9 SCK PB0 BEEP SCK +// 8 TX1 PA9 DOGLCD_CS CS +// 7 RX1 PA10 DOGLCD_SCK DC +// 6 ENA PC5 BTN_EN2 KNOB_ENB +// 5 DAT PB2 DOGLCD_MOSI RESET +// 4 TX3 PB10 BTN_ENC KNOB_ENC +// 3 RX3 PB11 BTN_EN1 KNOB_ENA +// 2 +5V +// 1 GND + +#define EXP1_03_PIN PB11 +#define EXP1_04_PIN PB10 +#define EXP1_05_PIN PB2 +#define EXP1_06_PIN PC5 +#define EXP1_07_PIN PA10 +#define EXP1_08_PIN PA9 +#define EXP1_09_PIN PB0 +#define EXP1_10_PIN PB1 + +// AUX1 connector +// 1 +5V +// 2 TX2 PA2 UART2_TX +// 3 RX2 PA3 UART2_RX +// 4 GND + +// AUX2 connector to BLTouch +// 1 +5V +// 2 SEN PC10 +// 3 PWM PA15 +// 4 GND +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PA15 + +// +// Limit Switches +// +#define X_STOP_PIN PC15 +#define Y_STOP_PIN PC13 +#define Z_STOP_PIN PB4 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PC10 // BLTouch (3DTouch) +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PC7 // E0_SW +//#define FIL_RUNOUT2_PIN PC11 // E1_SW + +// +// Steppers +// +#define MS1_PIN PA13 +#define MS2_PIN PA14 + +#define X_STEP_PIN PC9 +#define X_DIR_PIN PA8 +#define X_ENABLE_PIN PC8 + +#define Y_STEP_PIN PB8 +#define Y_DIR_PIN PB9 +#define Y_ENABLE_PIN PC14 + +#define Z_STEP_PIN PB6 +#define Z_DIR_PIN PB5 +#define Z_ENABLE_PIN PB7 + +#define E0_STEP_PIN PB14 +#define E0_DIR_PIN PB15 +#define E0_ENABLE_PIN PB13 + +#define E1_STEP_PIN PD2 +#define E1_DIR_PIN PC12 +#define E1_ENABLE_PIN PB3 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC0 // EXTRUDER 1 +#define HEATER_BED_PIN PC1 // BED + +#define FAN1_PIN PC6 +#define FAN_PIN PA1 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PC2 // Analog Input +#define TEMP_0_PIN PC3 // Analog Input + +#define LED_PIN PB12 +//#define KILL_PIN PB1 // @EXP1 +#define SUICIDE_PIN PA0 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// +// LCD Pins +// +#if ENABLED(ZONESTAR_12864LCD) + + //================================================================================ + // LCD 128x64 + //================================================================================ + // EXP1 connector + // MARK I/O ZONESTAR_12864LCD + // 10 MOSI PB1 KILL + // 9 SCK PB0 BEEP + // 8 TX1 PA9 LCD_PINS_RS + // 7 RX1 PA10 LCD_PINS_D4 + // 6 ENA PC5 BTN_EN2 + // 5 DAT PB2 LCD_PINS_ENABLE + // 4 TX3 PB10 BTN_ENC + // 3 RX3 PB11 BTN_EN1 + // 2 +5V + // 1 GND + + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_05_PIN + #define LCD_PINS_D4 EXP1_07_PIN + //#define KILL_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_04_PIN + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(200) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + +#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) + + //================================================================================ + // OLED 128x64 + //================================================================================ + // 10 MOSI PB1 OLED_SDA + // 9 SCK PB0 OLED_SCK + // 8 TX1 PA9 OLED_CS + // 7 RX1 PA10 OLED_DC + // 6 ENA PC5 KNOB_ENA + // 5 DAT PB2 OLED_RESET + // 4 TX3 PB10 KNOB_ENC + // 3 RX3 PB11 KNOB_ENB + + #define FORCE_SOFT_SPI + #define LCDSCREEN_NAME "ZONESTAR 12864OLED" + #define LCD_PINS_RS EXP1_05_PIN // = LCD_RESET_PIN + #define LCD_PINS_DC EXP1_07_PIN // DC + #define DOGLCD_CS EXP1_08_PIN // CS + #define DOGLCD_A0 LCD_PINS_DC // A0 = DC + #define DOGLCD_MOSI EXP1_10_PIN // SDA + #define DOGLCD_SCK EXP1_09_PIN // SCK + // Encoder + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_04_PIN + +#endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h new file mode 100644 index 0000000000..8a6bb4b5f8 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -0,0 +1,355 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E4 V1.0" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//#define OPTION_DUALZ_DRIVE +//#define OPTION_Z2_ENDSTOP +//#define SWITCH_EXTRUDER_SEQUENCE + +//============================================================================= +// Zonestar ZM3E4 V1.0 (STM32F103VCT6) board pin assignments +//============================================================================= +// PA0 | PB0 HEAT_1 | PC0 AXU_SDA +// PA1 | PB1 FAN1 | PC1 TEMP_E1 +// PA2 HEAT_BED | PB2 BOOT1 | PC2 TEMP_E0 +// PA3 PWR_HOLD | PB3 SPI3_SCK | PC3 TEMP_BED +// PA4 SD_CS | PB4 SPI3_MISO | PC4 SD_DETECT +// PA5 SD_SCK | PB5 SPI3_MOSI | PC5 HEAT_0 +// PA6 SD_MISO | PB6 SERVO3 | PC6 E1_STEP +// PA7 SD_MOSI | PB7 SERVO2 | PC7 E1_EN +// PA8 X_DIR | PB8 FAN2/SERVO1 | PC8 FIL_RUNOUT_PIN +// PA9 UART1_RX | PB9 SERVO0 | PC9 E0_DIR +// PA10 UART1_TX | PB10 TX3 | PC10 E0_EN +// PA11 USB_D- | PB11 RX3 | PC11 Z2_EN +// PA12 USB_D+ | PB12 LED | PC12 Z2_STEP +// PA13 SWD_SDO | PB13 Z1_MAX | PC13 X_MIN +// PA14 SWD_SCK | PB14 Y_MAX | PC14 WIFI_RST +// PA15 SPI3_CS | PB15 PWR_DET | PC15 WIFI_CS +// PD0 Z2_DIR | PE0 Y_EN +// PD1 Z2_MIN | PE1 Y_STEP +// PD2 Z1_EN | PE2 Y_DIR +// PD3 Z1_STEP | PE3 Y_MIN +// PD4 Z1_DIR | PE4 X_DIR +// PD5 WIFI_RXD | PE5 X_STEP +// PD6 WIFI_TXD | PE6 X_EN +// PD7 Z1_MIN | PE7 AXU_SCL +// PD8 X_MAX | PE8 BTN_EN1 +// PD9 E3_DIR | PE9 LCD_SCK +// PD10 E3_STEP | PE10 LCD_MOSI +// PD11 E3_EN | PE11 BEEPER +// PD12 E2_DIR | PE12 LCD_EN +// PD13 E2_STEP | PE13 KILL +// PD14 E2_EN | PE14 BTN_EN2 +// PD15 E1_DIR | PE15 BTN_ENC +//============================================================================= + +// EXP1 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 RS PE13 KILL BTN_ENC +// 9 BP PE11 BEEP BEEP +// 8 EN PE12 DOGLCD_CS LCDRS +// 7 MOSI PE10 DOGLCD_SCK LCDE +// 6 EN1 PE8 BTN_EN1 NC +// 5 SCK PE9 DOGLCD_MOSI LCD4 +// 4 ENC PE15 BTN_ENC NC +// 3 EN2 PE14 BTN_EN2 NC +// 2 +5V +5V +// 1 GND GND + +#define EXP1_03_PIN PE14 +#define EXP1_04_PIN PE15 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE8 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE12 +#define EXP1_09_PIN PE11 +#define EXP1_10_PIN PE13 + +// EXP2 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 +// 9 +// 8 RX0 PA9 UART1_RX +// 7 TX0 PA10 UART1_TX BTN_EN2 +// 6 CS3 PA15 +// 5 MISO3 PB4 BTN_EN1 +// 4 MOSI3 PB5 KILL +// 3 SCK3 PB3 +// 2 +5V +5V +// 1 GND GND + +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB5 +#define EXP2_05_PIN PB4 +#define EXP2_06_PIN PA15 +#define EXP2_07_PIN PA10 +#define EXP2_08_PIN PA9 + +// AUX1 connector +// 1 +5V +// 2 GND +// 3 RX3 PB11 UART3_RX +// 4 TX3 PB10 UART3_TX +// 5 SCL PE7 +// 6 SDA PC0 + +// WiFi +// 1 +5V +// 2 GND +// 3 WIFI_TXD PD5 UART2_RX +// 4 WIFI_RXD PD6 UART2_TX +// 5 WIFI_RST PC14 +// 6 WIFI_CS PC15 +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PB9 +#define SERVO2_PIN PB7 +#define SERVO3_PIN PB6 + +// +// Limit Switches +// +#define X_MIN_PIN PC13 +#define X_MAX_PIN PD8 +#define Y_MIN_PIN PE3 +#define Y_MAX_PIN PB14 +#define Z_MIN_PIN PD7 +#define Z_MAX_PIN PB13 + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PC8 +#endif + +// +// Steppers +// +#if ENABLED(COREXY) + #define X_ENABLE_PIN PE0 + #define X_STEP_PIN PE1 + #define X_DIR_PIN PE2 + + #define Y_ENABLE_PIN PE6 + #define Y_STEP_PIN PE5 + #define Y_DIR_PIN PE4 +#else + #define X_ENABLE_PIN PE6 + #define X_STEP_PIN PE5 + #define X_DIR_PIN PE4 + + #define Y_ENABLE_PIN PE0 + #define Y_STEP_PIN PE1 + #define Y_DIR_PIN PE2 +#endif + +#define Z_ENABLE_PIN PD2 +#define Z_STEP_PIN PD3 +#define Z_DIR_PIN PD4 + +#ifdef OPTION_DUALZ_DRIVE + #define Z2_ENABLE_PIN PC11 + #define Z2_STEP_PIN PC12 + #define Z2_DIR_PIN PD0 +#endif + +#ifdef OPTION_Z2_ENDSTOP + #define Z2_MIN_PIN PD1 + #define Z2_MAX_PIN PB12 +#endif + +#ifdef SWITCH_EXTRUDER_SEQUENCE + #define E3_ENABLE_PIN PC10 + #define E3_STEP_PIN PA8 + #define E3_DIR_PIN PC9 + + #define E2_STEP_PIN PC6 + #define E2_DIR_PIN PD15 + #define E2_ENABLE_PIN PC7 + + #define E1_STEP_PIN PD13 + #define E1_DIR_PIN PD12 + #define E1_ENABLE_PIN PD14 + + #define E0_STEP_PIN PD10 + #define E0_DIR_PIN PD9 + #define E0_ENABLE_PIN PD11 +#else + #define E0_ENABLE_PIN PC10 + #define E0_STEP_PIN PA8 + #define E0_DIR_PIN PC9 + + #define E1_STEP_PIN PC6 + #define E1_DIR_PIN PD15 + #define E1_ENABLE_PIN PC7 + + #define E2_STEP_PIN PD13 + #define E2_DIR_PIN PD12 + #define E2_ENABLE_PIN PD14 + + #define E3_STEP_PIN PD10 + #define E3_DIR_PIN PD9 + #define E3_ENABLE_PIN PD11 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC2 // TH0 +#define TEMP_BED_PIN PC3 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC5 // HEATER0 +#define HEATER_BED_PIN PA2 // HOT BED + +#if ENABLED(OPTION_CHAMBER) + #define TEMP_CHAMBER_PIN PC1 + #define HEATER_CHAMBER_PIN PB0 +#else + #define TEMP_1_PIN PC1 // TH1 + #define HEATER_1_PIN PB0 // HEATER1 +#endif + +#define FAN_PIN PB1 // FAN1 +#define FAN1_PIN PB8 // FAN2 + +// +// Misc. Functions +// + +//#define POWER_LOSS_PIN PB15 +#define LED_PIN PA0 +#define SUICIDE_PIN PA3 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// WiFi Functions +#define WIFI_RST PC15 +#define WIFI_EN PC14 + +// +// LCD / Controller +// +#if ENABLED(ZONESTAR_12864LCD) + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_04_PIN +#elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_07_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_05_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN EXP2_04_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_07_PIN + #define BTN_ENC EXP1_10_PIN +#elif ENABLED(ZONESTAR_DWIN_LCD) + // Connect to EXP2 connector + #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" + #define BEEPER_PIN EXP2_06_PIN + #define KILL_PIN PC0 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_04_PIN + #define BTN_ENC EXP2_05_PIN +#endif + +#if ENABLED(ZONESTAR_LCD2004_KNOB) + #define LCDSCREEN_NAME "LCD2004 KNOB" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_07_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_04_PIN + #define BTN_EN1 EXP2_07_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_10_PIN + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN EXP2_04_PIN +#elif ENABLED(ZONESTAR_LCD2004_ADCKEY) + #define LCDSCREEN_NAME "LCD2004 5KEY" + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_07_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_04_PIN + #define ADC_KEYPAD_PIN PC0 // PIN6 of AUX1 +#endif + +#if HAS_MARLINUI_U8GLIB + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#endif + +// Remap SERVO0 PIN for BLTouch +#if ENABLED(BLTOUCH_ON_EXP1) + // BLTouch connected to EXP1 + #define BLTOUCH_PROBE_PIN EXP1_06_PIN + #define BLTOUCH_GND_PIN EXP1_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP1_03_PIN +#elif ENABLED(BLTOUCH_ON_EXP2) + // BLTouch connected to EXP2 + #define BLTOUCH_PROBE_PIN EXP2_03_PIN + #define BLTOUCH_GND_PIN EXP2_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP2_06_PIN +#else + #define BLTOUCH_PROBE_PIN PB13 +#endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h new file mode 100644 index 0000000000..5bbf43bbfa --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -0,0 +1,328 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "env_validate.h" + +#define BOARD_INFO_NAME "ZONESTAR ZM3E4 V2.0" + +//#define DISABLE_DEBUG +#define DISABLE_JTAG + +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800) // 2KB + #define EEPROM_START_ADDRESS (0x08000000 + (STM32_FLASH_SIZE) * 1024 - 2 * EEPROM_PAGE_SIZE) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +//#define OPTION_DUALZ_DRIVE +//#define OPTION_Z2_ENDSTOP +//#define OPTION_REPEAT_PRINTING +//#define SWITCH_EXTRUDER_SEQUENCE + +//============================================================================= +// Zonestar ZM3E4 V2.0 (STM32F103VET6) board pin assignments +//============================================================================= +// PA0 | PB0 HEAT_1 | PC0 AUX_SDA +// PA1 | PB1 FAN1 | PC1 TEMP_E1 +// PA2 HEAT_BED | PB2 BOOT1 | PC2 TEMP_E0 +// PA3 PWR_HOLD | PB3 SPI3_SCK | PC3 TEMP_BED +// PA4 SD_CS | PB4 SPI3_MISO | PC4 SD_DETECT +// PA5 SD_SCK | PB5 SPI3_MOSI | PC5 HEAT_0 +// PA6 SD_MISO | PB6 SERVO3 | PC6 E1_STEP +// PA7 SD_MOSI | PB7 SERVO2 | PC7 E1_EN +// PA8 X_DIR | PB8 FAN2/SERVO1 | PC8 FIL_RUNOUT_PIN +// PA9 UART1_RX | PB9 SERVO0 | PC9 E0_DIR +// PA10 UART1_TX | PB10 TX3 | PC10 E0_EN +// PA11 USB_D- | PB11 RX3 | PC11 Z2_EN +// PA12 USB_D+ | PB12 LED | PC12 Z2_STEP +// PA13 SWD_SDO | PB13 Z1_MAX | PC13 X_MIN +// PA14 SWD_SCK | PB14 Y_MAX | PC14 WIFI_RST +// PA15 SPI3_CS | PB15 PWR_DET | PC15 WIFI_CS +// PD0 Z2_DIR | PE0 Y_EN +// PD1 Z2_MIN | PE1 Y_STEP +// PD2 Z1_EN | PE2 Y_DIR +// PD3 Z1_STEP | PE3 Y_MIN +// PD4 Z1_DIR | PE4 X_DIR +// PD5 WIFI_RXD | PE5 X_STEP +// PD6 WIFI_TXD | PE6 X_EN +// PD7 Z1_MIN | PE7 AUX_SCL +// PD8 X_MAX | PE8 BTN_EN1 +// PD9 E3_DIR | PE9 LCD_SCK +// PD10 E3_STEP | PE10 LCD_MOSI +// PD11 E3_EN | PE11 BEEPER +// PD12 E2_DIR | PE12 LCD_EN +// PD13 E2_STEP | PE13 KILL +// PD14 E2_EN | PE14 BTN_EN2 +// PD15 E1_DIR | PE15 BTN_ENC + +//============================================================================= +// EXP1 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 RS PE13 KILL BTN_ENC +// 9 BP PE11 BEEP BEEP +// 8 EN PE12 DOGLCD_CS LCDRS +// 7 MOSI PE10 DOGLCD_SCK LCDE +// 6 EN1 PE8 BTN_EN1 NC +// 5 SCK PE9 DOGLCD_MOSI LCD4 +// 4 ENC PE15 BTN_ENC NC +// 3 EN2 PE14 BTN_EN2 NC +// 2 +5V +// 1 GND + +#define EXP1_03_PIN PE14 +#define EXP1_04_PIN PE15 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE8 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE12 +#define EXP1_09_PIN PE11 +#define EXP1_10_PIN PE13 + +// EXP2 connector +// MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 +// 10 SDA PC0 +// 9 SCL PE7 +// 8 RX1 PA9 UART1_RX +// 7 TX1 PA10 UART1_TX BTN_EN2 +// 6 CS3 PA15 +// 5 MISO3 PB4 BTN_EN1 +// 4 MOSI3 PB5 KILL +// 3 SCK3 PB3 +// 2 +5V +// 1 GND + +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB5 +#define EXP2_05_PIN PB4 +#define EXP2_06_PIN PA15 +#define EXP2_07_PIN PA10 +#define EXP2_08_PIN PA9 +#define EXP2_09_PIN PE7 +#define EXP2_10_PIN PC0 + +// AUX1 connector +// 1 +5V +// 2 GND +// 3 RX3 PB11 UART3_RX +// 4 TX3 PB10 UART3_TX +// 5 SCL PE7 +// 6 SDA PC0 + +// WiFi +// 1 +5V +// 2 GND +// 3 WIFI_TXD PD5 UART2_RX +// 4 WIFI_RXD PD6 UART2_TX +// 5 WIFI_RST PC14 +// 6 WIFI_CS PC15 +//============================================================================= + +// +// Servos +// +#define SERVO0_PIN PB9 +//#define SERVO1_PIN PB8 +#define SERVO2_PIN PB7 +#define SERVO3_PIN PB6 + +// +// Limit Switches +// +#define X_MIN_PIN PC13 +#define Y_MIN_PIN PE3 +#define Z_MIN_PIN PD7 +#define X_MAX_PIN PD8 +#define Y_MAX_PIN PB14 +#define Z_MAX_PIN PB13 + +#ifdef OPTION_Z2_ENDSTOP + #define Z2_MIN_PIN PD1 + #define Z2_MAX_PIN PB12 +#endif + +// +// Steppers +// +#if ENABLED(COREXY) + #define X_ENABLE_PIN PE0 + #define X_STEP_PIN PE1 + #define X_DIR_PIN PE2 + + #define Y_ENABLE_PIN PE6 + #define Y_STEP_PIN PE5 + #define Y_DIR_PIN PE4 +#else + #define X_ENABLE_PIN PE6 + #define X_STEP_PIN PE5 + #define X_DIR_PIN PE4 + + #define Y_ENABLE_PIN PE0 + #define Y_STEP_PIN PE1 + #define Y_DIR_PIN PE2 +#endif + +#define Z_ENABLE_PIN PD2 +#define Z_STEP_PIN PD3 +#define Z_DIR_PIN PD4 + +#ifdef OPTION_DUALZ_DRIVE + #define Z2_ENABLE_PIN PC11 + #define Z2_STEP_PIN PC12 + #define Z2_DIR_PIN PD0 +#endif + +#ifdef OPTION_REPEAT_PRINTING + #define REPRINT_STOP_PIN PD8 // X_MAX_PIN + #define FORWARD_PIN PA13 + #define BACK_PIN PA14 +#endif + +#ifdef SWITCH_EXTRUDER_SEQUENCE + #define E3_ENABLE_PIN PC10 + #define E3_STEP_PIN PA8 + #define E3_DIR_PIN PC9 + + #define E2_STEP_PIN PC6 + #define E2_DIR_PIN PD15 + #define E2_ENABLE_PIN PC7 + + #define E1_STEP_PIN PD13 + #define E1_DIR_PIN PD12 + #define E1_ENABLE_PIN PD14 + + #define E0_STEP_PIN PD10 + #define E0_DIR_PIN PD9 + #define E0_ENABLE_PIN PD11 +#else + #define E0_ENABLE_PIN PC10 + #define E0_STEP_PIN PA8 + #define E0_DIR_PIN PC9 + + #define E1_STEP_PIN PC6 + #define E1_DIR_PIN PD15 + #define E1_ENABLE_PIN PC7 + + #define E2_STEP_PIN PD13 + #define E2_DIR_PIN PD12 + #define E2_ENABLE_PIN PD14 + + #define E3_STEP_PIN PD10 + #define E3_DIR_PIN PD9 + #define E3_ENABLE_PIN PD11 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC2 // TH0 +//#define TEMP_1_PIN PC1 // TH1 +#define TEMP_BED_PIN PC3 // TB1 + +// +// Heaters +// +#define HEATER_0_PIN PC5 // HEATER0 +//#define HEATER_1_PIN PB0 // HEATER1 +#define HEATER_BED_PIN PA2 // HOT BED + +// +// Fans +// +#define FAN_PIN PB1 // FAN1 +#define FAN1_PIN PB8 // FAN2 + +// +// Misc. Functions +// +//#define POWER_LOSS_PIN PB15 +#define LED_PIN PA0 +#define SUICIDE_PIN PA3 +#define FIL_RUNOUT_PIN PC8 + +// +// SD card +// +#define ENABLE_SPI1 +#define SD_DETECT_PIN PC4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN PA4 + +// WiFi Functions +#define WIFI_RST PC15 +#define WIFI_EN PC14 + +#if ENABLED(ZONESTAR_12864LCD) + #define LCDSCREEN_NAME "ZONESTAR LCD12864" + #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_09_PIN + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_04_PIN +#elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" + #define LCD_PINS_RS EXP2_08_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP2_05_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP2_07_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP2_10_PIN + #define KILL_PIN EXP2_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP2_04_PIN +#elif ENABLED(ZONESTAR_DWIN_LCD) + // Connect to EXP2 connector + #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" + #define BEEPER_PIN EXP2_06_PIN // PE11 + #define KILL_PIN -1 // EXP1_10_PIN + #define BTN_EN2 EXP2_04_PIN // PE8 + #define BTN_EN1 EXP2_03_PIN // PE14 + #define BTN_ENC EXP2_05_PIN // PE15 +#endif + +#if HAS_MARLINUI_U8GLIB + #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns + #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns +#endif + +// Remap SERVO0 PIN for BLTouch +#if ENABLED(BLTOUCH_ON_EXP1) + // BLTouch connected to EXP1 + #define BLTOUCH_PROBE_PIN EXP1_06_PIN + #define BLTOUCH_GND_PIN EXP1_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP1_03_PIN +#elif ENABLED(BLTOUCH_ON_EXP2) + // BLTouch connected to EXP2 + #define BLTOUCH_PROBE_PIN EXP2_03_PIN + #define BLTOUCH_GND_PIN EXP2_04_PIN + #undef SERVO0_PIN + #define SERVO0_PIN EXP2_06_PIN +#else + #define BLTOUCH_PROBE_PIN PB13 // Z1_MAX +#endif diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h index c4349d182b..d85bbf7bed 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h @@ -223,13 +223,16 @@ #define BTN_ENC PH8 #endif +// +// SD card +// #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #define SOFTWARE_SPI #define SDSS PA15 -#define SS_PIN SDSS +#define SD_SS_PIN SDSS #define SD_SCK_PIN PC10 #define SD_MISO_PIN PC11 #define SD_MOSI_PIN PC12 diff --git a/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld new file mode 100644 index 0000000000..2404e7cac9 --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_256K.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08005000, LENGTH = 256K - 20K - 4K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld new file mode 100644 index 0000000000..821c8ebbfe --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/ZONESTAR_ZM3E_512K.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08005000, LENGTH = 512K - 20K - 4K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/tests/STM32F103RC_fysetc b/buildroot/tests/STM32F103RC_fysetc_maple similarity index 100% rename from buildroot/tests/STM32F103RC_fysetc rename to buildroot/tests/STM32F103RC_fysetc_maple diff --git a/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple b/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple new file mode 100755 index 0000000000..8cbb84fb80 --- /dev/null +++ b/buildroot/tests/STM32F103VE_ZM3E4V2_USB_maple @@ -0,0 +1,14 @@ +#!/usr/bin/env bash +# +# Build tests for STM32F103VE_ZM3E4V2_USB +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_ZONESTAR_ZM3E4V2 SERIAL_PORT 1 +exec_test $1 $2 "Zonestar ZM3E4 V2.0" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/jgaurora_a5s_a1 b/buildroot/tests/jgaurora_a5s_a1_maple similarity index 100% rename from buildroot/tests/jgaurora_a5s_a1 rename to buildroot/tests/jgaurora_a5s_a1_maple diff --git a/buildroot/tests/mks_robin_lite b/buildroot/tests/mks_robin_lite_maple similarity index 100% rename from buildroot/tests/mks_robin_lite rename to buildroot/tests/mks_robin_lite_maple diff --git a/buildroot/tests/mks_robin_pro b/buildroot/tests/mks_robin_pro_maple similarity index 100% rename from buildroot/tests/mks_robin_pro rename to buildroot/tests/mks_robin_pro_maple diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 0258fb3b7c..c184dc247c 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -357,3 +357,46 @@ extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/custom_board.py build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 + +# +# Zonestar ZM3E2 V1.0 / ZM3E4 V1.0 / ZM3E4 V2.0 +# +# STM32F103RC_ZM3E2_USB_maple ........... RCT6 with 256K +# STM32F103VC_ZM3E4_USB_maple ........... VCT6 with 256K +# STM32F103VE_ZM3E4V2_USB_maple ......... VET6 with 512K +# +[ZONESTAR_ZM3E_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +platform_packages = tool-stm32duino +board_build.address = 0x08005000 +board_build.offset = 0x5000 +board_upload.maximum_size = 237568 +extra_scripts = ${common.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/offset_and_rename.py +build_flags = ${common_stm32f1.build_flags} + -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB +lib_deps = USBComposite for STM32F1@0.91 +lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper + +[env:STM32F103RC_ZM3E2_USB_maple] +platform = ${ZONESTAR_ZM3E_maple.platform} +extends = ZONESTAR_ZM3E_maple +board = genericSTM32F103RC +board_build.ldscript = ZONESTAR_ZM3E_256K.ld + +[env:STM32F103VC_ZM3E4_USB_maple] +platform = ${ZONESTAR_ZM3E_maple.platform} +extends = ZONESTAR_ZM3E_maple +board = genericSTM32F103VC +board_build.ldscript = ZONESTAR_ZM3E_256K.ld +build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 + +[env:STM32F103VE_ZM3E4V2_USB_maple] +platform = ${ZONESTAR_ZM3E_maple.platform} +extends = ZONESTAR_ZM3E_maple +board = genericSTM32F103VE +board_build.ldscript = ZONESTAR_ZM3E_512K.ld +build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 +board_upload.maximum_size = 499712 diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 1185e8f84d..d03898a12e 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -374,3 +374,43 @@ extra_scripts = ${stm32_variant.extra_scripts} platform = ${common_stm32.platform} extends = env:chitu_f103 build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX + +# +# Zonestar ZM3E2 V1.0 / ZM3E4 V1.0 / ZM3E4 V2.0 +# +# STM32F103RC_ZM3E2_USB ........... RCT6 with 256K +# STM32F103VC_ZM3E4_USB ........... VCT6 with 256K +# STM32F103VE_ZM3E4V2_USB ......... VET6 with 512K +# +[ZONESTAR_ZM3E] +platform = ${common_stm32.platform} +extends = stm32_variant +platform_packages = ${stm_flash_drive.platform_packages} +board_upload.offset_address = 0x08005000 +board_build.offset = 0x5000 +board_upload.maximum_size = 237568 +extra_scripts = ${stm32_variant.extra_scripts} +build_flags = ${common_stm32.build_flags} + -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DUSE_USB_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DUSBD_USE_CDC_MSC +build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC + +[env:STM32F103RC_ZM3E2_USB] +platform = ${ZONESTAR_ZM3E.platform} +extends = ZONESTAR_ZM3E +board = genericSTM32F103RC +board_build.variant = MARLIN_F103Rx + +[env:STM32F103VC_ZM3E4_USB] +platform = ${ZONESTAR_ZM3E.platform} +extends = ZONESTAR_ZM3E +board = genericSTM32F103VC +board_build.variant = MARLIN_F103Vx +build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=1 + +[env:STM32F103VE_ZM3E4V2_USB] +platform = ${ZONESTAR_ZM3E.platform} +extends = ZONESTAR_ZM3E +board = genericSTM32F103VE +board_build.variant = MARLIN_F103Vx +build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=1 +board_upload.maximum_size = 499712 From 47281012d9c7940206b8c7587c35b05c1288733d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 9 Aug 2021 00:59:01 +0000 Subject: [PATCH 0527/2168] [cron] Bump distribution date (2021-08-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c34cb52361..4020a3ae4c 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-08" +//#define STRING_DISTRIBUTION_DATE "2021-08-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ad1dff604c..e869278c76 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 "2021-08-08" + #define STRING_DISTRIBUTION_DATE "2021-08-09" #endif /** From 331cc5fd6a044e568dbe789ecd0b732b6eba454f Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 8 Aug 2021 19:25:17 -0700 Subject: [PATCH 0528/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20some=20Simulator?= =?UTF-8?q?=20on=20Windows=20issues=20(#22516)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 10 +- .../NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp | 2 +- .../src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp | 4 +- .../shared/cpu_exception/exception_arm.cpp | 4 +- Marlin/src/core/serial.cpp | 11 -- Marlin/src/core/serial.h | 27 ++--- Marlin/src/core/serial_base.h | 112 +++++++++++------- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/feature/tmc_util.h | 2 +- ini/native.ini | 4 +- 10 files changed, 93 insertions(+), 85 deletions(-) diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index 2aeeb52e92..7ba14574d0 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -21,6 +21,8 @@ * Support routines for X86_64 */ +#pragma once + /** * Translation of routines & variables used by pinsDebug.h */ @@ -37,16 +39,16 @@ #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // active ADC function/mode/code values for PINSEL registers -constexpr int8_t ADC_pin_mode(pin_t pin) { +inline constexpr int8_t ADC_pin_mode(pin_t pin) { return (-1); } -int8_t get_pin_mode(pin_t pin) { +inline int8_t get_pin_mode(pin_t pin) { if (!VALID_PIN(pin)) return -1; return 0; } -bool GET_PINMODE(pin_t pin) { +inline bool GET_PINMODE(pin_t pin) { int8_t pin_mode = get_pin_mode(pin); if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin return false; @@ -54,6 +56,6 @@ bool GET_PINMODE(pin_t pin) { return (Gpio::getMode(pin) != 0); //input/output state } -bool GET_ARRAY_IS_DIGITAL(pin_t pin) { +inline bool GET_ARRAY_IS_DIGITAL(pin_t pin) { return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); } diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp index e95c6ebfbd..c77c3d30f0 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -59,7 +59,7 @@ #if ENABLED(U8GLIB_ST7920) -#include +#include #include "../../shared/Delay.h" #undef SPI_SPEED diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 8e0ac9c7df..085954803c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -63,7 +63,7 @@ #define SPI_SPEED 2 // About 2 MHz #include -#include +#include #ifdef __cplusplus extern "C" { @@ -209,7 +209,7 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt #endif #elif !ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB - #include + #include uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {return 0;} #endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 #endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index 9a1b4caf8d..0f0f7c4807 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -322,7 +322,7 @@ void hook_cpu_exceptions() { unsigned long *vecAddr = (unsigned long*)get_vtor(); SERIAL_ECHOPGM("Vector table addr: "); - SERIAL_PRINTLN(get_vtor(), HEX); + SERIAL_PRINTLN(get_vtor(), PrintBase::Hex); #ifdef VECTOR_TABLE_SIZE uint32_t vec_size = VECTOR_TABLE_SIZE; @@ -349,7 +349,7 @@ void hook_cpu_exceptions() { alignas(128) static unsigned long vectable[VECTOR_TABLE_SENTINEL]; SERIAL_ECHOPGM("Detected vector table size: "); - SERIAL_PRINTLN(vec_size, HEX); + SERIAL_PRINTLN(vec_size, PrintBase::Hex); #endif uint32_t defaultFaultHandler = vecAddr[(unsigned)7]; diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 2e3a39b66a..50cc50ad57 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -76,17 +76,6 @@ void serialprintPGM(PGM_P str) { void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); } void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); } -void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); } -void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -void serial_echopair_PGM(PGM_P const s_P, unsigned char v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } - void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post/*=nullptr*/) { diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 7f96a30d6f..dfcf23ddb6 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -177,8 +177,8 @@ void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } template void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); } -template -void SERIAL_PRINTLN(T x, U y) { SERIAL_IMPL.println(x, y); } +template +void SERIAL_PRINTLN(T x, PrintBase y) { SERIAL_IMPL.println(x, y); } // Flush the serial port inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); } @@ -293,21 +293,18 @@ void serialprintPGM(PGM_P str); // // Functions for serial printing from PROGMEM. (Saves loads of SRAM.) // -void serial_echopair_PGM(PGM_P const s_P, serial_char_t v); -void serial_echopair_PGM(PGM_P const s_P, const char *v); -void serial_echopair_PGM(PGM_P const s_P, char v); -void serial_echopair_PGM(PGM_P const s_P, int v); -void serial_echopair_PGM(PGM_P const s_P, long v); -void serial_echopair_PGM(PGM_P const s_P, float v); -void serial_echopair_PGM(PGM_P const s_P, double v); -void serial_echopair_PGM(PGM_P const s_P, unsigned char v); -void serial_echopair_PGM(PGM_P const s_P, unsigned int v); -void serial_echopair_PGM(PGM_P const s_P, unsigned long v); +inline void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); } + +inline void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } +inline void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } +inline void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } + +// Default implementation for types without a specialization. Handles integers. +template +void serial_echopair_PGM(PGM_P const s_P, T v) { serialprintPGM(s_P); SERIAL_ECHO(v); } + inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); } inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); } -#if __INTPTR_WIDTH__ != __SIZE_WIDTH__ - inline void serial_echopair_PGM(PGM_P const s_P, size_t v) { serial_echopair_PGM(s_P, (long int)v); } -#endif void serial_echo_start(); void serial_error_start(); diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index d8090eb83a..a5abd67d87 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -74,12 +74,12 @@ CALL_IF_EXISTS_IMPL(SerialFeature, features, SerialFeature::None); // for any type other than double/float. For double/float, a conversion exists so the call will be invisible. struct EnsureDouble { double a; - FORCE_INLINE operator double() { return a; } + operator double() { return a; } // If the compiler breaks on ambiguity here, it's likely because print(X, base) is called with X not a double/float, and // a base that's not a PrintBase value. This code is made to detect the error. You MUST set a base explicitly like this: // SERIAL_PRINT(v, PrintBase::Hex) - FORCE_INLINE EnsureDouble(double a) : a(a) {} - FORCE_INLINE EnsureDouble(float a) : a(a) {} + EnsureDouble(double a) : a(a) {} + EnsureDouble(float a) : a(a) {} }; // Using Curiously-Recurring Template Pattern here to avoid virtual table cost when compiling. @@ -136,70 +136,90 @@ struct SerialBase { void flushTX() { CALL_IF_EXISTS(void, SerialChild, flushTX); } // Glue code here - FORCE_INLINE void write(const char *str) { while (*str) write(*str++); } - FORCE_INLINE void write(const uint8_t *buffer, size_t size) { while (size--) write(*buffer++); } - FORCE_INLINE void print(const char *str) { write(str); } + void write(const char *str) { while (*str) write(*str++); } + void write(const uint8_t *buffer, size_t size) { while (size--) write(*buffer++); } + void print(char *str) { write(str); } + void print(const char *str) { write(str); } // No default argument to avoid ambiguity - NO_INLINE void print(char c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); } - NO_INLINE void print(unsigned char c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); } - NO_INLINE void print(int c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); } - NO_INLINE void print(unsigned int c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); } - void print(unsigned long c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); } - void print(long c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); } - void print(EnsureDouble c, int digits) { printFloat(c, digits); } + + // Define print for every fundamental integer type, to ensure that all redirect properly + // to the correct underlying implementation. + + // Prints are performed with a single size, to avoid needing multiple print functions. + // The fixed integer size used for prints will be the larger of long or a pointer. + #if __LONG_WIDTH__ >= __INTPTR_WIDTH__ + typedef long int_fixed_print_t; + typedef unsigned long uint_fixed_print_t; + #else + typedef intptr_t int_fixed_print_t; + typedef uintptr_t uint_fixed_print_t; + + FORCE_INLINE void print(intptr_t c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(uintptr_t c, PrintBase base) { printNumber_unsigned(c, base); } + #endif + + FORCE_INLINE void print(char c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(short c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(int c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(long c, PrintBase base) { printNumber_signed(c, base); } + FORCE_INLINE void print(unsigned char c, PrintBase base) { printNumber_unsigned(c, base); } + FORCE_INLINE void print(unsigned short c, PrintBase base) { printNumber_unsigned(c, base); } + FORCE_INLINE void print(unsigned int c, PrintBase base) { printNumber_unsigned(c, base); } + FORCE_INLINE void print(unsigned long c, PrintBase base) { printNumber_unsigned(c, base); } + + + void print(EnsureDouble c, int digits) { printFloat(c, digits); } // Forward the call to the former's method - FORCE_INLINE void print(char c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(unsigned char c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(int c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(unsigned int c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(unsigned long c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(long c) { print(c, PrintBase::Dec); } - FORCE_INLINE void print(double c) { print(c, 2); } - FORCE_INLINE void println(const char s[]) { print(s); println(); } - FORCE_INLINE void println(char c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(unsigned char c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(int c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(unsigned int c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(long c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(unsigned long c, PrintBase base) { print(c, base); println(); } - FORCE_INLINE void println(double c, int digits) { print(c, digits); println(); } - FORCE_INLINE void println() { write('\r'); write('\n'); } + // Default implementation for anything without a specialization + // This handles integers since they are the most common + template + void print(T c) { print(c, PrintBase::Dec); } + + void print(float c) { print(c, 2); } + void print(double c) { print(c, 2); } + + void println(char *s) { print(s); println(); } + void println(const char *s) { print(s); println(); } + void println(float c, int digits) { print(c, digits); println(); } + void println(double c, int digits) { print(c, digits); println(); } + void println() { write('\r'); write('\n'); } + + // Default implementations for types without a specialization. Handles integers. + template + void println(T c, PrintBase base) { print(c, base); println(); } + + template + void println(T c) { println(c, PrintBase::Dec); } // Forward the call to the former's method - FORCE_INLINE void println(char c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(unsigned char c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(int c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(unsigned int c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(unsigned long c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(long c) { println(c, PrintBase::Dec); } - FORCE_INLINE void println(double c) { println(c, 2); } + void println(float c) { println(c, 2); } + void println(double c) { println(c, 2); } // Print a number with the given base - NO_INLINE void printNumber(unsigned long n, const uint8_t base) { - if (!base) return; // Hopefully, this should raise visible bug immediately - + NO_INLINE void printNumber_unsigned(uint_fixed_print_t n, PrintBase base) { if (n) { unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 int8_t i = 0; while (n) { - buf[i++] = n % base; - n /= base; + buf[i++] = n % (uint_fixed_print_t)base; + n /= (uint_fixed_print_t)base; } while (i--) write((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); } else write('0'); } - void printNumber(signed long n, const uint8_t base) { - if (base == 10 && n < 0) { + + NO_INLINE void printNumber_signed(int_fixed_print_t n, PrintBase base) { + if (base == PrintBase::Dec && n < 0) { n = -n; // This works because all platforms Marlin's builds on are using 2-complement encoding for negative number // On such CPU, changing the sign of a number is done by inverting the bits and adding one, so if n = 0x80000000 = -2147483648 then // -n = 0x7FFFFFFF + 1 => 0x80000000 = 2147483648 (if interpreted as unsigned) or -2147483648 if interpreted as signed. // On non 2-complement CPU, there would be no possible representation for 2147483648. write('-'); } - printNumber((unsigned long)n , base); + printNumber_unsigned((uint_fixed_print_t)n , base); } // Print a decimal number @@ -218,7 +238,7 @@ struct SerialBase { // Extract the integer part of the number and print it unsigned long int_part = (unsigned long)number; double remainder = number - (double)int_part; - printNumber(int_part, 10); + printNumber_unsigned(int_part, PrintBase::Dec); // Print the decimal point, but only if there are digits beyond if (digits) { @@ -227,7 +247,7 @@ struct SerialBase { while (digits--) { remainder *= 10.0; unsigned long toPrint = (unsigned long)remainder; - printNumber(toPrint, 10); + printNumber_unsigned(toPrint, PrintBase::Dec); remainder -= toPrint; } } diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 48b26cc101..99cfd996c8 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -208,7 +208,7 @@ #if ENABLED(STOP_ON_ERROR) void report_driver_error(const TMC_driver_data &data) { SERIAL_ECHOPGM(" driver error detected: 0x"); - SERIAL_PRINTLN(data.drv_status, HEX); + SERIAL_PRINTLN(data.drv_status, PrintBase::Hex); if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); TERN_(TMC_DEBUG, tmc_report_all()); diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index c878d86fae..87780486eb 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -330,7 +330,7 @@ void tmc_print_current(TMC &st) { void tmc_print_sgt(TMC &st) { st.printLabel(); SERIAL_ECHOPGM(" homing sensitivity: "); - SERIAL_PRINTLN(st.homing_threshold(), DEC); + SERIAL_PRINTLN(st.homing_threshold(), PrintBase::Dec); } #endif diff --git a/ini/native.ini b/ini/native.ini index b40ea836da..548e791f5a 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -120,11 +120,11 @@ build_unflags = ${simulator_macos.build_unflags} # Simulator for Windows 10 # # MSYS2 mingw-w64-x86_64 with these packages: -# pacman -S --needed base-devel mingw-w64-x86_64-toolchain mingw64/mingw-w64-x86_64-glm mingw64/mingw-w64-x86_64-SDL2 mingw64/mingw-w64-x86_64-SDL2_net +# pacman -S --needed base-devel mingw-w64-x86_64-toolchain mingw64/mingw-w64-x86_64-glm mingw64/mingw-w64-x86_64-SDL2 mingw64/mingw-w64-x86_64-SDL2_net mingw-w64-x86_64-dlfcn # [env:simulator_windows] platform = ${simulator_common.platform} extends = simulator_common src_build_flags = ${simulator_common.src_build_flags} -fpermissive -build_flags = ${simulator_common.build_flags} ${simulator_common.debug_build_flags} -fno-stack-protector -Wl,-subsystem,windows -ldl -lmingw32 -lSDL2main -lSDL2 -lSDL2_net -lopengl32 -lssp +build_flags = ${simulator_common.build_flags} ${simulator_common.debug_build_flags} -IC:\\msys64\\mingw64\\include\\SDL2 -fno-stack-protector -Wl,-subsystem,windows -ldl -lmingw32 -lSDL2main -lSDL2 -lSDL2_net -lopengl32 -lssp build_type = debug From 76c10b3e02aa5a699ee68a36663337de60fea4e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 8 Aug 2021 21:31:10 -0500 Subject: [PATCH 0529/2168] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Define=20HAL?= =?UTF-8?q?=5FSTM32=20for=20HAL/STM32=20(#22537)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.cpp | 6 ++++-- Marlin/src/HAL/STM32/HAL_MinSerial.cpp | 6 ++++-- Marlin/src/HAL/STM32/HAL_SPI.cpp | 6 ++++-- Marlin/src/HAL/STM32/MarlinSPI.cpp | 4 ++-- Marlin/src/HAL/STM32/MarlinSerial.cpp | 6 ++++-- Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 6 ++++-- Marlin/src/HAL/STM32/Servo.cpp | 6 ++++-- Marlin/src/HAL/STM32/eeprom_flash.cpp | 6 ++++-- Marlin/src/HAL/STM32/eeprom_sdcard.cpp | 6 ++++-- Marlin/src/HAL/STM32/eeprom_sram.cpp | 6 ++++-- Marlin/src/HAL/STM32/eeprom_wired.cpp | 6 ++++-- Marlin/src/HAL/STM32/fast_pwm.cpp | 6 ++++-- Marlin/src/HAL/STM32/fastio.cpp | 6 ++++-- Marlin/src/HAL/STM32/msc_sd.cpp | 6 ++++-- Marlin/src/HAL/STM32/tft/gt911.cpp | 6 ++++-- Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 6 ++++-- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 6 ++++-- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 6 ++++-- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 6 ++++-- Marlin/src/HAL/STM32/timers.cpp | 6 ++++-- Marlin/src/HAL/STM32/usb_host.cpp | 5 +++-- Marlin/src/HAL/STM32/usb_serial.cpp | 6 ++++-- Marlin/src/HAL/STM32/watchdog.cpp | 6 ++++-- Marlin/src/HAL/platforms.h | 3 +++ .../src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 2 +- Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp | 6 ++++-- ini/features.ini | 2 +- ini/stm32-common.ini | 2 +- ini/stm32f0.ini | 2 +- ini/stm32f1-maple.ini | 2 +- ini/stm32f1.ini | 2 +- ini/stm32f4.ini | 2 +- ini/stm32f7.ini | 2 +- ini/stm32h7.ini | 2 +- 34 files changed, 105 insertions(+), 57 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index d8035a979d..9e7922e3a4 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "HAL.h" #include "usb_serial.h" @@ -165,4 +167,4 @@ void HAL_SYSTICK_Callback() { if (systick_user_callback) systick_user_callback(); } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp index c780a50c57..29826a890d 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" @@ -149,4 +151,4 @@ extern "C" { #endif #endif // POSTMORTEM_DEBUGGING -#endif // ARDUINO_ARCH_STM32 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index ba8e6bef19..85a5238b54 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -224,4 +226,4 @@ static SPISettings spiConfig; #endif // SOFTWARE_SPI -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index 41081dfb80..330c895697 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -19,7 +19,7 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) && !defined(STM32H7xx) +#if defined(HAL_STM32) && !defined(STM32H7xx) #include "MarlinSPI.h" @@ -165,4 +165,4 @@ uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) return 1; } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 && !STM32H7xx +#endif // HAL_STM32 && !STM32H7xx diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index d990d2f428..3caedc72eb 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -16,7 +16,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" #include "MarlinSerial.h" @@ -101,4 +103,4 @@ void MarlinSerial::_rx_complete_irq(serial_t *obj) { } } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 55e807f94e..914969f10c 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -320,4 +322,4 @@ extern "C" void SDIO_IRQHandler(void) { HAL_SD_IRQHandler(&hsd); } extern "C" void DMA_IRQ_HANDLER(void) { HAL_DMA_IRQHandler(&hdma_sdio); } #endif // SDIO_SUPPORT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index 54b1fbe670..a00186e0e7 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -107,4 +109,4 @@ void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriori } #endif // HAS_SERVOS -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index c3efec6062..e785e59249 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -272,4 +274,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // FLASH_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index 9cab90f109..77563b2ae5 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 /** * Implementation of EEPROM settings in SD Card @@ -88,4 +90,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uin } #endif // SDCARD_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index c391785234..687e7f55c2 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -65,4 +67,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // SRAM_EEPROM_EMULATION -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index 3346abbe4a..cf0468151e 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -75,4 +77,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // USE_WIRED_EEPROM -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index eaffb8cfa4..a8fcbe5f82 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" @@ -56,4 +58,4 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } #endif // NEEDS_HARDWARE_PWM -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index 5056e99d35..9e6a2fb658 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -20,7 +20,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -31,4 +33,4 @@ void FastIO_init() { FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index f95f75c5fc..4f85af0d44 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -13,7 +13,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" @@ -125,4 +127,4 @@ void MSC_SD_init() { } #endif // HAS_SD_HOST_DRIVE -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index 8c59a60f92..92e14edb20 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -199,4 +201,4 @@ bool GT911::getPoint(int16_t *x, int16_t *y) { } #endif // TFT_TOUCH_DEVICE_GT911 -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index f349eacac3..e9e712d5a3 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -178,4 +180,4 @@ void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou } #endif // HAS_FSMC_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 5b0c27e412..0549dbf108 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -384,4 +386,4 @@ void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou } #endif // HAS_LTDC_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 4e3f894a52..29a309f40e 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -240,4 +242,4 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun } #endif // HAS_SPI_TFT -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index d50c24d177..912e6c2db7 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfig.h" @@ -167,4 +169,4 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { } #endif // HAS_TFT_XPT2046 -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 7806198180..9b69323ef5 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -319,4 +321,4 @@ static constexpr bool verify_no_timer_conflicts() { // when hovering over it, making it easy to identify the conflicting timers. static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict."); -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index e45ab560e6..d2d1d69a1a 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -19,8 +19,9 @@ * along with this program. If not, see . * */ +#include "../platforms.h" -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" @@ -114,4 +115,4 @@ uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t b } #endif // USE_OTG_USB_HOST && USBHOST -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 0e23175fc0..959ca4ff43 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -16,7 +16,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" @@ -51,4 +53,4 @@ void USB_Hook_init() { } #endif // EMERGENCY_PARSER && USBD_USE_CDC -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index 09b403e7f2..72c74a2e3b 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../platforms.h" + +#ifdef HAL_STM32 #include "../../inc/MarlinConfigPre.h" @@ -46,4 +48,4 @@ void HAL_watchdog_refresh() { } #endif // USE_WATCHDOG -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC && !MAPLE_STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index 0b1b305f6d..28fe28e109 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -38,6 +38,9 @@ #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32F1/NAME) #elif defined(ARDUINO_ARCH_STM32) + #ifndef HAL_STM32 + #define HAL_STM32 + #endif #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME) #elif defined(ARDUINO_ARCH_ESP32) #define HAL_PATH(PATH, NAME) XSTR(PATH/ESP32/NAME) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 339b337e55..b4438a92b9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -288,7 +288,7 @@ // Remove compiler warning on an unused variable #ifndef UNUSED - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) + #ifdef HAL_STM32 #define UNUSED(X) (void)X #else #define UNUSED(x) ((void)(x)) diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp index 37fd2a81dc..6607e7531f 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(MAPLE_STM32F1) +#include "../../../HAL/platforms.h" + +#ifdef HAL_STM32 #include "../../../inc/MarlinConfigPre.h" @@ -349,4 +351,4 @@ int WifiSerial::write(uint8_t c) { } #endif // HAS_TFT_LVGL_UI && MKS_WIFI_MODULE -#endif // !__STM32F1__ +#endif // HAL_STM32 diff --git a/ini/features.ini b/ini/features.ini index 250540797d..e5b0fb3f66 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -31,7 +31,7 @@ LIB_INTERNAL_MAX31865 = src_filter=+ NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ I2C_AMMETER = peterus/INA226Lib@1.1.2 -USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 +USES_LIQUIDCRYSTAL = LiquidCrystal=https://github.com/MarlinFirmware/New-LiquidCrystal/archive/1.5.1.zip USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 HAS_WIRED_LCD = src_filter=+ diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 08b0f70b4d..1d3f858bf8 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -13,7 +13,7 @@ platform = ststm32@~12.1 board_build.core = stm32 build_flags = ${common.build_flags} - -std=gnu++14 + -std=gnu++14 -DHAL_STM32 -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index 6aebd88298..4559f115bd 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -10,7 +10,7 @@ # Naming Example: STM32F070CBT6 # # F : Foundation -# 0 : Cortex M0 core +# 0 : Cortex M0 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 70 : Line/Features # C : 48 pins (R:64 or 66, F:20) # B : 128KB Flash-memory (C:256KB, D:384KB, E:512KB, G:1024KB) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index c184dc247c..00ba93aa63 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -10,7 +10,7 @@ # Naming Example: STM32F103RCT6 # # F : Foundation (sometimes High Performance F2/F4) -# 1 : Cortex M1 core +# 1 : Cortex M3 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 03 : Line/Features # R : 64 or 66 pins (V:100, Z:144, I:176) # C : 256KB Flash-memory (D:384KB, E:512KB, G:1024KB) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index d03898a12e..f1cb078fd8 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -10,7 +10,7 @@ # Naming Example: STM32F103RCT6 # # F : Foundation (sometimes High Performance F2/F4) -# 1 : Cortex M3 core +# 1 : Cortex M3 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 03 : Line/Features # R : 64 or 66 pins (T:36, C:48, V:100, Z:144, I:176) # C : 256KB Flash-memory (B: 128KB, D:384KB, E:512KB, G:1024KB) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index b32efb83a9..62ac89d9fa 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -10,7 +10,7 @@ # Naming Example: STM32F401RGT6 # # F : Foundation (sometimes High Performance F2/F4) -# 4 : Cortex M4 core +# 4 : Cortex M4 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 01 : Line/Features # R : 64 or 66 pins (T:36, C:48 or 49, M:81, V:100, Z:144, I:176) # G : 1024KB Flash-memory (B:128KB, C:256KB, D:384KB, E:512KB) diff --git a/ini/stm32f7.ini b/ini/stm32f7.ini index 984b25162e..200740589b 100644 --- a/ini/stm32f7.ini +++ b/ini/stm32f7.ini @@ -10,7 +10,7 @@ # Naming Example: STM32F767ZIT6 # # F : Foundation (sometimes High Performance F2/F4) -# 7 : Cortex M7 core +# 7 : Cortex M7 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 67 : Line/Features # Z : 144 pins # I : 4096KB Flash-memory diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index 3d0753a235..fb39d4cc6b 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -10,7 +10,7 @@ # Naming Example: STM32H743IIT6 # # H : High Performance -# 7 : Cortex M7 core +# 7 : Cortex M7 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 43 : Line/Features # I : 176 pins # I : 2048KB Flash-memory From ae846c2cb2cdd9c57d62253dfddcf6dba15ab14a Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Mon, 9 Aug 2021 04:37:27 +0200 Subject: [PATCH 0530/2168] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Init=20FastIO?= =?UTF-8?q?=20before=20anything=20else=20(#22508)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.cpp | 2 -- Marlin/src/HAL/STM32/fastio.cpp | 2 +- Marlin/src/HAL/STM32/fastio.h | 1 + Marlin/src/HAL/STM32F1/pinsDebug.h | 6 +++--- Marlin/src/MarlinCore.cpp | 4 ++++ Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 9 +-------- 6 files changed, 10 insertions(+), 14 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 9e7922e3a4..a04a24c112 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -63,8 +63,6 @@ TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); // HAL initialization task void HAL_init() { - FastIO_init(); - // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index 9e6a2fb658..b34555b8c8 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -GPIO_TypeDef* FastIOPortMap[LastPort + 1]; +GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 }; void FastIO_init() { LOOP_L_N(i, NUM_DIGITAL_PINS) diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index 17751c44dd..4a48954471 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -38,6 +38,7 @@ extern GPIO_TypeDef * FastIOPortMap[]; // ------------------------ void FastIO_init(); // Must be called before using fast io macros +#define FASTIO_INIT() FastIO_init() // ------------------------ // Defines diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 8e7a3d8135..b018a0fc8c 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -19,15 +19,15 @@ #pragma once /** - * Support routines for STM32GENERIC (Maple) + * Support routines for MAPLE_STM32F1 */ /** * Translation of routines & variables used by pinsDebug.h */ -#ifndef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple) - #error "Expected BOARD_NR_GPIO_PINS not found" +#ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1 + #error "Expected BOARD_NR_GPIO_PINS not found" #endif #include "fastio.h" diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 6134699aa1..e8f9f16a8f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1131,6 +1131,10 @@ inline void tmc_standby_setup() { * - Set Marlin to RUNNING State */ void setup() { + #ifdef FASTIO_INIT + FASTIO_INIT(); + #endif + #ifdef BOARD_PREINIT BOARD_PREINIT(); // Low-level init (before serial init) #endif diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index bdf215fa8e..f9ec42b68e 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -99,19 +99,12 @@ // Avoid nozzle heat and fan start before serial init #define BOARD_OPENDRAIN_MOSFETS -#define BOARD_INIT_OD_PINS() { \ +#define BOARD_PREINIT() { \ OUT_WRITE_OD(HEATER_0_PIN, 0); \ OUT_WRITE_OD(HEATER_BED_PIN, 0); \ OUT_WRITE_OD(FAN_PIN, 0); \ } -#ifdef MAPLE_STM32F1 - // Only Maple Framework allow that early - #define BOARD_PREINIT BOARD_INIT_OD_PINS -#else - #define BOARD_INIT BOARD_INIT_OD_PINS -#endif - // // PWM for a servo probe // Other servo devices are not supported on this board! From cc109c1802193ac2830791e8dbce269a1edb4a3b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 9 Aug 2021 16:07:15 -0500 Subject: [PATCH 0531/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20CoreXY=20plus=20?= =?UTF-8?q?extra=20axes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #22490 --- Marlin/src/inc/SanityCheck.h | 18 ++++++++++++++++++ Marlin/src/module/planner.cpp | 33 ++++++++++++++++++++++++++++++++- 2 files changed, 50 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index da51f5ca9e..94f1f010c5 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1383,6 +1383,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if LINEAR_AXES >= 4 #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W' #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(I_MIN_POS) || !defined(I_MAX_POS) + #error "I_MIN_POS and I_MAX_POS are required with LINEAR_AXES >= 4." + #elif !defined(I_HOME_DIR) + #error "I_HOME_DIR is required with LINEAR_AXES >= 4." + #elif HAS_I_ENABLE && !defined(I_ENABLE_ON) + #error "I_ENABLE_ON is required for your I driver with LINEAR_AXES >= 4." #endif #endif #if LINEAR_AXES >= 5 @@ -1390,6 +1396,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME" #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(J_MIN_POS) || !defined(J_MAX_POS) + #error "J_MIN_POS and J_MAX_POS are required with LINEAR_AXES >= 5." + #elif !defined(J_HOME_DIR) + #error "J_HOME_DIR is required with LINEAR_AXES >= 5." + #elif HAS_J_ENABLE && !defined(J_ENABLE_ON) + #error "J_ENABLE_ON is required for your J driver with LINEAR_AXES >= 5." #endif #endif #if LINEAR_AXES >= 6 @@ -1397,6 +1409,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME." #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #elif !defined(K_MIN_POS) || !defined(K_MAX_POS) + #error "K_MIN_POS and K_MAX_POS are required with LINEAR_AXES >= 6." + #elif !defined(K_HOME_DIR) + #error "K_HOME_DIR is required with LINEAR_AXES >= 6." + #elif HAS_K_ENABLE && !defined(K_ENABLE_ON) + #error "K_ENABLE_ON is required for your K driver with LINEAR_AXES >= 6." #endif #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 52ca76308c..7bf672a85d 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1877,6 +1877,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, " A:", target.a, " (", da, " steps)" " B:", target.b, " (", db, " steps)" " C:", target.c, " (", dc, " steps)" + #if LINEAR_AXES >= 4 + " " AXIS4_STR ":", target.i, " (", di, " steps)" + #endif + #if LINEAR_AXES >= 5 + " " AXIS5_STR ":", target.j, " (", dj, " steps)" + #endif + #if LINEAR_AXES >= 6 + " " AXIS6_STR ":", target.k, " (", dk, " steps)" + #endif #if HAS_EXTRUDERS " E:", target.e, " (", de, " steps)" #endif @@ -1953,6 +1962,19 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (dk < 0) SBI(dm, K_AXIS) ); #endif + + #if IS_CORE + #if LINEAR_AXES >= 4 + if (di < 0) SBI(dm, I_AXIS); + #endif + #if LINEAR_AXES >= 5 + if (dj < 0) SBI(dm, J_AXIS); + #endif + #if LINEAR_AXES >= 6 + if (dk < 0) SBI(dm, K_AXIS); + #endif + #endif + #if HAS_EXTRUDERS if (de < 0) SBI(dm, E_AXIS); #endif @@ -2004,7 +2026,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, */ struct DistanceMM : abce_float_t { #if EITHER(IS_CORE, MARKFORGED_XY) - xyz_pos_t head; + struct { float x, y, z; } head; #endif } steps_dist_mm; #if IS_CORE @@ -2027,6 +2049,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif + #if LINEAR_AXES >= 4 + steps_dist_mm.i = di * steps_to_mm[I_AXIS]; + #endif + #if LINEAR_AXES >= 5 + steps_dist_mm.j = dj * steps_to_mm[J_AXIS]; + #endif + #if LINEAR_AXES >= 6 + steps_dist_mm.k = dk * steps_to_mm[K_AXIS]; + #endif #elif ENABLED(MARKFORGED_XY) steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; From 1ed59fef9305fe1784dfe3d180a56ed4e0d0f6d9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 10 Aug 2021 01:01:05 +0000 Subject: [PATCH 0532/2168] [cron] Bump distribution date (2021-08-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4020a3ae4c..11b2688647 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-09" +//#define STRING_DISTRIBUTION_DATE "2021-08-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e869278c76..31122f7ec3 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 "2021-08-09" + #define STRING_DISTRIBUTION_DATE "2021-08-10" #endif /** From 13e4e24e21514f5d55322af0ff2b6337be0775f9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 10 Aug 2021 02:39:50 -0500 Subject: [PATCH 0533/2168] =?UTF-8?q?=F0=9F=90=9B=20Use=20delete=20[]=20fo?= =?UTF-8?q?r=20new=20[]?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index d7aca6cdc7..c0bc81a3ef 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1219,7 +1219,7 @@ void CardReader::cdroot() { #if ENABLED(SDSORT_USES_RAM) && DISABLED(SDSORT_CACHE_NAMES) #if ENABLED(SDSORT_DYNAMIC_RAM) for (uint16_t i = 0; i < fileCnt; ++i) free(sortnames[i]); - TERN_(HAS_FOLDER_SORTING, free(isDir)); + TERN_(HAS_FOLDER_SORTING, delete [] isDir); #endif #endif } @@ -1245,14 +1245,14 @@ void CardReader::cdroot() { void CardReader::flush_presort() { if (sort_count > 0) { #if ENABLED(SDSORT_DYNAMIC_RAM) - delete sort_order; + delete [] sort_order; #if ENABLED(SDSORT_CACHE_NAMES) LOOP_L_N(i, sort_count) { free(sortshort[i]); // strdup free(sortnames[i]); // strdup } - delete sortshort; - delete sortnames; + delete [] sortshort; + delete [] sortnames; #endif #endif sort_count = 0; From 25d5d2ab507075f282787c6e5c9d57f1a3972e1e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 10 Aug 2021 02:53:28 -0500 Subject: [PATCH 0534/2168] =?UTF-8?q?=F0=9F=9A=B8=20Set=20M122=20interval?= =?UTF-8?q?=20only=20with=20S0=20or=20Pn?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/trinamic/M122.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 52a6920f05..fdab548774 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -43,10 +43,13 @@ void GcodeSuite::M122() { #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) - uint16_t interval = MONITOR_DRIVER_STATUS_INTERVAL_MS; - if (parser.seen('S') && !parser.value_bool()) interval = 0; - if (parser.seenval('P')) NOMORE(interval, parser.value_ushort()); - tmc_set_report_interval(interval); + const bool sflag = parser.seen_test('S'), sval = sflag && parser.value_bool(); + if (sflag && !sval) + tmc_set_report_interval(0); + else if (parser.seenval('P')) + tmc_set_report_interval(_MAX(250, parser.value_ushort())); + else if (sval) + tmc_set_report_interval(MONITOR_DRIVER_STATUS_INTERVAL_MS); #endif if (parser.seen_test('V')) From cad142ab1be311f568ce69a5faaf3706d2f2f244 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 11 Aug 2021 00:59:26 +0000 Subject: [PATCH 0535/2168] [cron] Bump distribution date (2021-08-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 11b2688647..64eaee3084 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-10" +//#define STRING_DISTRIBUTION_DATE "2021-08-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 31122f7ec3..6a07a4c049 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 "2021-08-10" + #define STRING_DISTRIBUTION_DATE "2021-08-11" #endif /** From c657fe2112fcd0dec1fb7012819b19a538fa8f21 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 12 Aug 2021 00:58:28 +0200 Subject: [PATCH 0536/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M575=20port=20in?= =?UTF-8?q?dex=20output=20(#22553)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/config/M575.cpp | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index ce5f8fda0e..7739510cf3 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -52,19 +52,25 @@ void GcodeSuite::M575() { case 2400: case 9600: case 19200: case 38400: case 57600: case 115200: case 250000: case 500000: case 1000000: { const int8_t port = parser.intval('P', -99); - const bool set0 = (port == -99 || port == 0); - if (set0) SERIAL_ECHO_MSG(" Serial ", '0', " baud rate set to ", baud); + const bool set1 = (port == -99 || port == 0); + if (set1) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('0'), " baud rate set to ", baud); #if HAS_MULTI_SERIAL - const bool set1 = (port == -99 || port == 1); - if (set1) SERIAL_ECHO_MSG(" Serial ", '1', " baud rate set to ", baud); + const bool set2 = (port == -99 || port == 1); + if (set2) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('1'), " baud rate set to ", baud); + #ifdef SERIAL_PORT_3 + const bool set3 = (port == -99 || port == 2); + if (set3) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('2'), " baud rate set to ", baud); + #endif #endif SERIAL_FLUSH(); - if (set0) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } - + if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } #if HAS_MULTI_SERIAL - if (set1) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } + if (set2) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } + #ifdef SERIAL_PORT_3 + if (set3) { MYSERIAL3.end(); MYSERIAL3.begin(baud); } + #endif #endif } break; From 5c610b2c18fdbf84f9707ef3a81553c2e130befc Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 12 Aug 2021 11:06:09 +1200 Subject: [PATCH 0537/2168] =?UTF-8?q?=F0=9F=9A=B8=20Better=20error=20for?= =?UTF-8?q?=20MOTHERBOARD=20not=20defined=20(#22551)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index f1c431cf04..28c7ed0071 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -769,8 +769,10 @@ #error "BOARD_RAMPS_LONGER3D_LK4PRO is now BOARD_LONGER3D_LKx_PRO. Please update your configuration." #elif MB(BTT_SKR_V2_0) #error "BTT_SKR_V2_0 is now BTT_SKR_V2_0_REV_A or BTT_SKR_V2_0_REV_B. See https://bit.ly/3t5d9JQ for more information. Please update your configuration." + #elif defined(MOTHERBOARD) + #error "Unknown MOTHERBOARD value set in Configuration.h." #else - #error "Unknown MOTHERBOARD value set in Configuration.h" + #error "MOTHERBOARD not defined! Use '#define MOTHERBOARD BOARD_...' in Configuration.h." #endif #undef BOARD_MKS_13 From bf9cd90cc4e70f9cebd129376580c4c6ffa5dff2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 10 Aug 2021 23:49:56 -0500 Subject: [PATCH 0538/2168] =?UTF-8?q?=F0=9F=8E=A8=20Tweak=20M73=20conditio?= =?UTF-8?q?n?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/lcd/M73.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index e94a2825f7..8996e5c88e 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -40,7 +40,7 @@ void GcodeSuite::M73() { ? parser.value_float() * (PROGRESS_SCALE) : parser.value_byte() ); - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) + #if ENABLED(USE_M73_REMAINING_TIME) if (parser.seenval('R')) ui.set_remaining_time(60 * parser.value_ulong()); #endif } From 4d3cb95bd8fbe325254d3885b5c648b6ca5dfa19 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 11 Aug 2021 18:19:55 -0500 Subject: [PATCH 0539/2168] =?UTF-8?q?=F0=9F=94=A8=20Use=20zip=20link=20for?= =?UTF-8?q?=20MarlinSimUI?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/native.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/native.ini b/ini/native.ini index 548e791f5a..2f38e715ed 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -45,7 +45,7 @@ lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI.git + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} From 534da44e1f824543c22f81d8f65ba9b86dd9aa98 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 12 Aug 2021 00:57:35 +0000 Subject: [PATCH 0540/2168] [cron] Bump distribution date (2021-08-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 64eaee3084..c8d8b3b3fb 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-11" +//#define STRING_DISTRIBUTION_DATE "2021-08-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6a07a4c049..6a1dd60ee1 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 "2021-08-11" + #define STRING_DISTRIBUTION_DATE "2021-08-12" #endif /** From 59324a411f022cbe6757f15924120ad1976e850b Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Wed, 11 Aug 2021 21:00:47 -0500 Subject: [PATCH 0541/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Ender-3=20v2=20l?= =?UTF-8?q?anguage=20init=20(#22550)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/lcd/e3v2/creality/dwin.h | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index e8f9f16a8f..3a1ac6fd04 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1591,7 +1591,7 @@ void setup() { #if ENABLED(DWIN_CREALITY_LCD) Encoder_Configuration(); HMI_Init(); - DWIN_JPG_CacheTo1(Language_English); + HMI_SetLanguageCache(); HMI_StartFrame(true); DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG)); #endif diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index 36948678aa..2808fea99c 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -215,6 +215,7 @@ void HMI_MaxFeedspeedXYZE(); void HMI_MaxAccelerationXYZE(); void HMI_MaxJerkXYZE(); void HMI_StepXYZE(); +void HMI_SetLanguageCache(); void update_variable(); void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); From b028df4228a9eb93d4e111ee8dcffb0d1aac7ff3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 13 Aug 2021 00:58:12 +0000 Subject: [PATCH 0542/2168] [cron] Bump distribution date (2021-08-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c8d8b3b3fb..d9db58bfa6 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-12" +//#define STRING_DISTRIBUTION_DATE "2021-08-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6a1dd60ee1..c661bd2b91 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 "2021-08-12" + #define STRING_DISTRIBUTION_DATE "2021-08-13" #endif /** From 1555db237e841c754931cbe43e48ebae14c6fdc5 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 13 Aug 2021 05:40:52 +0200 Subject: [PATCH 0543/2168] =?UTF-8?q?=F0=9F=9A=B8=20Fewer=20CRs=20in=20set?= =?UTF-8?q?tings=20report=20(#22560)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index b30c82260f..47c1314e28 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2320,7 +2320,6 @@ void MarlinSettings::postprocess() { ubl.report_state(); if (!ubl.sanity_check()) { - SERIAL_EOL(); #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) ubl.echo_name(); DEBUG_ECHOLNPGM(" initialized.\n"); @@ -3266,7 +3265,6 @@ void MarlinSettings::reset() { if (!forReplay) { SERIAL_EOL(); ubl.report_state(); - SERIAL_EOL(); config_heading(false, PSTR("Active Mesh Slot: "), false); SERIAL_ECHOLN(ubl.storage_slot); config_heading(false, PSTR("EEPROM can hold "), false); @@ -3886,7 +3884,7 @@ void MarlinSettings::reset() { #if HAS_MULTI_LANGUAGE CONFIG_ECHO_HEADING("UI Language:"); - SERIAL_ECHO_MSG(" M414 S", ui.language); + CONFIG_ECHO_MSG(" M414 S", ui.language); #endif } From feb6d2887eee1b31713ef0ad665b166c8fe6e70b Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Fri, 13 Aug 2021 12:26:26 +0800 Subject: [PATCH 0544/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20some=20BTT=20SKR?= =?UTF-8?q?2=20pins=20(#22558)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 14 +++++++------- ini/stm32f4.ini | 1 + 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index a9dfc367bf..e5d6b6891b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -153,13 +153,6 @@ #define POWER_LOSS_PIN PC15 // PWRDET #endif -// -// NeoPixel LED -// -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PE6 -#endif - // // Control pin of driver/heater/fan power supply // @@ -511,6 +504,13 @@ #endif #endif +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PE6 +#endif + // // WIFI // diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 62ac89d9fa..e2e93eaa43 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -207,6 +207,7 @@ build_flags = ${stm_flash_drive.build_flags} -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED + -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 # # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Media Share Support From c161a46112debd280dc1ed6945d50f971ff505e6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 13 Aug 2021 16:32:25 -0500 Subject: [PATCH 0545/2168] =?UTF-8?q?=F0=9F=8E=A8=20Update=20MKSPWC,=20som?= =?UTF-8?q?e=20other=20pins=20(#22557)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/HAL/DUE/HAL_SPI.cpp | 16 ++--- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 2 +- Marlin/src/HAL/shared/eeprom_if_spi.cpp | 12 ++-- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/MarlinCore.h | 2 +- Marlin/src/feature/dac/dac_dac084s085.cpp | 42 +++++++------- Marlin/src/gcode/control/M80_M81.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 7 +++ .../src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 6 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 6 +- .../lcd/extui/mks_ui/printer_operation.cpp | 6 +- Marlin/src/libs/W25Qxx.cpp | 48 ++++++--------- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 8 +-- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 12 ++-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 12 ++-- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 12 ++-- Marlin/src/pins/pinsDebug_list.h | 20 +++---- Marlin/src/pins/pins_postprocess.h | 4 +- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 4 +- Marlin/src/pins/sam/pins_ALLIGATOR_R2.h | 10 ++-- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 6 +- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 6 +- Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h | 8 +-- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 4 +- Marlin/src/pins/stm32f1/pins_CHITU3D_common.h | 8 +-- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 6 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 16 ++--- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 16 ++--- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 8 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 26 ++++----- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 12 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 14 +++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 43 +++++++------- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 44 +++++++------- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 31 +++++----- Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 8 +-- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 28 ++++----- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 58 +++++++++---------- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 22 +++---- 41 files changed, 279 insertions(+), 321 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d01fc98b40..763c143158 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -367,6 +367,7 @@ //#define PSU_NAME "Power Supply" #if ENABLED(PSU_CONTROL) + //#define MKS_PWC // Using the MKS PWC add-on //#define PS_OFF_CONFIRM // Confirm dialog when power off //#define PS_OFF_SOUND // Beep 1s when power off #define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index d3d76e94e5..c5e8f2433d 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -594,18 +594,14 @@ SPI_Configure(SPI0, ID_SPI0, SPI_MR_MSTR | SPI_MR_MODFDIS | SPI_MR_PS); SPI_Enable(SPI0); - SET_OUTPUT(DAC0_SYNC); + SET_OUTPUT(DAC0_SYNC_PIN); #if HAS_MULTI_EXTRUDER - SET_OUTPUT(DAC1_SYNC); - WRITE(DAC1_SYNC, HIGH); + OUT_WRITE(DAC1_SYNC_PIN, HIGH); #endif - SET_OUTPUT(SPI_EEPROM1_CS); - SET_OUTPUT(SPI_EEPROM2_CS); - SET_OUTPUT(SPI_FLASH_CS); - WRITE(DAC0_SYNC, HIGH); - WRITE(SPI_EEPROM1_CS, HIGH); - WRITE(SPI_EEPROM2_CS, HIGH); - WRITE(SPI_FLASH_CS, HIGH); + WRITE(DAC0_SYNC_PIN, HIGH); + OUT_WRITE(SPI_EEPROM1_CS_PIN, HIGH); + OUT_WRITE(SPI_EEPROM2_CS_PIN, HIGH); + OUT_WRITE(SPI_FLASH_CS_PIN, HIGH); WRITE(SD_SS_PIN, HIGH); OUT_WRITE(SDSS, LOW); diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 0ad69065cf..4cac36554f 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -44,7 +44,7 @@ bool PersistentStore::access_start() { SET_OUTPUT(BOARD_SPI1_SCK_PIN); SET_OUTPUT(BOARD_SPI1_MOSI_PIN); SET_INPUT(BOARD_SPI1_MISO_PIN); - SET_OUTPUT(SPI_EEPROM1_CS); + SET_OUTPUT(SPI_EEPROM1_CS_PIN); #endif spiInit(0); #endif diff --git a/Marlin/src/HAL/shared/eeprom_if_spi.cpp b/Marlin/src/HAL/shared/eeprom_if_spi.cpp index 6aa6e09096..72c35addcb 100644 --- a/Marlin/src/HAL/shared/eeprom_if_spi.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_spi.cpp @@ -49,8 +49,8 @@ static void _eeprom_begin(uint8_t * const pos, const uint8_t cmd) { (unsigned(pos) >> 8) & 0xFF, // Address High unsigned(pos) & 0xFF // Address Low }; - WRITE(SPI_EEPROM1_CS, HIGH); // Usually free already - WRITE(SPI_EEPROM1_CS, LOW); // Activate the Bus + WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Usually free already + WRITE(SPI_EEPROM1_CS_PIN, LOW); // Activate the Bus spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3); // Leave the Bus in-use } @@ -60,23 +60,23 @@ uint8_t eeprom_read_byte(uint8_t *pos) { const uint8_t v = spiRec(SPI_CHAN_EEPROM1); // After READ a value sits on the Bus - WRITE(SPI_EEPROM1_CS, HIGH); // Done with device + WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with device return v; } void eeprom_write_byte(uint8_t *pos, uint8_t value) { const uint8_t eeprom_temp = CMD_WREN; - WRITE(SPI_EEPROM1_CS, LOW); + WRITE(SPI_EEPROM1_CS_PIN, LOW); spiSend(SPI_CHAN_EEPROM1, &eeprom_temp, 1); // Write Enable - WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus + WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with the Bus delay(1); // For a small amount of time _eeprom_begin(pos, CMD_WRITE); // Set write address and begin transmission spiSend(SPI_CHAN_EEPROM1, value); // Send the value to be written - WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus + WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with the Bus delay(EEPROM_WRITE_DELAY); // Give page write time to complete } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3a1ac6fd04..39ff4393d7 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1192,7 +1192,7 @@ void setup() { #if HAS_SUICIDE SETUP_LOG("SUICIDE_PIN"); - OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); + OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_STATE); #endif #ifdef JTAGSWD_RESET diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index d7ab11d046..6147d43f17 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -84,7 +84,7 @@ extern bool wait_for_heatup; bool pin_is_protected(const pin_t pin); #if HAS_SUICIDE - inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); } + inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); } #endif #if HAS_KILL diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index 649aa5561b..b88aaf802b 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -20,35 +20,35 @@ void dac084s085::begin() { uint8_t externalDac_buf[] = { 0x20, 0x00 }; // all off // All SPI chip-select HIGH - SET_OUTPUT(DAC0_SYNC); + SET_OUTPUT(DAC0_SYNC_PIN); #if HAS_MULTI_EXTRUDER - SET_OUTPUT(DAC1_SYNC); + SET_OUTPUT(DAC1_SYNC_PIN); #endif cshigh(); spiBegin(); //init onboard DAC DELAY_US(2); - WRITE(DAC0_SYNC, LOW); + WRITE(DAC0_SYNC_PIN, LOW); DELAY_US(2); - WRITE(DAC0_SYNC, HIGH); + WRITE(DAC0_SYNC_PIN, HIGH); DELAY_US(2); - WRITE(DAC0_SYNC, LOW); + WRITE(DAC0_SYNC_PIN, LOW); spiSend(SPI_CHAN_DAC, externalDac_buf, COUNT(externalDac_buf)); - WRITE(DAC0_SYNC, HIGH); + WRITE(DAC0_SYNC_PIN, HIGH); #if HAS_MULTI_EXTRUDER //init Piggy DAC DELAY_US(2); - WRITE(DAC1_SYNC, LOW); + WRITE(DAC1_SYNC_PIN, LOW); DELAY_US(2); - WRITE(DAC1_SYNC, HIGH); + WRITE(DAC1_SYNC_PIN, HIGH); DELAY_US(2); - WRITE(DAC1_SYNC, LOW); + WRITE(DAC1_SYNC_PIN, LOW); spiSend(SPI_CHAN_DAC, externalDac_buf, COUNT(externalDac_buf)); - WRITE(DAC1_SYNC, HIGH); + WRITE(DAC1_SYNC_PIN, HIGH); #endif return; @@ -66,18 +66,18 @@ void dac084s085::setValue(const uint8_t channel, const uint8_t value) { cshigh(); if (channel > 3) { // DAC Piggy E1,E2,E3 - WRITE(DAC1_SYNC, LOW); + WRITE(DAC1_SYNC_PIN, LOW); DELAY_US(2); - WRITE(DAC1_SYNC, HIGH); + WRITE(DAC1_SYNC_PIN, HIGH); DELAY_US(2); - WRITE(DAC1_SYNC, LOW); + WRITE(DAC1_SYNC_PIN, LOW); } else { // DAC onboard X,Y,Z,E0 - WRITE(DAC0_SYNC, LOW); + WRITE(DAC0_SYNC_PIN, LOW); DELAY_US(2); - WRITE(DAC0_SYNC, HIGH); + WRITE(DAC0_SYNC_PIN, HIGH); DELAY_US(2); - WRITE(DAC0_SYNC, LOW); + WRITE(DAC0_SYNC_PIN, LOW); } DELAY_US(2); @@ -85,13 +85,13 @@ void dac084s085::setValue(const uint8_t channel, const uint8_t value) { } void dac084s085::cshigh() { - WRITE(DAC0_SYNC, HIGH); + WRITE(DAC0_SYNC_PIN, HIGH); #if HAS_MULTI_EXTRUDER - WRITE(DAC1_SYNC, HIGH); + WRITE(DAC1_SYNC_PIN, HIGH); #endif - WRITE(SPI_EEPROM1_CS, HIGH); - WRITE(SPI_EEPROM2_CS, HIGH); - WRITE(SPI_FLASH_CS, HIGH); + WRITE(SPI_EEPROM1_CS_PIN, HIGH); + WRITE(SPI_EEPROM2_CS_PIN, HIGH); + WRITE(SPI_FLASH_CS_PIN, HIGH); WRITE(SD_SS_PIN, HIGH); } diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 9640c72006..149613ee15 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -60,7 +60,7 @@ * a print without suicide... */ #if HAS_SUICIDE - OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); + OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_STATE); #endif TERN_(HAS_LCD_MENU, ui.reset_status()); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 94f1f010c5..f1204532fe 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3473,6 +3473,13 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #endif +/** + * Validate MKS_PWC + */ +#if ENABLED(MKS_PWC) && PSU_ACTIVE_STATE != HIGH + #error "MKS_PWC requires PSU_ACTIVE_STATE to be set HIGH." +#endif + /** * Ensure this option is set intentionally */ diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index c78e35e75b..407782f559 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -28,9 +28,9 @@ #define LOGO_TIME_DELAY TERN(USE_MKS_GREEN_UI, 8000, 1500) #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) - #define MT_DET_1_PIN 1 - #define MT_DET_2_PIN 2 - #define MT_DET_PIN_INVERTING false + #define MT_DET_1_PIN 1 + #define MT_DET_2_PIN 2 + #define MT_DET_PIN_STATE LOW #endif #define MKS_FINSH diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 8c806f0ecd..c80191c8e5 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -1495,17 +1495,17 @@ void DGUSScreenHandler::DGUS_Runout_Idle(void) { break; case UNRUNOUT_STATUS: - if (READ(MT_DET_1_PIN) == LOW) + if (READ(MT_DET_1_PIN) == MT_DET_PIN_STATE) runout_mks.runout_status = RUNOUT_STATUS; break; case RUNOUT_BEGIN_STATUS: - if (READ(MT_DET_1_PIN) == HIGH) + if (READ(MT_DET_1_PIN) != MT_DET_PIN_STATE) runout_mks.runout_status = RUNOUT_WAITTING_STATUS; break; case RUNOUT_WAITTING_STATUS: - if (READ(MT_DET_1_PIN) == LOW) + if (READ(MT_DET_1_PIN) == MT_DET_PIN_STATE) runout_mks.runout_status = RUNOUT_BEGIN_STATUS; break; diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 1bb17bb4f2..362fdeb43d 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -163,7 +163,7 @@ void filament_check() { #endif #if PIN_EXISTS(MT_DET_1) static int fil_det_count_1 = 0; - if (READ(MT_DET_1_PIN) == MT_DET_PIN_INVERTING) + if (READ(MT_DET_1_PIN) == MT_DET_PIN_STATE) fil_det_count_1++; else if (fil_det_count_1 > 0) fil_det_count_1--; @@ -171,7 +171,7 @@ void filament_check() { #if PIN_EXISTS(MT_DET_2) static int fil_det_count_2 = 0; - if (READ(MT_DET_2_PIN) == MT_DET_PIN_INVERTING) + if (READ(MT_DET_2_PIN) == MT_DET_PIN_STATE) fil_det_count_2++; else if (fil_det_count_2 > 0) fil_det_count_2--; @@ -179,7 +179,7 @@ void filament_check() { #if PIN_EXISTS(MT_DET_3) static int fil_det_count_3 = 0; - if (READ(MT_DET_3_PIN) == MT_DET_PIN_INVERTING) + if (READ(MT_DET_3_PIN) == MT_DET_PIN_STATE) fil_det_count_3++; else if (fil_det_count_3 > 0) fil_det_count_3--; diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index 56581ed46e..b458a7c965 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -28,26 +28,14 @@ W25QXXFlash W25QXX; -#ifndef SPI_FLASH_MISO_PIN - #define SPI_FLASH_MISO_PIN W25QXX_MISO_PIN -#endif -#ifndef SPI_FLASH_MOSI_PIN - #define SPI_FLASH_MOSI_PIN W25QXX_MOSI_PIN -#endif -#ifndef SPI_FLASH_SCK_PIN - #define SPI_FLASH_SCK_PIN W25QXX_SCK_PIN -#endif -#ifndef SPI_FLASH_CS_PIN - #define SPI_FLASH_CS_PIN W25QXX_CS_PIN -#endif #ifndef NC #define NC -1 #endif MarlinSPI W25QXXFlash::mySPI(SPI_FLASH_MOSI_PIN, SPI_FLASH_MISO_PIN, SPI_FLASH_SCK_PIN, NC); -#define W25QXX_CS_H OUT_WRITE(SPI_FLASH_CS_PIN, HIGH) -#define W25QXX_CS_L OUT_WRITE(SPI_FLASH_CS_PIN, LOW) +#define SPI_FLASH_CS_H() OUT_WRITE(SPI_FLASH_CS_PIN, HIGH) +#define SPI_FLASH_CS_L() OUT_WRITE(SPI_FLASH_CS_PIN, LOW) bool flash_dma_mode = true; @@ -134,24 +122,24 @@ void W25QXXFlash::spi_flash_SendBlock(uint8_t token, const uint8_t *buf) { uint16_t W25QXXFlash::W25QXX_ReadID(void) { uint16_t Temp = 0; - W25QXX_CS_L; + SPI_FLASH_CS_L(); spi_flash_Send(0x90); spi_flash_Send(0x00); spi_flash_Send(0x00); spi_flash_Send(0x00); Temp |= spi_flash_Rec() << 8; Temp |= spi_flash_Rec(); - W25QXX_CS_H; + SPI_FLASH_CS_H(); return Temp; } void W25QXXFlash::SPI_FLASH_WriteEnable(void) { // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send "Write Enable" instruction spi_flash_Send(W25X_WriteEnable); // Deselect the FLASH: Chip Select high - W25QXX_CS_H; + SPI_FLASH_CS_H(); } /******************************************************************************* @@ -167,7 +155,7 @@ void W25QXXFlash::SPI_FLASH_WaitForWriteEnd(void) { uint8_t FLASH_Status = 0; // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send "Read Status Register" instruction spi_flash_Send(W25X_ReadStatusReg); @@ -179,7 +167,7 @@ void W25QXXFlash::SPI_FLASH_WaitForWriteEnd(void) { while ((FLASH_Status & WIP_Flag) == 0x01); // Write in progress // Deselect the FLASH: Chip Select high - W25QXX_CS_H; + SPI_FLASH_CS_H(); } void W25QXXFlash::SPI_FLASH_SectorErase(uint32_t SectorAddr) { @@ -188,7 +176,7 @@ void W25QXXFlash::SPI_FLASH_SectorErase(uint32_t SectorAddr) { // Sector Erase // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send Sector Erase instruction spi_flash_Send(W25X_SectorErase); // Send SectorAddr high nybble address byte @@ -199,14 +187,14 @@ void W25QXXFlash::SPI_FLASH_SectorErase(uint32_t SectorAddr) { spi_flash_Send(SectorAddr & 0xFF); // Deselect the FLASH: Chip Select high - W25QXX_CS_H; + SPI_FLASH_CS_H(); // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); } void W25QXXFlash::SPI_FLASH_BlockErase(uint32_t BlockAddr) { SPI_FLASH_WriteEnable(); - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send Sector Erase instruction spi_flash_Send(W25X_BlockErase); // Send SectorAddr high nybble address byte @@ -216,7 +204,7 @@ void W25QXXFlash::SPI_FLASH_BlockErase(uint32_t BlockAddr) { // Send SectorAddr low nybble address byte spi_flash_Send(BlockAddr & 0xFF); - W25QXX_CS_H; + SPI_FLASH_CS_H(); SPI_FLASH_WaitForWriteEnd(); } @@ -234,12 +222,12 @@ void W25QXXFlash::SPI_FLASH_BulkErase(void) { // Bulk Erase // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send Bulk Erase instruction spi_flash_Send(W25X_ChipErase); // Deselect the FLASH: Chip Select high - W25QXX_CS_H; + SPI_FLASH_CS_H(); // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); } @@ -262,7 +250,7 @@ void W25QXXFlash::SPI_FLASH_PageWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint SPI_FLASH_WriteEnable(); // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send "Write to Memory " instruction spi_flash_Send(W25X_PageProgram); // Send WriteAddr high nybble address byte to write to @@ -283,7 +271,7 @@ void W25QXXFlash::SPI_FLASH_PageWrite(uint8_t *pBuffer, uint32_t WriteAddr, uint } // Deselect the FLASH: Chip Select high - W25QXX_CS_H; + SPI_FLASH_CS_H(); // Wait the end of Flash writing SPI_FLASH_WaitForWriteEnd(); @@ -366,7 +354,7 @@ void W25QXXFlash::SPI_FLASH_BufferWrite(uint8_t *pBuffer, uint32_t WriteAddr, ui *******************************************************************************/ void W25QXXFlash::SPI_FLASH_BufferRead(uint8_t *pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead) { // Select the FLASH: Chip Select low - W25QXX_CS_L; + SPI_FLASH_CS_L(); // Send "Read from Memory " instruction spi_flash_Send(W25X_ReadData); @@ -389,7 +377,7 @@ void W25QXXFlash::SPI_FLASH_BufferRead(uint8_t *pBuffer, uint32_t ReadAddr, uint else spi_flash_Read(pBuffer, NumByteToRead); - W25QXX_CS_H; + SPI_FLASH_CS_H(); } #endif // HAS_SPI_FLASH diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index a0f8c1648c..1b3cf15e5a 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -416,10 +416,10 @@ #if HAS_SPI_FLASH #define SPI_DEVICE 1 #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN 31 - #define W25QXX_MOSI_PIN SD_MOSI_PIN - #define W25QXX_MISO_PIN SD_MISO_PIN - #define W25QXX_SCK_PIN SD_SCK_PIN + #define SPI_FLASH_CS_PIN 31 + #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN + #define SPI_FLASH_MISO_PIN SD_MISO_PIN + #define SPI_FLASH_SCK_PIN SD_SCK_PIN #endif #define TFT_BUFFER_SIZE 0xFFFF diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 4c2b606929..44dbaacb73 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -138,14 +138,10 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #ifndef PS_ON_PIN - #define PS_ON_PIN P0_25 // SERVO - #endif - #ifndef KILL_PIN - #define KILL_PIN P1_29 // Z+ - #define KILL_PIN_STATE HIGH - #endif +#if ENABLED(MKS_PWC) + #define PS_ON_PIN P0_25 // SERVO + #define KILL_PIN P1_29 // Z+ + #define KILL_PIN_STATE HIGH #endif // diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 0c3f44ceb7..8808c3a228 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -218,14 +218,10 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #ifndef PS_ON_PIN - #define PS_ON_PIN P2_00 // SERVO - #endif - #ifndef KILL_PIN - #define KILL_PIN P1_24 // Z+ - #define KILL_PIN_STATE HIGH - #endif +#if ENABLED(MKS_PWC) + #define PS_ON_PIN P2_00 // SERVO + #define KILL_PIN P1_24 // Z+ + #define KILL_PIN_STATE HIGH #endif // diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 4020ac23c6..7547279bbd 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -229,14 +229,10 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #ifndef PS_ON_PIN - #define PS_ON_PIN P2_00 // Suggestion (SERVO) - #endif - #ifndef KILL_PIN - #define KILL_PIN P1_24 // Suggestion (Z+) - #define KILL_PIN_STATE HIGH - #endif +#if ENABLED(MKS_PWC) + #define PS_ON_PIN P2_00 // SERVO + #define KILL_PIN P1_24 // Z+ + #define KILL_PIN_STATE HIGH #endif // diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 8b1cad3a7c..78ee71749d 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -291,11 +291,11 @@ #if PIN_EXISTS(DAC_DISABLE) REPORT_NAME_DIGITAL(__LINE__, DAC_DISABLE_PIN) #endif -#if defined(DAC0_SYNC) && DAC0_SYNC >= 0 - REPORT_NAME_DIGITAL(__LINE__, DAC0_SYNC) +#if PIN_EXISTS(DAC0_SYNC) + REPORT_NAME_DIGITAL(__LINE__, DAC0_SYNC_PIN) #endif -#if defined(DAC1_SYNC) && DAC1_SYNC >= 0 - REPORT_NAME_DIGITAL(__LINE__, DAC1_SYNC) +#if PIN_EXISTS(DAC1_SYNC) + REPORT_NAME_DIGITAL(__LINE__, DAC1_SYNC_PIN) #endif #if PIN_EXISTS(DEBUG) REPORT_NAME_DIGITAL(__LINE__, DEBUG_PIN) @@ -974,14 +974,14 @@ #if defined(SPARE_IO) && SPARE_IO >= 0 REPORT_NAME_DIGITAL(__LINE__, SPARE_IO) #endif -#if defined(SPI_EEPROM1_CS) && SPI_EEPROM1_CS >= 0 - REPORT_NAME_DIGITAL(__LINE__, SPI_EEPROM1_CS) +#if PIN_EXISTS(SPI_EEPROM1_CS) + REPORT_NAME_DIGITAL(__LINE__, SPI_EEPROM1_CS_PIN) #endif -#if defined(SPI_EEPROM2_CS) && SPI_EEPROM2_CS >= 0 - REPORT_NAME_DIGITAL(__LINE__, SPI_EEPROM2_CS) +#if PIN_EXISTS(SPI_EEPROM2_CS) + REPORT_NAME_DIGITAL(__LINE__, SPI_EEPROM2_CS_PIN) #endif -#if defined(SPI_FLASH_CS) && SPI_FLASH_CS >= 0 - REPORT_NAME_DIGITAL(__LINE__, SPI_FLASH_CS) +#if PIN_EXISTS(SPI_FLASH_CS) + REPORT_NAME_DIGITAL(__LINE__, SPI_FLASH_CS_PIN) #endif #if PIN_EXISTS(SPINDLE_DIR) REPORT_NAME_DIGITAL(__LINE__, SPINDLE_DIR_PIN) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index f7152770e5..fc82e600df 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -391,8 +391,8 @@ #ifndef SUICIDE_PIN #define SUICIDE_PIN -1 #endif -#ifndef SUICIDE_PIN_INVERTING - #define SUICIDE_PIN_INVERTING false +#ifndef SUICIDE_PIN_STATE + #define SUICIDE_PIN_STATE LOW #endif #ifndef NUM_SERVO_PLUGS diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 6133a6417e..8756a33218 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -34,7 +34,7 @@ #endif #define RESET_PIN 30 -#define SPI_FLASH_CS 83 +#define SPI_FLASH_CS_PIN 83 // // Servos diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 05de208ca1..def71fefc1 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -63,6 +63,6 @@ #define EXP4_PIN 12 // PS_ON_PIN #define SUICIDE_PIN 12 // Used by CR2020 Industrial series -#ifndef SUICIDE_PIN_INVERTING - #define SUICIDE_PIN_INVERTING true +#ifndef SUICIDE_PIN_STATE + #define SUICIDE_PIN_STATE HIGH #endif diff --git a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h index c273edfc6b..70c3853dc9 100644 --- a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h +++ b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h @@ -123,20 +123,20 @@ #define SPI_CHAN_DAC 1 -#define DAC0_SYNC 53 // PB14 -#define DAC1_SYNC 6 // PC24 +#define DAC0_SYNC_PIN 53 // PB14 +#define DAC1_SYNC_PIN 6 // PC24 // 64K SPI EEPROM #define SPI_EEPROM #define SPI_CHAN_EEPROM1 2 -#define SPI_EEPROM1_CS 25 // PD0 +#define SPI_EEPROM1_CS_PIN 25 // PD0 // 2K SPI EEPROM -#define SPI_EEPROM2_CS 26 // PD1 +#define SPI_EEPROM2_CS_PIN 26 // PD1 // FLASH SPI // 32Mb -#define SPI_FLASH_CS 23 // PA14 +#define SPI_FLASH_CS_PIN 23 // PA14 // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index b5569c810d..5e612d3e8c 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -190,11 +190,11 @@ //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 //#define SPI_CHAN_EEPROM1 ? -//#define SPI_EEPROM1_CS ? +//#define SPI_EEPROM1_CS_PIN ? // 2K EEPROM -//#define SPI_EEPROM2_CS ? +//#define SPI_EEPROM2_CS_PIN ? // 32Mb FLASH -//#define SPI_FLASH_CS ? +//#define SPI_FLASH_CS_PIN ? // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index b06de1bc69..37a76c5278 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -176,11 +176,11 @@ //#define EEPROM_SD // EEPROM on SDCARD //#define SPI_EEPROM // EEPROM on SPI-0 //#define SPI_CHAN_EEPROM1 ? -//#define SPI_EEPROM1_CS ? +//#define SPI_EEPROM1_CS_PIN ? // 2K EEPROM -//#define SPI_EEPROM2_CS ? +//#define SPI_EEPROM2_CS_PIN ? // 32Mb FLASH -//#define SPI_FLASH_CS ? +//#define SPI_FLASH_CS_PIN ? // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index a655d0121c..fd30c2b69a 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -137,13 +137,13 @@ // SPI Buses // -#define DAC0_SYNC 53 // PB14 +#define DAC0_SYNC_PIN 53 // PB14 #define SPI_CHAN_DAC 1 #define SPI_CHAN_EEPROM1 -1 -#define SPI_EEPROM1_CS -1 -#define SPI_EEPROM2_CS -1 -#define SPI_FLASH_CS -1 +#define SPI_EEPROM1_CS_PIN -1 +#define SPI_EEPROM2_CS_PIN -1 +#define SPI_FLASH_CS_PIN -1 #define SD_SCK_PIN 76 #define SD_MISO_PIN 74 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index 63ad06dc57..bd5f2068f1 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -179,6 +179,6 @@ #endif #define SUICIDE_PIN PC13 -#ifndef SUICIDE_PIN_INVERTING - #define SUICIDE_PIN_INVERTING false +#ifndef SUICIDE_PIN_STATE + #define SUICIDE_PIN_STATE LOW #endif diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h index 0319afa5e9..989b7eec6f 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -120,10 +120,10 @@ #endif // SPI 2 -#define W25QXX_CS_PIN PB12 -#define W25QXX_MOSI_PIN PB15 -#define W25QXX_MISO_PIN PB14 -#define W25QXX_SCK_PIN PB13 +#define SPI_FLASH_CS_PIN PB12 +#define SPI_FLASH_MOSI_PIN PB15 +#define SPI_FLASH_MISO_PIN PB14 +#define SPI_FLASH_SCK_PIN PB13 // // TFT with FSMC interface diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index d106c98e13..f971f65628 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -61,13 +61,13 @@ // SPI //#define SPI_EEPROM // EEPROM on SPI-0 //#define SPI_CHAN_EEPROM1 ? - //#define SPI_EEPROM1_CS ? + //#define SPI_EEPROM1_CS_PIN ? // 2K EEPROM - //#define SPI_EEPROM2_CS ? + //#define SPI_EEPROM2_CS_PIN ? // 32Mb FLASH - //#define SPI_FLASH_CS ? + //#define SPI_FLASH_CS_PIN ? #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index 2dea59ef41..21bbd23ca9 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -73,10 +73,10 @@ #if HAS_SPI_FLASH // SPI 2 - #define W25QXX_CS_PIN PB12 // SPI2_NSS / Flash chip-select - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 // SPI2_NSS / Flash chip-select + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif // @@ -222,9 +222,11 @@ //#define PS_ON_PIN PA3 // PW_CN /PW_OFF #endif -#define MT_DET_1_PIN PA4 // MT_DET -#define MT_DET_2_PIN PE6 // FALA_CRTL -#define MT_DET_PIN_INVERTING false +#if HAS_TFT_LVGL_UI + #define MT_DET_1_PIN PA4 // MT_DET + #define MT_DET_2_PIN PE6 + #define MT_DET_PIN_STATE LOW +#endif // // LED / NEOPixel diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index f9ec42b68e..c9d16b16b0 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -170,18 +170,18 @@ #if ENABLED(SPI_EEPROM) // SPI1 EEPROM Winbond W25Q64 (8MB/64Mbits) #define SPI_CHAN_EEPROM1 1 - #define SPI_EEPROM1_CS PC5 // pin 34 - #define EEPROM_SCK BOARD_SPI1_SCK_PIN // PA5 pin 30 - #define EEPROM_MISO BOARD_SPI1_MISO_PIN // PA6 pin 31 - #define EEPROM_MOSI BOARD_SPI1_MOSI_PIN // PA7 pin 32 + #define SPI_EEPROM1_CS_PIN PC5 // pin 34 + #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 pin 30 + #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 pin 31 + #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 pin 32 #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... #elif HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x40000U // limit to 256KB (M993 will reboot with 512) - #define W25QXX_CS_PIN PC5 - #define W25QXX_MOSI_PIN PA7 - #define W25QXX_MISO_PIN PA6 - #define W25QXX_SCK_PIN PA5 + #define SPI_FLASH_CS_PIN PC5 + #define SPI_FLASH_MOSI_PIN PA7 + #define SPI_FLASH_MISO_PIN PA6 + #define SPI_FLASH_SCK_PIN PA5 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2KB diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 4d798ffe28..889e1f5e07 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -275,8 +275,8 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x800000 // 8MB - #define W25QXX_CS_PIN PG9 - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PG9 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 2fc99f2971..ba51980065 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -183,19 +183,19 @@ // Misc. Functions // #if HAS_TFT_LVGL_UI - #if ENABLED(PSU_CONTROL) // MKSPWC - #define SUICIDE_PIN PB2 // PW_OFF - #define SUICIDE_PIN_INVERTING false - #define KILL_PIN PA2 // PW_DET + #if ENABLED(MKS_PWC) + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_STATE LOW + #define KILL_PIN PA2 #define KILL_PIN_STATE HIGH #endif - #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN - #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE + #define MT_DET_1_PIN PA4 + #define MT_DET_PIN_STATE LOW - #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN - #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN - #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN + #define WIFI_IO0_PIN PC13 + #define WIFI_IO1_PIN PC7 + #define WIFI_RESET_PIN PE9 #if ENABLED(MKS_TEST) #define MKS_TEST_POWER_LOSS_PIN PA2 // PW_DET @@ -363,10 +363,10 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif #ifndef BEEPER_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index da7ba05795..5a35932801 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -129,14 +129,10 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #ifndef PS_ON_PIN - #define PS_ON_PIN PA14 // PW_OFF - #endif - #ifndef KILL_PIN - #define KILL_PIN PB10 // PW_DET - #define KILL_PIN_STATE HIGH - #endif +#if ENABLED(MKS_PWC) + #define PS_ON_PIN PA14 // PW_OFF + #define KILL_PIN PB10 // PW_DET + #define KILL_PIN_STATE HIGH #endif /** diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index d4a2f59b42..ae45d8b6d1 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -119,8 +119,10 @@ #define POWER_LOSS_PIN PA2 // PW_DET #define PS_ON_PIN PA3 // PW_OFF -#define MT_DET_1_PIN PA4 -#define MT_DET_PIN_INVERTING false +#if HAS_TFT_LVGL_UI + #define MT_DET_1_PIN PA4 // MT_DET + #define MT_DET_PIN_STATE LOW +#endif #define WIFI_IO0_PIN PC13 @@ -194,8 +196,8 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 // Flash chip-select - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 // Flash chip-select + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 2a5c9f7273..975ecb8bd5 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -130,33 +130,30 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #if HAS_TFT_LVGL_UI - #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." +#if ENABLED(MKS_PWC) + #if ENABLED(TFT_LVGL_UI) + #undef PSU_CONTROL + #undef MKS_PWC + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_STATE LOW + #else + #define PS_ON_PIN PB2 // PW_OFF #endif - #ifndef PS_ON_PIN - #define PS_ON_PIN PB2 // SUICIDE - #endif - #ifndef KILL_PIN - #define KILL_PIN PA2 - #define KILL_PIN_STATE HIGH - #endif -#else - #define SUICIDE_PIN PB2 - #define SUICIDE_PIN_INVERTING false + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH #endif // // Misc. Functions // #if HAS_TFT_LVGL_UI - #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN - #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN - #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE + #define MT_DET_1_PIN PA4 + #define MT_DET_2_PIN PE6 + #define MT_DET_PIN_STATE LOW - #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN - #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN - #define WIFI_RESET_PIN PA5 // MKS ESP WIFI RESET PIN + #define WIFI_IO0_PIN PC13 + #define WIFI_IO1_PIN PC7 + #define WIFI_RESET_PIN PA5 #else //#define POWER_LOSS_PIN PA2 // PW_DET //#define PS_ON_PIN PB2 // PW_OFF @@ -221,8 +218,8 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 31ce016e67..49d5476fec 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -194,34 +194,30 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #if HAS_TFT_LVGL_UI - #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." +#if ENABLED(MKS_PWC) + #if ENABLED(TFT_LVGL_UI) + #undef PSU_CONTROL + #undef MKS_PWC + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_STATE LOW + #else + #define PS_ON_PIN PB2 // PW_OFF #endif - #ifndef PS_ON_PIN - #define PS_ON_PIN PB2 // SUICIDE - #endif - #ifndef KILL_PIN - #define KILL_PIN PA2 - #define KILL_PIN_STATE HIGH - #endif -#else - #define SUICIDE_PIN PB2 - #define SUICIDE_PIN_INVERTING false + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH #endif // // Misc. Functions // #if HAS_TFT_LVGL_UI + #define MT_DET_1_PIN PA4 + #define MT_DET_2_PIN PE6 + #define MT_DET_PIN_STATE LOW - #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN - #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN - #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE - - #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN - #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN - #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN + #define WIFI_IO0_PIN PC13 + #define WIFI_IO1_PIN PC7 + #define WIFI_RESET_PIN PE9 #if ENABLED(MKS_TEST) #define MKS_TEST_POWER_LOSS_PIN PA2 // PW_DET @@ -390,10 +386,10 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif #ifndef BEEPER_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 2f62563edb..d752d52a3a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -186,20 +186,17 @@ // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #if HAS_TFT_LVGL_UI - #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." +#if ENABLED(MKS_PWC) + #if ENABLED(TFT_LVGL_UI) + #undef PSU_CONTROL + #undef MKS_PWC + #define SUICIDE_PIN PG11 + #define SUICIDE_PIN_STATE LOW + #else + #define PS_ON_PIN PG11 // PW_OFF #endif - #ifndef PS_ON_PIN - #define PS_ON_PIN PG11 // SUICIDE - #endif - #ifndef KILL_PIN - #define KILL_PIN PA2 - #define KILL_PIN_STATE HIGH - #endif -#else - #define SUICIDE_PIN PG11 - #define SUICIDE_PIN_INVERTING false + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH #endif // @@ -318,8 +315,8 @@ #define HAS_SPI_FLASH 1 #if HAS_SPI_FLASH #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define W25QXX_CS_PIN PB12 // Flash chip-select - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 // Flash chip-select + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 65db99025c..4707a16e14 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -179,10 +179,10 @@ #if ENABLED(SPI_EEPROM) // Lerdge has an SPI EEPROM Winbond W25Q128 (128Mbits) https://www.pjrc.com/teensy/W25Q128FV.pdf #define SPI_CHAN_EEPROM1 1 - #define SPI_EEPROM1_CS PB12 // datasheet: /CS pin, found with multimeter, not tested - #define EEPROM_SCK PB13 // datasheet: CLK pin, found with multimeter, not tested - #define EEPROM_MISO PB14 // datasheet: DO pin, found with multimeter, not tested - #define EEPROM_MOSI PB15 // datasheet: DI pin, found with multimeter, not tested + #define SPI_EEPROM1_CS_PIN PB12 // datasheet: /CS pin, found with multimeter, not tested + #define EEPROM_SCK_PIN PB13 // datasheet: CLK pin, found with multimeter, not tested + #define EEPROM_MISO_PIN PB14 // datasheet: DO pin, found with multimeter, not tested + #define EEPROM_MOSI_PIN PB15 // datasheet: DI pin, found with multimeter, not tested #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... #else diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 2db5584109..5c66685629 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -210,32 +210,24 @@ // // Misc. Functions // -#define MT_DET_1 PC5 // Y+ -#define MT_DET_2 PB12 // Z+ - +#define PW_DET PC5 // Y+ +#define PW_OFF PB12 // Z+ +#define MT_DET_1_PIN PW_DET +#define MT_DET_2_PIN PW_OFF #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1 + #define FIL_RUNOUT_PIN MT_DET_1_PIN #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN MT_DET_2 + #define FIL_RUNOUT2_PIN MT_DET_2_PIN #endif // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #ifndef PS_ON_PIN - #define PS_ON_PIN MT_DET_2 // Z+ - #endif - #ifndef KILL_PIN - #define KILL_PIN MT_DET_1 // Y+ - #define KILL_PIN_STATE HIGH - #endif -#else - #define PW_DET MT_DET_1 - #define PW_OFF MT_DET_2 - #define POWER_LOSS_PIN PW_DET - #define PS_ON_PIN PW_OFF +#if ENABLED(MKS_PWC) + #define PS_ON_PIN PW_OFF + #define KILL_PIN PW_DET + #define KILL_PIN_STATE HIGH #endif // Random Info diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index eff941b957..9193a85511 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -178,9 +178,11 @@ // // Misc. Functions // -#define MT_DET_1_PIN PA4 -#define MT_DET_2_PIN PE6 -#define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE +#if HAS_TFT_LVGL_UI + #define MT_DET_1_PIN PA4 // MT_DET + #define MT_DET_2_PIN PE6 + #define MT_DET_PIN_STATE LOW +#endif #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN MT_DET_1_PIN @@ -189,35 +191,29 @@ #define FIL_RUNOUT2_PIN MT_DET_2_PIN #endif -// -// Enable MKSPWC support -// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PA13 // PW_DET +#endif + //#define SUICIDE_PIN PB2 //#define LED_PIN PB2 //#define KILL_PIN PA2 -//#define KILL_PIN_STATE HIGH +//#define KILL_PIN_STATE LOW // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - #if HAS_TFT_LVGL_UI - #error "PSU_CONTROL cannot be used with TFT_LVGL_UI. Disable PSU_CONTROL to continue." +#if ENABLED(MKS_PWC) + #if ENABLED(TFT_LVGL_UI) + #undef PSU_CONTROL + #undef MKS_PWC + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_STATE LOW + #else + #define PS_ON_PIN PB2 // PW_OFF #endif - #ifndef PS_ON_PIN - #define PS_ON_PIN PB2 // SUICIDE - #endif - #ifndef KILL_PIN - #define KILL_PIN PA13 // PW_DET - #define KILL_PIN_STATE HIGH - #endif -#else - #define SUICIDE_PIN PB2 - #define SUICIDE_PIN_INVERTING false -#endif - -#ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PA13 // PW_DET + #define KILL_PIN PA13 // PW_DET + #define KILL_PIN_STATE HIGH #endif // Random Info @@ -232,9 +228,9 @@ // MKS WIFI MODULE #if ENABLED(MKS_WIFI_MODULE) - #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN - #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN - #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN + #define WIFI_IO0_PIN PC13 + #define WIFI_IO1_PIN PC7 + #define WIFI_RESET_PIN PE9 #endif // MKS TEST @@ -276,10 +272,10 @@ #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) - #define W25QXX_CS_PIN PB12 - #define W25QXX_MOSI_PIN PC3 - #define W25QXX_MISO_PIN PC2 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PC3 + #define SPI_FLASH_MISO_PIN PC2 + #define SPI_FLASH_SCK_PIN PB13 #endif /** diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 2e47f98e9f..c2809c8553 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -195,18 +195,18 @@ // // Misc. Functions // +//#define POWER_LOSS_PIN PA2 // PW_DET //#define PS_ON_PIN PA3 // PW_OFF // // Power Supply Control // -#if ENABLED(PSU_CONTROL) // MKSPWC - //#define SUICIDE_PIN PB2 // LED - //#define KILL_PIN PA2 // PW_DET - //#define KILL_PIN_STATE HIGH +#if ENABLED(MKS_PWC) + #define SUICIDE_PIN PB2 + #define KILL_PIN PA2 + #define KILL_PIN_STATE LOW #else - //#define POWER_LOSS_PIN PA2 // PW_DET - //#define LED_PIN PB2 + #define LED_PIN PB2 #endif #ifndef SDCARD_CONNECTION @@ -251,14 +251,14 @@ // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) - #define W25QXX_CS_PIN PB12 - #define W25QXX_MOSI_PIN PB15 - #define W25QXX_MISO_PIN PB14 - #define W25QXX_SCK_PIN PB13 + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 #endif /** From fc817feee3ddfb652e370aa38e723e74b319a0bc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 13 Aug 2021 18:49:27 -0500 Subject: [PATCH 0546/2168] =?UTF-8?q?=F0=9F=8E=A8=20Update=20HAL/STM32=20w?= =?UTF-8?q?rappers?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22537 --- Marlin/src/HAL/STM32/MarlinSPI.cpp | 2 ++ Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp | 6 ++++-- Marlin/src/HAL/STM32/eeprom_if_iic.cpp | 7 ++++--- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index 330c895697..e1be50820f 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -19,6 +19,8 @@ * along with this program. If not, see . * */ +#include "../platforms.h" + #if defined(HAL_STM32) && !defined(STM32H7xx) #include "MarlinSPI.h" diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp index 165b3c6bab..5bd4c18577 100644 --- a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp @@ -19,7 +19,9 @@ * along with this program. If not, see . * */ -#ifdef STM32F1 +#include "../platforms.h" + +#ifdef HAL_STM32 /** * PersistentStore for Arduino-style EEPROM interface @@ -79,4 +81,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t } #endif // IIC_BL24CXX_EEPROM -#endif // STM32F1 +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp index 5c6cc802a6..26b3d9044e 100644 --- a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp @@ -19,14 +19,15 @@ * along with this program. If not, see . * */ +#include "../platforms.h" + +#ifdef HAL_STM32 /** * Platform-independent Arduino functions for I2C EEPROM. * Enable USE_SHARED_EEPROM if not supplied by the framework. */ -#ifdef STM32F1 - #include "../../inc/MarlinConfig.h" #if ENABLED(IIC_BL24CXX_EEPROM) @@ -51,4 +52,4 @@ uint8_t eeprom_read_byte(uint8_t *pos) { } #endif // IIC_BL24CXX_EEPROM -#endif // STM32F1 +#endif // HAL_STM32 From 8fe84fcf870967d755b1bb884e380b75559f0bec Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 14 Aug 2021 00:54:13 +0000 Subject: [PATCH 0547/2168] [cron] Bump distribution date (2021-08-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d9db58bfa6..9713c47880 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-13" +//#define STRING_DISTRIBUTION_DATE "2021-08-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c661bd2b91..eed4860c36 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 "2021-08-13" + #define STRING_DISTRIBUTION_DATE "2021-08-14" #endif /** From a307348b898f2d2a61c2a348a9e53034679bfe62 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 15 Aug 2021 00:57:42 +0000 Subject: [PATCH 0548/2168] [cron] Bump distribution date (2021-08-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 9713c47880..16b613b139 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-14" +//#define STRING_DISTRIBUTION_DATE "2021-08-15" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index eed4860c36..c9357a26bc 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 "2021-08-14" + #define STRING_DISTRIBUTION_DATE "2021-08-15" #endif /** From af0cd400bebdfd77baa068ab27b091611de1b20d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 15 Aug 2021 19:02:08 -0500 Subject: [PATCH 0549/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LCD=5FCOL=5FX=5F?= =?UTF-8?q?RJ?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22471 --- Marlin/src/lcd/lcdprint.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index 8bfd72e9f5..32d958bf7f 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -79,7 +79,6 @@ // Graphical LCD uses the menu font size for cursor positioning #define LCD_COL_X(col) (( (col)) * (MENU_FONT_WIDTH)) #define LCD_ROW_Y(row) ((1 + (row)) * (MENU_LINE_HEIGHT)) - #define LCD_COL_X_RJ(len) (LCD_WIDTH - LCD_COL_X(len)) #else @@ -99,7 +98,6 @@ // Character LCD uses direct cursor positioning #define LCD_COL_X(col) (col) #define LCD_ROW_Y(row) (row) - #define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) #endif @@ -107,6 +105,7 @@ #define MENU_LINE_HEIGHT MENU_FONT_HEIGHT #endif +#define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) #define SETCURSOR(col, row) lcd_moveto(LCD_COL_X(col), LCD_ROW_Y(row)) #define SETCURSOR_RJ(len, row) lcd_moveto(LCD_COL_X_RJ(len), LCD_ROW_Y(row)) #define SETCURSOR_X(col) SETCURSOR(col, _lcdLineNr) From d586340655b30362f4790cc1aa8082c7f37b902c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 16 Aug 2021 00:57:32 +0000 Subject: [PATCH 0550/2168] [cron] Bump distribution date (2021-08-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 16b613b139..5324f841e5 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-15" +//#define STRING_DISTRIBUTION_DATE "2021-08-16" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c9357a26bc..684f606daf 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 "2021-08-15" + #define STRING_DISTRIBUTION_DATE "2021-08-16" #endif /** From 510f8d3e0ccb07911c6d57f5c29f16cad86f6c02 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 15 Aug 2021 21:31:00 -0500 Subject: [PATCH 0551/2168] =?UTF-8?q?=F0=9F=92=9A=20Update=20STM32F103RET6?= =?UTF-8?q?=5Fcreality=20test=20path?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/STM32F103RET6_creality | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index 8348b6347d..8c4177b907 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -9,11 +9,11 @@ set -e # # Build with configs included in the PR # -use_example_configs "Creality/Ender-3 V2" +use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING exec_test $1 $2 "Ender 3 v2" "$3" -use_example_configs "Creality/Ender-3 V2" +use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_disable CLASSIC_JERK opt_add SDCARD_EEPROM_EMULATION opt_set TEMP_SENSOR_BED 0 From 3e0d8e16aacfbf85f1254d4fb2229e9da66c8cac Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 17 Aug 2021 00:57:07 +0000 Subject: [PATCH 0552/2168] [cron] Bump distribution date (2021-08-17) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5324f841e5..092d76f71d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-16" +//#define STRING_DISTRIBUTION_DATE "2021-08-17" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 684f606daf..4cc068511e 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 "2021-08-16" + #define STRING_DISTRIBUTION_DATE "2021-08-17" #endif /** From 09af42e1af38b441d44ddcc71b9d6906ce68b51d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 17 Aug 2021 06:18:19 -0500 Subject: [PATCH 0553/2168] Clean up CrealityUI and MarlinUI (#22586) --- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 2 + Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 7 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 24 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 1687 +++++++++++--------- Marlin/src/lcd/e3v2/creality/dwin.h | 13 - Marlin/src/lcd/e3v2/creality/dwin_lcd.h | 13 +- Marlin/src/lcd/language/language_en.h | 18 +- Marlin/src/lcd/menu/menu_media.cpp | 2 +- buildroot/tests/STM32F103RET6_creality | 2 +- 10 files changed, 947 insertions(+), 823 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 054a14161c..2eecc0adb3 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1580,7 +1580,7 @@ */ #if HAS_MARLINUI_U8GLIB // Show SD percentage next to the progress bar - //#define DOGM_SD_PERCENT + //#define SHOW_SD_PERCENT // Save many cycles by drawing a hollow frame or no frame on the Info Screen //#define XYZ_NO_FRAME diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f1204532fe..817bce28bc 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -577,6 +577,8 @@ #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." #elif defined(MKS_LCD12864) #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." +#elif defined(DOGM_SD_PERCENT) + #error "DOGM_SD_PERCENT is now SHOW_SD_PERCENT." #elif defined(NEOPIXEL_BKGD_LED_INDEX) #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." #elif defined(TEMP_SENSOR_1_AS_REDUNDANT) diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 25e943a14d..33bb3e4b92 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -354,12 +354,11 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop #if ENABLED(ADVANCED_PAUSE_FEATURE) void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { - row_y1 = row * (MENU_FONT_HEIGHT) + 1; - row_y2 = row_y1 + MENU_FONT_HEIGHT - 1; + u8g_uint_t y1 = row * (MENU_FONT_HEIGHT) + 1, y2 = y1 + MENU_FONT_HEIGHT - 1; - if (!PAGE_CONTAINS(row_y1 + 1, row_y2 + 2)) return; + if (!PAGE_CONTAINS(y1 + 1, y2 + 2)) return; - lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), row_y2, 'E'); + lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), y2, 'E'); lcd_put_wchar((char)('1' + extruder)); lcd_put_wchar(' '); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 5fe8b61bf4..8b707ba7c7 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -456,13 +456,13 @@ void MarlinUI::draw_status_screen() { #endif #if HAS_PRINT_PROGRESS - #if DISABLED(DOGM_SD_PERCENT) + #if DISABLED(SHOW_SD_PERCENT) #define _SD_INFO_X(len) (PROGRESS_BAR_X + (PROGRESS_BAR_WIDTH) / 2 - (len) * (MENU_FONT_WIDTH) / 2) #else #define _SD_INFO_X(len) (LCD_PIXEL_WIDTH - (len) * (MENU_FONT_WIDTH)) #endif - #if ENABLED(DOGM_SD_PERCENT) + #if ENABLED(SHOW_SD_PERCENT) static char progress_string[5]; #endif static uint8_t lastElapsed = 0xFF, lastProgress = 0xFF; @@ -471,7 +471,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(SHOW_REMAINING_TIME) static u8g_uint_t estimation_x_pos = 0; static char estimation_string[10]; - #if BOTH(DOGM_SD_PERCENT, ROTATE_PROGRESS_DISPLAY) + #if BOTH(SHOW_SD_PERCENT, ROTATE_PROGRESS_DISPLAY) static u8g_uint_t progress_x_pos = 0; static uint8_t progress_state = 0; static bool prev_blink = 0; @@ -526,7 +526,7 @@ void MarlinUI::draw_status_screen() { progress_bar_solid_width = u8g_uint_t((PROGRESS_BAR_WIDTH - 2) * (progress / (PROGRESS_SCALE)) * 0.01f); - #if ENABLED(DOGM_SD_PERCENT) + #if ENABLED(SHOW_SD_PERCENT) if (progress == 0) { progress_string[0] = '\0'; #if ENABLED(SHOW_REMAINING_TIME) @@ -543,7 +543,7 @@ void MarlinUI::draw_status_screen() { #endif } - constexpr bool can_show_days = DISABLED(DOGM_SD_PERCENT) || ENABLED(ROTATE_PROGRESS_DISPLAY); + constexpr bool can_show_days = DISABLED(SHOW_SD_PERCENT) || ENABLED(ROTATE_PROGRESS_DISPLAY); if (ev != lastElapsed) { lastElapsed = ev; const uint8_t len = elapsed.toDigital(elapsed_string, can_show_days && elapsed.value >= 60*60*24L); @@ -564,11 +564,7 @@ void MarlinUI::draw_status_screen() { else { duration_t estimation = timeval; const uint8_t len = estimation.toDigital(estimation_string, can_show_days && estimation.value >= 60*60*24L); - estimation_x_pos = _SD_INFO_X(len - #if !BOTH(DOGM_SD_PERCENT, ROTATE_PROGRESS_DISPLAY) - + 1 - #endif - ); + estimation_x_pos = _SD_INFO_X(len + !BOTH(SHOW_SD_PERCENT, ROTATE_PROGRESS_DISPLAY)); } } #endif @@ -767,7 +763,7 @@ void MarlinUI::draw_status_screen() { if (PAGE_CONTAINS(EXTRAS_BASELINE - INFO_FONT_ASCENT, EXTRAS_BASELINE - 1)) { - #if ALL(DOGM_SD_PERCENT, SHOW_REMAINING_TIME, ROTATE_PROGRESS_DISPLAY) + #if ALL(SHOW_SD_PERCENT, SHOW_REMAINING_TIME, ROTATE_PROGRESS_DISPLAY) if (prev_blink != blink) { prev_blink = blink; @@ -789,13 +785,13 @@ void MarlinUI::draw_status_screen() { lcd_put_u8str(elapsed_x_pos, EXTRAS_BASELINE, elapsed_string); } - #else // !DOGM_SD_PERCENT || !SHOW_REMAINING_TIME || !ROTATE_PROGRESS_DISPLAY + #else // !SHOW_SD_PERCENT || !SHOW_REMAINING_TIME || !ROTATE_PROGRESS_DISPLAY // // SD Percent Complete // - #if ENABLED(DOGM_SD_PERCENT) + #if ENABLED(SHOW_SD_PERCENT) if (progress_string[0]) { lcd_put_u8str(55, EXTRAS_BASELINE, progress_string); // Percent complete lcd_put_wchar('%'); @@ -815,7 +811,7 @@ void MarlinUI::draw_status_screen() { #endif lcd_put_u8str(elapsed_x_pos, EXTRAS_BASELINE, elapsed_string); - #endif // !DOGM_SD_PERCENT || !SHOW_REMAINING_TIME || !ROTATE_PROGRESS_DISPLAY + #endif // !SHOW_SD_PERCENT || !SHOW_REMAINING_TIME || !ROTATE_PROGRESS_DISPLAY } #endif // HAS_PRINT_PROGRESS diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 05da343f9e..f008a7a2b4 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -94,9 +94,6 @@ #define PAUSE_HEAT -#define USE_STRING_HEADINGS -//#define USE_STRING_TITLES - #define MENU_CHAR_LIMIT 24 #define STATUS_Y 360 @@ -121,20 +118,22 @@ #define DWIN_SCROLL_UPDATE_INTERVAL SEC_TO_MS(2) #define DWIN_REMAIN_TIME_UPDATE_INTERVAL SEC_TO_MS(20) -constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other-than-Back - TITLE_HEIGHT = 30, // Title bar height - MLINE = 53, // Menu line height - LBLX = 60, // Menu item label X +#define TROWS 6 // Total rows +constexpr uint16_t MROWS = TROWS - 1, // Last Row Index + TITLE_HEIGHT = 30, // Title bar height + MLINE = 53, // Menu line height + LBLX = 60, // Menu item label X MENU_CHR_W = 8, STAT_CHR_W = 10; #define MBASE(L) (49 + MLINE * (L)) +#define EBASE(L) (MBASE(L) - 2 * DISABLED(USE_STRING_TITLES)) #define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) #define DWIN_BOTTOM (DWIN_HEIGHT-1) #define DWIN_RIGHT (DWIN_WIDTH-1) -/* Value Init */ +// Value Init HMI_value_t HMI_ValueStruct; HMI_Flag_t HMI_flag{0}; @@ -228,166 +227,122 @@ void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t } } +typedef struct { uint16_t x, y, w, h; } icon_info_t; +typedef struct { uint16_t x, y[2], w, h; } text_info_t; + +void ICON_Button(const bool here, const int iconid, const icon_info_t &ico, const text_info_t (&txt)[2]) { + const bool cn = HMI_IsChinese(); + DWIN_ICON_Show(ICON, iconid + here, ico.x, ico.y); + if (here) DWIN_Draw_Rectangle(0, Color_White, ico.x, ico.y, ico.x + ico.w - 1, ico.y + ico.h - 1); + DWIN_Frame_AreaCopy(1, txt[cn].x, txt[cn].y[here], txt[cn].x + txt[cn].w - 1, txt[cn].y[here] + txt[cn].h - 1, ico.x + (ico.w - txt[cn].w) / 2, (ico.y + ico.h - 28) - txt[cn].h/2); +} + +// +// Main Menu: "Print" +// void ICON_Print() { - if (select_page.now == 0) { - DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); - DWIN_Draw_Rectangle(0, Color_White, 17, 130, 126, 229); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 451, 31, 463, 57, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 423, 31, 435, 57, 201); - } + constexpr icon_info_t ico = { 17, 130, 110, 100 }; + constexpr text_info_t txt[2] = { + { 1, { 417, 449 }, 30, 14 }, + { 1, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 0, ICON_Print_0, ico, txt); } +// +// Main Menu: "Prepare" +// void ICON_Prepare() { - if (select_page.now == 1) { - DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); - DWIN_Draw_Rectangle(0, Color_White, 145, 130, 254, 229); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 451, 82, 466, 175, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 31, 405, 58, 420, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 423, 82, 438, 175, 201); - } + constexpr icon_info_t ico = { 145, 130, 110, 100 }; + constexpr text_info_t txt[2] = { + { 33, { 417, 449 }, 51, 14 }, + { 31, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 1, ICON_Prepare_0, ico, txt); } +// +// Main Menu: "Control" +// void ICON_Control() { - if (select_page.now == 2) { - DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); - DWIN_Draw_Rectangle(0, Color_White, 17, 246, 126, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 451, 132, 463, 48, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 61, 405, 88, 420, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 423, 132, 434, 48, 318); - } + constexpr icon_info_t ico = { 17, 246, 110, 100 }; + constexpr text_info_t txt[2] = { + { 85, { 417, 449 }, 46, 14 }, + { 61, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 2, ICON_Control_0, ico, txt); } -void ICON_StartInfo(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); - DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 451, 159, 466, 186, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 91, 405, 118, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); - } +// +// Main Menu: "Info" +// +void ICON_StartInfo() { + constexpr icon_info_t ico = { 145, 246, 110, 100 }; + constexpr text_info_t txt[2] = { + { 133, { 417, 449 }, 23, 14 }, + { 91, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 3, ICON_Info_0, ico, txt); } -void ICON_Leveling(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); - DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 182, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 182, 318); - } +// +// Main Menu: "Level" +// +void ICON_Leveling() { + constexpr icon_info_t ico = { 145, 246, 110, 100 }; + constexpr text_info_t txt[2] = { + { 88, { 433, 464 }, 36, 14 }, + { 211, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 3, ICON_Leveling_0, ico, txt); } +// +// Printing: "Tune" +// void ICON_Tune() { - if (select_print.now == 0) { - DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); - DWIN_Draw_Rectangle(0, Color_White, 8, 252, 87, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); - else - DWIN_Frame_AreaCopy(1, 0, 466, 34, 476, 31, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); - else - DWIN_Frame_AreaCopy(1, 0, 438, 32, 448, 31, 325); - } + constexpr icon_info_t ico = { 8, 252, 80, 100 }; + constexpr text_info_t txt[2] = { + { 0, { 433, 464 }, 32, 14 }, + { 121, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 0, ICON_Setup_0, ico, txt); } +// +// Printing: "Pause" +// void ICON_Pause() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); - DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 451, 216, 462, 116, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 181, 405, 208, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 423, 215, 433, 116, 325); - } + constexpr icon_info_t ico = { 96, 252, 80, 100 }; + constexpr text_info_t txt[2] = { + { 157, { 417, 449 }, 39, 14 }, + { 181, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 1, ICON_Pause_0, ico, txt); } -void ICON_Continue() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); - DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 452, 32, 464, 121, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 424, 31, 434, 121, 325); - } +// +// Printing: "Resume" +// +void ICON_Resume() { + constexpr icon_info_t ico = { 96, 252, 80, 100 }; + constexpr text_info_t txt[2] = { + { 33, { 433, 464 }, 53, 14 }, + { 1, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 1, ICON_Continue_0, ico, txt); } +// +// Printing: "Stop" +// void ICON_Stop() { - if (select_print.now == 2) { - DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); - DWIN_Draw_Rectangle(0, Color_White, 184, 252, 263, 351); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 452, 249, 466, 209, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 151, 405, 178, 420, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 423, 247, 436, 209, 325); - } + constexpr icon_info_t ico = { 184, 252, 80, 100 }; + constexpr text_info_t txt[2] = { + { 196, { 417, 449 }, 29, 14 }, + { 151, { 405, 447 }, 27, 12 } + }; + ICON_Button(select_print.now == 2, ICON_Stop_0, ico, txt); } inline void Clear_Title_Bar() { @@ -425,7 +380,7 @@ void Draw_More_Icon(const uint8_t line) { } void Draw_Menu_Cursor(const uint8_t line) { - // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, MBASE(line) - 18); + //DWIN_ICON_Show(ICON, ICON_Rectangle, 0, MBASE(line) - 18); DWIN_Draw_Rectangle(1, Rectangle_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } @@ -474,22 +429,29 @@ void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } -void Draw_Chkb_Line(const uint8_t line, const bool mode) { - DWIN_Draw_Checkbox(Color_White, Color_Bg_Black, 225, MBASE(line) - 1, mode); +void Draw_Checkbox_Line(const uint8_t line, const bool ison) { + const uint16_t x = 225, y = EBASE(line) - 2; + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x + 5, y, F(ison ? "X" : " ")); + DWIN_Draw_Rectangle(0, Color_White, x + 2, y + 2, x + 17, y + 17); } -// The "Back" label is always on the first line -void Draw_Back_Label() { - if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); - else - DWIN_Frame_AreaCopy(1, 226, 179, 256, 189, LBLX, MBASE(0)); +// AreaCopy for a Menu Item +void Item_AreaCopy(const uint16_t x1, const uint16_t y1, const uint16_t x2, const uint16_t y2, const uint8_t row=0, const uint16_t inset=0, const uint16_t yadd=0) { + DWIN_Frame_AreaCopy(1, x1, y1, x2, y2, LBLX + inset, MBASE(row) + yadd); +} + +// AreaCopy for a Screen Title +void DWIN_Frame_TitleCopy(const uint16_t x1, const uint16_t y1, const uint16_t w, const uint16_t h) { + DWIN_Frame_AreaCopy(1, x1, y1, x1 + w - 1, y1 + h - 1, (DWIN_WIDTH - w) / 2, (TITLE_HEIGHT - h) / 2); } // Draw "Back" line at the top void Draw_Back_First(const bool is_sel=true) { Draw_Menu_Line(0, ICON_Back); - Draw_Back_Label(); + if (HMI_IsChinese()) + Item_AreaCopy(129, 72, 156, 84); + else + Item_AreaCopy(223, 179, 254, 189); if (is_sel) Draw_Menu_Cursor(0); } @@ -562,42 +524,81 @@ inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) // Draw Menus // -void DWIN_Draw_Label(const uint16_t y, char *string) { - DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, LBLX, y, string); +void say_move_en(const uint8_t row) { + Item_AreaCopy( 69, 61, 102, 71, row); // "Move" } -void DWIN_Draw_Label(const uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_Label(y, (char*)title); +void say_max_en(const uint8_t row) { + Item_AreaCopy( 75, 119, 100, 129, row); // "Max" +} +void say_jerk_en(const uint8_t row) { + Item_AreaCopy(104, 119, 128, 129, row, 30); // "Jerk" +} +void say_speed_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(133, 119, 172, 132, row, inset); // "Speed" +} +void say_max_accel_en(const uint8_t row) { + say_max_en(row); // "Max" + Item_AreaCopy( 0, 135, 79, 145, row, 30); // "Acceleration" +} +void say_max_jerk_speed_en(const uint8_t row) { + Item_AreaCopy( 75, 119, 172, 132, row); // "Max Jerk Speed" +} +void say_x_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(175, 119, 184, 129, row, inset); // "X" +} +void say_y_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(184, 119, 192, 129, row, inset); // "Y" +} +void say_z_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(193, 119, 201, 129, row, inset); // "Z" +} +void say_e_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(201, 119, 209, 129, row, inset); // "E" +} +void say_pla_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(131, 164, 153, 174, row, inset); // "PLA" +} +void say_abs_en(const uint16_t inset, const uint8_t row) { + Item_AreaCopy(157, 76, 181, 86, row, inset); // "ABS" +} +void say_home_offs_en(const uint8_t row) { + Item_AreaCopy(153, 193, 225, 203, row); // "Home Offset" +} +void say_probe_offs_en(const uint8_t row) { + Item_AreaCopy(153, 205, 225, 215, row); // "Probe Offset" +} +void say_steps_per_mm_en(const uint8_t row) { + Item_AreaCopy( 1, 151, 91, 161, row); // "Steps-per-mm" } -void draw_move_en(const uint16_t line) { - #ifdef USE_STRING_TITLES - DWIN_Draw_Label(line, F("Move")); - #else - DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" - #endif +void DWIN_Draw_Label(const uint8_t row, char *string) { + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(row), string); +} +void DWIN_Draw_Label(const uint8_t row, const __FlashStringHelper *title) { + DWIN_Draw_Label(row, (char*)title); } -inline void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { - DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); -} +// +// Prepare Menu +// void Item_Prepare_Move(const uint8_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); + Item_AreaCopy(159, 70, 200, 84, row); else - draw_move_en(MBASE(row)); // "Move" + say_move_en(row); // "Move" Draw_Menu_Line(row, ICON_Axis); Draw_More_Icon(row); } void Item_Prepare_Disable(const uint8_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); + Item_AreaCopy(204, 70, 259, 82, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_DISABLE_STEPPERS)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_DISABLE_STEPPERS)); #else - DWIN_Frame_AreaCopy(1, 103, 59, 200, 74, LBLX, MBASE(row)); // "Disable Stepper" + Item_AreaCopy(104, 61, 191, 74, row); // "Disable Stepper" #endif } Draw_Menu_Line(row, ICON_CloseMotor); @@ -605,12 +606,12 @@ void Item_Prepare_Disable(const uint8_t row) { void Item_Prepare_Home(const uint8_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); + Item_AreaCopy(0, 89, 41, 101, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_AUTO_HOME)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_AUTO_HOME)); #else - DWIN_Frame_AreaCopy(1, 202, 61, 271, 71, LBLX, MBASE(row)); // "Auto Home" + Item_AreaCopy(202, 61, 271, 71, row); // "Auto Home" #endif } Draw_Menu_Line(row, ICON_Homing); @@ -621,25 +622,25 @@ void Item_Prepare_Home(const uint8_t row) { void Item_Prepare_Offset(const uint8_t row) { if (HMI_IsChinese()) { #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + Item_AreaCopy(174, 164, 223, 177, row); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(row), probe.offset.z * 100); #else - DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); + Item_AreaCopy(43, 89, 98, 101, row); #endif } else { #if HAS_BED_PROBE #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" + Item_AreaCopy(94, 179, 143, 190, row); // "Z-Offset" #endif - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(row), probe.offset.z * 100); #else #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); #else - DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "Set home offsets" + Item_AreaCopy(1, 76, 103, 87, row); // "Set home offsets" #endif #endif } @@ -650,30 +651,28 @@ void Item_Prepare_Home(const uint8_t row) { #if HAS_HOTEND void Item_Prepare_PLA(const uint8_t row) { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); - } + if (HMI_IsChinese()) + Item_AreaCopy(100, 89, 151, 101, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), F("Preheat " PREHEAT_1_LABEL)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_PREHEAT_1)); #else - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(row)); // "PLA" + Item_AreaCopy(108, 76, 155, 87, row); // "Preheat" + say_pla_en(52, row); // "PLA" #endif } Draw_Menu_Line(row, ICON_PLAPreheat); } void Item_Prepare_ABS(const uint8_t row) { - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); - } + if (HMI_IsChinese()) + Item_AreaCopy(180, 89, 233, 100, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), F("Preheat " PREHEAT_2_LABEL)); + DWIN_Draw_Label(row, F("Preheat " PREHEAT_2_LABEL)); #else - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(row)); // "ABS" + Item_AreaCopy(108, 76, 155, 87, row); // "Preheat" + say_abs_en(52, row); // "ABS" #endif } Draw_Menu_Line(row, ICON_ABSPreheat); @@ -683,12 +682,12 @@ void Item_Prepare_Home(const uint8_t row) { #if HAS_PREHEAT void Item_Prepare_Cool(const uint8_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); + Item_AreaCopy(1, 104, 56, 117, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), GET_TEXT_F(MSG_COOLDOWN)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_COOLDOWN)); #else - DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" + Item_AreaCopy(200, 76, 264, 86, row); // "Cooldown" #endif } Draw_Menu_Line(row, ICON_Cool); @@ -697,33 +696,34 @@ void Item_Prepare_Home(const uint8_t row) { void Item_Prepare_Lang(const uint8_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); + Item_AreaCopy(239, 134, 266, 146, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(row), F("UI Language")); + DWIN_Draw_Label(row, F("UI Language")); #else - DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" + Item_AreaCopy(1, 194, 96, 206, row); // "LCD Language" #endif } - DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), HMI_IsChinese() ? F("CN") : F("EN")); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 226, EBASE(row), HMI_IsChinese() ? F("CN") : F("EN")); Draw_Menu_Icon(row, ICON_Language); } +#define VISI(T,L,S) (WITHIN(L, T - MROWS, MROWS) || WITHIN(S, 0, MROWS)) + void Draw_Prepare_Menu() { Clear_Main_Window(); const int16_t scroll = MROWS - index_prepare; // Scrolled-up lines #define PSCROL(L) (scroll + (L)) - #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) + #define PVISI(L) VISI(PREPARE_CASE_TOTAL, L, PSCROL(L)) - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 133, 1, 160, 13); // "Prepare" - } + if (HMI_IsChinese()) + DWIN_Frame_TitleCopy(133, 1, 28, 13); // "Prepare" else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_PREPARE)); #else - DWIN_Frame_TitleCopy(1, 178, 2, 229, 14); // "Prepare" + DWIN_Frame_TitleCopy(179, 0, 48, 14); // "Prepare" #endif } @@ -746,80 +746,125 @@ void Draw_Prepare_Menu() { if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); } -void Item_Control_Info(const uint16_t line) { +// +// Control Menu +// + +void Item_Control_Temp(const uint16_t row) { if (HMI_IsChinese()) - DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, line); + Item_AreaCopy(57, 104, 84, 116, row); else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(line, F("Info")); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_TEMPERATURE)); #else - DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, line); + Item_AreaCopy(1, 89, 83, 101, row); #endif } + Draw_Menu_Line(row, ICON_Temperature); + Draw_More_Icon(row); +} + +void Item_Control_Motion(const uint16_t row) { + if (HMI_IsChinese()) + Item_AreaCopy(87, 104, 114, 116, row); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_MOTION)); + #else + Item_AreaCopy(84, 89, 128, 99, row); + #endif + } + Draw_Menu_Line(row, ICON_Motion); + Draw_More_Icon(row); +} + +void Item_Control_Advanced(const uint16_t row) { + if (HMI_IsChinese()) + Item_AreaCopy(62, 180, 120, 192, row); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); + #else + Item_AreaCopy(82, 135, 200, 149, row); + #endif + } + Draw_Menu_Line(row, ICON_AdvSet); + Draw_More_Icon(row); +} + +void Item_Control_Info(const uint16_t row) { + if (HMI_IsChinese()) + Item_AreaCopy(231, 104, 258, 116, row); + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_INFO_SCREEN)); + #else + Item_AreaCopy(0, 104, 24, 114, row); + #endif + } + Draw_Menu_Line(row, ICON_Info); + Draw_More_Icon(row); } void Draw_Control_Menu() { Clear_Main_Window(); - #if CONTROL_CASE_TOTAL >= 6 + #if CONTROL_CASE_TOTAL >= TROWS const int16_t scroll = MROWS - index_control; // Scrolled-up lines - #define CSCROL(L) (scroll + (L)) #else - #define CSCROL(L) (L) + constexpr int16_t scroll = 0; #endif - #define CLINE(L) MBASE(CSCROL(L)) - #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) + #define CSCROL(L) (scroll + (L)) + #define CLINE(L) MBASE(CSCROL(L)) + #define CVISI(L) VISI(CONTROL_CASE_TOTAL, L, CSCROL(L)) - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back - - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 103, 1, 130, 14); // "Control" - - DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > - DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > - - #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(CONTROL_CASE_SAVE)); // Store Configuration - DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(CONTROL_CASE_LOAD)); // Read Configuration - DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(CONTROL_CASE_RESET)); // Reset Configuration - #endif - } + // "Control" Title + if (HMI_IsChinese()) + DWIN_Frame_TitleCopy(103, 1, 28, 14); else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); #else - DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" + DWIN_Frame_TitleCopy(128, 2, 49, 11); // "Control" #endif + } + + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + if (CVISI(CONTROL_CASE_TEMP)) Item_Control_Temp(CSCROL(CONTROL_CASE_TEMP)); // Temperature > + if (CVISI(CONTROL_CASE_MOVE)) Item_Control_Motion(CSCROL(CONTROL_CASE_MOVE)); // Motion > + + if (HMI_IsChinese()) { + #if ENABLED(EEPROM_SETTINGS) + Item_AreaCopy(117, 104, 172, 116, CSCROL(CONTROL_CASE_SAVE)); // "Store Configuration" + Item_AreaCopy(174, 103, 229, 116, CSCROL(CONTROL_CASE_LOAD)); // "Read Configuration" + Item_AreaCopy( 1, 118, 56, 131, CSCROL(CONTROL_CASE_RESET)); // "Reset Configuration" + #endif + } + else { #ifdef USE_STRING_TITLES - if (CVISI(CONTROL_CASE_TEMP)) DWIN_Draw_Label(CLINE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); - if (CVISI(CONTROL_CASE_MOVE)) DWIN_Draw_Label(CLINE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); #if ENABLED(EEPROM_SETTINGS) - if (CVISI(CONTROL_CASE_SAVE)) DWIN_Draw_Label(CLINE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - if (CVISI(CONTROL_CASE_LOAD)) DWIN_Draw_Label(CLINE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); - if (CVISI(CONTROL_CASE_RESET)) DWIN_Draw_Label(CLINE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + if (CVISI(CONTROL_CASE_SAVE)) DWIN_Draw_Label(CSCROL(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); // "Store Configuration" + if (CVISI(CONTROL_CASE_LOAD)) DWIN_Draw_Label(CSCROL(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); // "Read Configuration" + if (CVISI(CONTROL_CASE_RESET)) DWIN_Draw_Label(CSCROL(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); // "Reset Configuration" #endif #else - if (CVISI(CONTROL_CASE_TEMP)) DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > - if (CVISI(CONTROL_CASE_MOVE)) DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > #if ENABLED(EEPROM_SETTINGS) - if (CVISI(CONTROL_CASE_SAVE)) DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX , CLINE(CONTROL_CASE_SAVE)); // "Store Configuration" + if (CVISI(CONTROL_CASE_SAVE)) + Item_AreaCopy(150, 89, 263, 102, CSCROL(CONTROL_CASE_SAVE)); // "Store Configuration" if (CVISI(CONTROL_CASE_LOAD)) { - DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX , CLINE(CONTROL_CASE_LOAD)); // "Read" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(CONTROL_CASE_LOAD)); // "Configuration" + Item_AreaCopy( 26, 104, 57, 114, CSCROL(CONTROL_CASE_LOAD)); // "Read" + Item_AreaCopy(182, 89, 263, 102, CSCROL(CONTROL_CASE_LOAD), 34); // "Configuration" } if (CVISI(CONTROL_CASE_RESET)) { - DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX , CLINE(CONTROL_CASE_RESET)); // "Reset" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(CONTROL_CASE_RESET)); // "Configuration" + Item_AreaCopy( 59, 104, 93, 114, CSCROL(CONTROL_CASE_RESET)); // "Reset" + Item_AreaCopy(182, 89, 263, 102, CSCROL(CONTROL_CASE_RESET), 37); // "Configuration" } #endif #endif } - if (CVISI(CONTROL_CASE_ADVSET)) { - DWIN_Draw_Label(CLINE(CONTROL_CASE_ADVSET), GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // Advanced Settings - } - - if (CVISI(CONTROL_CASE_INFO)) Item_Control_Info(CLINE(CONTROL_CASE_INFO)); + if (CVISI(CONTROL_CASE_ADVSET)) Item_Control_Advanced(CSCROL(CONTROL_CASE_ADVSET)); + if (CVISI(CONTROL_CASE_INFO)) Item_Control_Info(CSCROL(CONTROL_CASE_INFO)); if (select_control.now && CVISI(select_control.now)) Draw_Menu_Cursor(CSCROL(select_control.now)); @@ -834,72 +879,77 @@ void Draw_Control_Menu() { } \ } while(0) - _TEMP_ICON(CONTROL_CASE_TEMP, ICON_Temperature, true); - _TEMP_ICON(CONTROL_CASE_MOVE, ICON_Motion, true); - #if ENABLED(EEPROM_SETTINGS) _TEMP_ICON(CONTROL_CASE_SAVE, ICON_WriteEEPROM, false); _TEMP_ICON(CONTROL_CASE_LOAD, ICON_ReadEEPROM, false); _TEMP_ICON(CONTROL_CASE_RESET, ICON_ResumeEEPROM, false); #endif - - _TEMP_ICON(CONTROL_CASE_ADVSET, ICON_AdvSet, true); - _TEMP_ICON(CONTROL_CASE_INFO, ICON_Info, true); } +void Draw_Edit_Integer3(const uint8_t line, const uint16_t value, const bool active=false) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, 220, EBASE(line), value); +} + +void Draw_Edit_Integer4(const uint8_t line, const uint16_t value, const bool active=false) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 4, 210, EBASE(line), value); +} + +// +// Tune Menu +// + void Draw_Tune_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 73, 2, 100, 13); - DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(TUNE_CASE_SPEED)); + DWIN_Frame_TitleCopy(73, 2, 28, 12); // "Tune" + Item_AreaCopy(116, 164, 171, 176, TUNE_CASE_SPEED); #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TUNE_CASE_TEMP)); + Item_AreaCopy(1, 134, 56, 146, TUNE_CASE_TEMP); #endif #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TUNE_CASE_BED)); + Item_AreaCopy(58, 134, 113, 146, TUNE_CASE_BED); #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TUNE_CASE_FAN)); + Item_AreaCopy(115, 134, 170, 146, TUNE_CASE_FAN); #endif #if HAS_ZOFFSET_ITEM - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(TUNE_CASE_ZOFF)); + Item_AreaCopy(174, 164, 223, 177, TUNE_CASE_ZOFF); #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TUNE)); #else - DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); + DWIN_Frame_TitleCopy(94, 2, 33, 11); // "Tune" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); + DWIN_Draw_Label(TUNE_CASE_SPEED, GET_TEXT_F(MSG_SPEED)); #if HAS_HOTEND - DWIN_Draw_Label(MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_Label(TUNE_CASE_TEMP, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); #endif #if HAS_HEATED_BED - DWIN_Draw_Label(MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_Label(TUNE_CASE_BED, GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); #endif #if HAS_FAN - DWIN_Draw_Label(MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_Label(TUNE_CASE_FAN, GET_TEXT_F(MSG_FAN_SPEED)); #endif - DWIN_Draw_Label(MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + DWIN_Draw_Label(TUNE_CASE_ZOFF, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else - DWIN_Frame_TitleCopy(1, 94, 2, 126, 12); - DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed + Item_AreaCopy(1, 179, 92, 190, TUNE_CASE_SPEED); // "Print speed" #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TUNE_CASE_TEMP)); // Hotend... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TUNE_CASE_TEMP)); // ...Temperature + Item_AreaCopy(197, 104, 238, 114, TUNE_CASE_TEMP); // "Hotend" + Item_AreaCopy( 1, 89, 83, 101, TUNE_CASE_TEMP, 44); // "Temperature" #endif #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TUNE_CASE_BED)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TUNE_CASE_BED)); // ...Temperature + Item_AreaCopy(240, 104, 264, 114, TUNE_CASE_BED); // "Bed" + Item_AreaCopy( 1, 89, 83, 101, TUNE_CASE_BED, 27); // "Temperature" #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TUNE_CASE_FAN)); // Fan speed + Item_AreaCopy(0, 119, 64, 132, TUNE_CASE_FAN); // "Fan speed" #endif #if HAS_ZOFFSET_ITEM - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(TUNE_CASE_ZOFF)); // Z-offset + Item_AreaCopy(93, 179, 141, 189, TUNE_CASE_ZOFF); // "Z-offset" #endif #endif } @@ -908,90 +958,64 @@ void Draw_Tune_Menu() { if (select_tune.now) Draw_Menu_Cursor(select_tune.now); Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); + Draw_Edit_Integer3(TUNE_CASE_SPEED, feedrate_percentage); #if HAS_HOTEND Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.degTargetHotend(0)); + Draw_Edit_Integer3(TUNE_CASE_TEMP, thermalManager.degTargetHotend(0)); #endif #if HAS_HEATED_BED Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.degTargetBed()); + Draw_Edit_Integer3(TUNE_CASE_BED, thermalManager.degTargetBed()); #endif #if HAS_FAN Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN), thermalManager.fan_speed[0]); + Draw_Edit_Integer3(TUNE_CASE_FAN, thermalManager.fan_speed[0]); #endif #if HAS_ZOFFSET_ITEM Draw_Menu_Line(TUNE_CASE_ZOFF, ICON_Zoffset); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); #endif } -void draw_max_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 245, 119, 269, 129, LBLX, line); // "Max" -} -void draw_max_accel_en(const uint16_t line) { - draw_max_en(line); - DWIN_Frame_AreaCopy(1, 1, 135, 79, 145, LBLX + 27, line); // "Acceleration" -} -void draw_speed_en(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 184, 119, 224, 132, LBLX + inset, line); // "Speed" -} -void draw_jerk_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 64, 119, 106, 129, LBLX + 27, line); // "Jerk" -} -void draw_steps_per_mm(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 1, 151, 101, 161, LBLX, line); // "Steps-per-mm" -} -void say_x(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 95, 104, 102, 114, LBLX + inset, line); // "X" -} -void say_y(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 104, 104, 110, 114, LBLX + inset, line); // "Y" -} -void say_z(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 112, 104, 120, 114, LBLX + inset, line); // "Z" -} -void say_e(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 237, 119, 244, 129, LBLX + inset, line); // "E" -} - +// +// Motion Menu +// void Draw_Motion_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Motion" - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(MOTION_CASE_RATE)); // Max speed - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_ACCEL)); // Max... - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(MOTION_CASE_ACCEL) + 1); // ...Acceleration + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Motion" + Item_AreaCopy(173, 133, 228, 147, MOTION_CASE_RATE); // Max speed + Item_AreaCopy(173, 133, 200, 147, MOTION_CASE_ACCEL); // Max... + Item_AreaCopy(28, 149, 69, 161, MOTION_CASE_ACCEL, 30, 1); // ...Acceleration #if HAS_CLASSIC_JERK - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_JERK)); // Max... - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(MOTION_CASE_JERK) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(MOTION_CASE_JERK)); // ...Jerk + Item_AreaCopy(173, 133, 200, 147, MOTION_CASE_JERK); // Max... + Item_AreaCopy(1, 180, 28, 192, MOTION_CASE_JERK, 30, 1); // ... + Item_AreaCopy(202, 133, 228, 147, MOTION_CASE_JERK, 57); // ...Jerk #endif - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(MOTION_CASE_STEPS)); // Flow ratio + Item_AreaCopy(153, 148, 194, 161, MOTION_CASE_STEPS); // Flow ratio } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOTION)); #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" + DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Motion" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(MOTION_CASE_RATE), F("Feedrate")); - DWIN_Draw_Label(MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); + DWIN_Draw_Label(MOTION_CASE_RATE, F("Feedrate")); // "Feedrate" + DWIN_Draw_Label(MOTION_CASE_ACCEL, GET_TEXT_F(MSG_ACCELERATION)); // "Acceleration" #if HAS_CLASSIC_JERK - DWIN_Draw_Label(MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); + DWIN_Draw_Label(MOTION_CASE_JERK, GET_TEXT_F(MSG_JERK)); // "Jerk" #endif - DWIN_Draw_Label(MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); + DWIN_Draw_Label(MOTION_CASE_STEPS, GET_TEXT_F(MSG_STEPS_PER_MM)); // "Steps/mm" #else - draw_max_en(MBASE(MOTION_CASE_RATE)); draw_speed_en(27, MBASE(MOTION_CASE_RATE)); // "Max Speed" - draw_max_accel_en(MBASE(MOTION_CASE_ACCEL)); // "Max Acceleration" + say_max_en(MOTION_CASE_RATE); say_speed_en(30, MOTION_CASE_RATE); // "Max Speed" + say_max_accel_en(MOTION_CASE_ACCEL); // "Max Acceleration" #if HAS_CLASSIC_JERK - draw_max_en(MBASE(MOTION_CASE_JERK)); draw_jerk_en(MBASE(MOTION_CASE_JERK)); // "Max Jerk" + say_max_en(MOTION_CASE_JERK); say_jerk_en(MOTION_CASE_JERK); // "Max Jerk" #endif - draw_steps_per_mm(MBASE(MOTION_CASE_STEPS)); // "Steps-per-mm" + say_steps_per_mm_en(MOTION_CASE_STEPS); // "Steps-per-mm" #endif } @@ -1020,9 +1044,9 @@ void Draw_Motion_Menu() { if (toohigh) { DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); // Temp Too High DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); @@ -1032,7 +1056,7 @@ void Draw_Motion_Menu() { else { DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); // Tenp Too Low DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { @@ -1055,7 +1079,7 @@ void Draw_Popup_Bkgd_60() { Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); + DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); // Nozzle Too Cold DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 69 + 33, 240); DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); } @@ -1071,7 +1095,7 @@ void Popup_Window_Resume() { Clear_Popup_Area(); Draw_Popup_Bkgd_105(); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); // Resume Interrupted Print DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); DWIN_ICON_Show(ICON, ICON_Cancel_C, 26, 307); DWIN_ICON_Show(ICON, ICON_Continue_C, 146, 307); @@ -1090,7 +1114,7 @@ void Popup_Window_Home(const bool parking/*=false*/) { Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); + DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); // Wait for Move to Complete DWIN_Frame_AreaCopy(1, 203, 286, 271, 302, 118, 240); DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); } @@ -1107,7 +1131,7 @@ void Popup_Window_Home(const bool parking/*=false*/) { Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); + DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); // Wait for Leveling DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); } else { @@ -1132,8 +1156,8 @@ void Popup_window_PauseOrStop() { Clear_Main_Window(); Draw_Popup_Bkgd_60(); if (HMI_IsChinese()) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause Print + else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop Print DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); @@ -1149,14 +1173,14 @@ void Popup_window_PauseOrStop() { void Draw_Printing_Screen() { if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 30, 1, 71, 14, 14, 9); // Tune - DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // Pause - DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // Stop + DWIN_Frame_TitleCopy(30, 1, 42, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // "Printing Time" + DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // "Remain" } else { - DWIN_Frame_AreaCopy(1, 40, 2, 92, 14, 14, 9); // Tune - DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, 188); // Pause - DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, 188); // Stop + DWIN_Frame_TitleCopy(42, 0, 47, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 1, 43, 97, 59, 41, 188); // "Printing Time" + DWIN_Frame_AreaCopy(1, 100, 43, 152, 56, 176, 188); // "Remain" } } @@ -1180,6 +1204,13 @@ void Draw_Print_ProgressRemain() { DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (_remain_time % 3600) / 60); } +void ICON_ResumeOrPause() { + if (printingIsPaused() || HMI_flag.pause_flag || HMI_flag.pause_action) + ICON_Resume(); + else + ICON_Pause(); +} + void Goto_PrintProcess() { checkkey = PrintProcess; @@ -1187,7 +1218,7 @@ void Goto_PrintProcess() { Draw_Printing_Screen(); ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); ICON_Stop(); // Copy into filebuf string before entry @@ -1209,12 +1240,12 @@ void Goto_MainMenu() { Clear_Main_Window(); if (HMI_IsChinese()) - DWIN_Frame_TitleCopy(1, 2, 2, 27, 14); // "Home" + DWIN_Frame_TitleCopy(2, 2, 26, 13); // "Home" etc else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MAIN)); #else - DWIN_Frame_TitleCopy(1, 0, 2, 39, 12); + DWIN_Frame_TitleCopy(0, 2, 40, 11); // "Home" #endif } @@ -1223,7 +1254,7 @@ void Goto_MainMenu() { ICON_Print(); ICON_Prepare(); ICON_Control(); - TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(select_page.now == 3); + TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); } inline ENCODER_DiffState get_encoder_state() { @@ -1253,11 +1284,13 @@ void HMI_Move_Done(const AxisEnum axis) { void HMI_Move_X() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) { + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); return HMI_Move_Done(X_AXIS); + } LIMIT(HMI_ValueStruct.Move_X_scaled, (X_MIN_POS) * MINUNITMULT, (X_MAX_POS) * MINUNITMULT); current_position.x = HMI_ValueStruct.Move_X_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); DWIN_UpdateLCD(); HMI_Plan_Move(homing_feedrate(X_AXIS)); } @@ -1266,11 +1299,13 @@ void HMI_Move_X() { void HMI_Move_Y() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) { + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); return HMI_Move_Done(Y_AXIS); + } LIMIT(HMI_ValueStruct.Move_Y_scaled, (Y_MIN_POS) * MINUNITMULT, (Y_MAX_POS) * MINUNITMULT); current_position.y = HMI_ValueStruct.Move_Y_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); DWIN_UpdateLCD(); HMI_Plan_Move(homing_feedrate(Y_AXIS)); } @@ -1279,11 +1314,13 @@ void HMI_Move_Y() { void HMI_Move_Z() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) { + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); return HMI_Move_Done(Z_AXIS); + } LIMIT(HMI_ValueStruct.Move_Z_scaled, (Z_MIN_POS) * MINUNITMULT, (Z_MAX_POS) * MINUNITMULT); current_position.z = HMI_ValueStruct.Move_Z_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); DWIN_UpdateLCD(); HMI_Plan_Move(homing_feedrate(Z_AXIS)); } @@ -1297,11 +1334,12 @@ void HMI_Move_Z() { if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scaled)) { last_E_scaled = HMI_ValueStruct.Move_E_scaled; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), last_E_scaled); return HMI_Move_Done(E_AXIS); } LIMIT(HMI_ValueStruct.Move_E_scaled, last_E_scaled - (EXTRUDE_MAXLENGTH) * MINUNITMULT, last_E_scaled + (EXTRUDE_MAXLENGTH) * MINUNITMULT); current_position.e = HMI_ValueStruct.Move_E_scaled / MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); DWIN_UpdateLCD(); HMI_Plan_Move(MMM_TO_MMS(FEEDRATE_E)); } @@ -1328,7 +1366,7 @@ void HMI_Move_Z() { TERN_(EEPROM_SETTINGS, settings.save()); #endif checkkey = HMI_ValueStruct.show_mode == -4 ? Prepare : Tune; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); DWIN_UpdateLCD(); return; } @@ -1338,7 +1376,7 @@ void HMI_Move_Z() { #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(zoff_line), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(zoff_line), HMI_ValueStruct.offset_value); DWIN_UpdateLCD(); } } @@ -1362,27 +1400,27 @@ void HMI_Move_Z() { if (HMI_ValueStruct.show_mode == -2) { checkkey = PLAPreheat; ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[0].hotend_temp); + Draw_Edit_Integer3(temp_line, ui.material_preset[0].hotend_temp); return; } else if (HMI_ValueStruct.show_mode == -3) { checkkey = ABSPreheat; ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); + Draw_Edit_Integer3(temp_line, ui.material_preset[1].hotend_temp); return; } else if (HMI_ValueStruct.show_mode == -1) // Temperature checkkey = TemperatureID; else checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp); thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); return; } // E_Temp limit LIMIT(HMI_ValueStruct.E_Temp, HEATER_0_MINTEMP, thermalManager.hotend_max_target(0)); // E_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp, true); } } @@ -1405,27 +1443,27 @@ void HMI_Move_Z() { if (HMI_ValueStruct.show_mode == -2) { checkkey = PLAPreheat; ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[0].bed_temp); + Draw_Edit_Integer3(bed_line, ui.material_preset[0].bed_temp); return; } else if (HMI_ValueStruct.show_mode == -3) { checkkey = ABSPreheat; ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[1].bed_temp); + Draw_Edit_Integer3(bed_line, ui.material_preset[1].bed_temp); return; } else if (HMI_ValueStruct.show_mode == -1) checkkey = TemperatureID; else checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp); thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); return; } // Bed_Temp limit LIMIT(HMI_ValueStruct.Bed_Temp, BED_MINTEMP, BED_MAX_TARGET); // Bed_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp, true); } } @@ -1449,27 +1487,27 @@ void HMI_Move_Z() { if (HMI_ValueStruct.show_mode == -2) { checkkey = PLAPreheat; ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[0].fan_speed); + Draw_Edit_Integer3(fan_line, ui.material_preset[0].fan_speed); return; } else if (HMI_ValueStruct.show_mode == -3) { checkkey = ABSPreheat; ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[1].fan_speed); + Draw_Edit_Integer3(fan_line, ui.material_preset[1].fan_speed); return; } else if (HMI_ValueStruct.show_mode == -1) checkkey = TemperatureID; else checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed); thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); return; } // Fan_speed limit LIMIT(HMI_ValueStruct.Fan_speed, 0, 255); // Fan_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed, true); } } @@ -1482,13 +1520,13 @@ void HMI_PrintSpeed() { checkkey = Tune; EncoderRate.enabled = false; feedrate_percentage = HMI_ValueStruct.print_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed); return; } // print_speed limit LIMIT(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED, MAX_PRINT_SPEED); // print_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed, true); } } @@ -1502,7 +1540,7 @@ void HMI_MaxFeedspeedXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed); return; } // MaxFeedspeed limit @@ -1510,7 +1548,7 @@ void HMI_MaxFeedspeedXYZE() { NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; // MaxFeedspeed value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed, true); } } @@ -1522,7 +1560,7 @@ void HMI_MaxAccelerationXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) planner.set_max_acceleration(HMI_flag.acc_axis, HMI_ValueStruct.Max_Acceleration); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration); return; } // MaxAcceleration limit @@ -1530,7 +1568,7 @@ void HMI_MaxAccelerationXYZE() { NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; // MaxAcceleration value - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration, true); } } @@ -1544,7 +1582,7 @@ void HMI_MaxAccelerationXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) planner.set_max_jerk(HMI_flag.jerk_axis, HMI_ValueStruct.Max_Jerk_scaled / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); return; } // MaxJerk limit @@ -1552,7 +1590,7 @@ void HMI_MaxAccelerationXYZE() { NOMORE(HMI_ValueStruct.Max_Jerk_scaled, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Jerk_scaled, (MIN_MAXJERK) * MINUNITMULT); // MaxJerk value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); } } @@ -1566,7 +1604,7 @@ void HMI_StepXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step_scaled / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); return; } // Step limit @@ -1574,7 +1612,7 @@ void HMI_StepXYZE() { NOMORE(HMI_ValueStruct.Max_Step_scaled, 999.9 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Step_scaled, MIN_STEP); // Step value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); } } @@ -1642,30 +1680,27 @@ void update_variable() { // Tune page temperature update #if HAS_HOTEND if (_new_hotend_target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), _hotendtarget); + Draw_Edit_Integer3(TUNE_CASE_TEMP + MROWS - index_tune, _hotendtarget); #endif #if HAS_HEATED_BED if (_new_bed_target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), _bedtarget); + Draw_Edit_Integer3(TUNE_CASE_BED + MROWS - index_tune, _bedtarget); #endif #if HAS_FAN if (_new_fanspeed) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), _fanspeed); + Draw_Edit_Integer3(TUNE_CASE_FAN + MROWS - index_tune, _fanspeed); #endif } else if (checkkey == TemperatureID) { // Temperature page temperature update #if HAS_HOTEND - if (_new_hotend_target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_TEMP), _hotendtarget); + if (_new_hotend_target) Draw_Edit_Integer3(TEMP_CASE_TEMP, _hotendtarget); #endif #if HAS_HEATED_BED - if (_new_bed_target) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_BED), _bedtarget); + if (_new_bed_target) Draw_Edit_Integer3(TEMP_CASE_BED, _bedtarget); #endif #if HAS_FAN - if (_new_fanspeed) - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_FAN), _fanspeed); + if (_new_fanspeed) Draw_Edit_Integer3(TEMP_CASE_FAN, _fanspeed); #endif } @@ -1976,22 +2011,22 @@ void Draw_Info_Menu() { DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, F(SHORT_BUILD_VERSION)); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" + DWIN_Frame_TitleCopy(30, 17, 28, 13); // "Info" - DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); - DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); - DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); + DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); // "Size" + DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" + DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); #else - DWIN_Frame_TitleCopy(1, 190, 16, 215, 26); // "Info" + DWIN_Frame_TitleCopy(192, 15, 23, 12); // "Info" #endif - DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); - DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); - DWIN_Frame_AreaCopy(1, 0, 165, 94, 175, 89, 248); + DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); // "Size" + DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); // "Firmware Version" + DWIN_Frame_AreaCopy(1, 1, 164, 96, 175, 89, 248); // "Contact details" } DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); @@ -2005,21 +2040,20 @@ void Draw_Info_Menu() { void Draw_Print_File_Menu() { Clear_Title_Bar(); - if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 0, 31, 55, 44); // "Print file" - } + if (HMI_IsChinese()) + DWIN_Frame_TitleCopy(0, 31, 56, 14); // "Print file" else { #ifdef USE_STRING_HEADINGS - Draw_Title("Print file"); // TODO: GET_TEXT_F + Draw_Title(GET_TEXT_F(MSG_MEDIA_MENU)); #else - DWIN_Frame_TitleCopy(1, 52, 31, 137, 41); // "Print file" + DWIN_Frame_TitleCopy(52, 31, 86, 11); // "Print file" #endif } Redraw_SD_List(); } -/* Main Process */ +// Main Process void HMI_MainMenu() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2030,7 +2064,7 @@ void HMI_MainMenu() { case 0: ICON_Print(); break; case 1: ICON_Print(); ICON_Prepare(); break; case 2: ICON_Prepare(); ICON_Control(); break; - case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } @@ -2039,8 +2073,8 @@ void HMI_MainMenu() { switch (select_page.now) { case 0: ICON_Print(); ICON_Prepare(); break; case 1: ICON_Prepare(); ICON_Control(); break; - case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(0); break; - case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } @@ -2144,9 +2178,8 @@ void HMI_SelectFile() { Draw_Back_First(); TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); } - else { + else Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) - } } else { Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight @@ -2195,11 +2228,12 @@ void HMI_SelectFile() { Goto_PrintProcess(); } } -HMI_SelectFileExit: - DWIN_UpdateLCD(); + + HMI_SelectFileExit: + DWIN_UpdateLCD(); } -/* Printing */ +// Printing void HMI_Printing() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2219,10 +2253,10 @@ void HMI_Printing() { case 0: ICON_Tune(); break; case 1: ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); break; case 2: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); ICON_Stop(); break; } @@ -2233,10 +2267,10 @@ void HMI_Printing() { switch (select_print.now) { case 0: ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); break; case 1: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); ICON_Stop(); break; case 2: ICON_Stop(); break; @@ -2288,7 +2322,7 @@ void HMI_Printing() { DWIN_UpdateLCD(); } -/* Pause and Stop window */ +// Pause and Stop window void HMI_PauseOrStop() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2301,18 +2335,13 @@ void HMI_PauseOrStop() { if (select_print.now == 1) { // pause window if (HMI_flag.select_flag) { HMI_flag.pause_action = true; - ICON_Continue(); queue.inject_P(PSTR("M25")); } - else { - // cancel pause - } Goto_PrintProcess(); } else if (select_print.now == 2) { // stop window if (HMI_flag.select_flag) { checkkey = Back_Main; - if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user card.abortFilePrintSoon(); // Let the main loop handle SD abort dwin_abort_flag = true; // Reset feedrate, return to Home @@ -2320,6 +2349,7 @@ void HMI_PauseOrStop() { host_action_cancel(); #endif Popup_Window_Home(true); + if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! } else Goto_PrintProcess(); // cancel stop @@ -2332,25 +2362,35 @@ void Draw_Move_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 192, 1, 233, 14); // "Move" - DWIN_Frame_AreaCopy(1, 58, 118, 106, 132, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 109, 118, 157, 132, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 160, 118, 209, 132, LBLX, MBASE(3)); + DWIN_Frame_TitleCopy(192, 1, 42, 14); // "Move" + Item_AreaCopy(58, 118, 106, 132, 1); + Item_AreaCopy(109, 118, 157, 132, 2); + Item_AreaCopy(160, 118, 209, 132, 3); #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 212, 118, 253, 131, LBLX, MBASE(4)); + Item_AreaCopy(212, 118, 253, 131, 4); #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); #else - DWIN_Frame_TitleCopy(1, 231, 2, 265, 12); // "Move" + DWIN_Frame_TitleCopy(231, 2, 35, 11); // "Move" #endif - draw_move_en(MBASE(1)); say_x(36, MBASE(1)); // "Move X" - draw_move_en(MBASE(2)); say_y(36, MBASE(2)); // "Move Y" - draw_move_en(MBASE(3)); say_z(36, MBASE(3)); // "Move Z" - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" + + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(1, GET_TEXT_F(MSG_MOVE_X)); + DWIN_Draw_Label(2, GET_TEXT_F(MSG_MOVE_Y)); + DWIN_Draw_Label(3, GET_TEXT_F(MSG_MOVE_Z)); + #if HAS_HOTEND + DWIN_Draw_Label(4, GET_TEXT_F(MSG_MOVE_E)); + #endif + #else + say_move_en(1); say_x_en(38, 1); // "Move X" + say_move_en(2); say_y_en(38, 2); // "Move Y" + say_move_en(3); say_z_en(38, 3); // "Move Z" + #if HAS_HOTEND + say_move_en(4); Item_AreaCopy(99, 194, 151, 204, 4, 38); // "Move Extruder" + #endif #endif } @@ -2361,58 +2401,208 @@ void Draw_Move_Menu() { LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); } -void Draw_AdvSet_Menu() { +void Item_Adv_HomeOffsets(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Set Home Offsets" + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + #else + Item_AreaCopy(1, 76, 102, 87, row); // "Set Home Offsets" + #endif + } + Draw_Menu_Line(row, ICON_HomeOff); + Draw_More_Icon(row); +} + +#if HAS_ONESTEP_LEVELING + + void Item_Adv_ProbeOffsets(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Probe Offsets" + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + #else + say_probe_offs_en(0, row); + #endif + } + Draw_Menu_Line(row, ICON_ProbeOff); + Draw_More_Icon(row); + } + +#endif + +void Item_Adv_HotendPID(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Hotend PID" + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, F("Hotend PID")); + #else + Item_AreaCopy(96, 104, 167, 114, row); // "Hotend PID" + #endif + } + Draw_Menu_Line(row, ICON_PIDNozzle); +} + +void Item_Adv_BedPID(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Bed PID" + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, F("Bed PID")); + #else + Item_AreaCopy(241, 104, 263, 115, row); // "Bed" + Item_AreaCopy(145, 104, 167, 114, row, 27); // "PID" + #endif + } + Draw_Menu_Line(row, ICON_PIDbed); +} + +#if ENABLED(POWER_LOSS_RECOVERY) + + void Item_Adv_PLR(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Power-loss Recovery" + } + else { + #ifdef USE_STRING_TITLES + DWIN_Draw_Label(row, GET_TEXT_F(MSG_ZPROBE_OFFSETS)); + #else + Item_AreaCopy(1, 208, 137, 221, row); // "Power-loss Recovery" + #endif + } + Draw_Menu_Line(row, ICON_Motion); + Draw_Checkbox_Line(row, recovery.enabled); + } + +#endif + +void Draw_AdvancedSettings_Menu() { Clear_Main_Window(); - #if ADVSET_CASE_TOTAL >= 6 + #if ADVSET_CASE_TOTAL >= TROWS const int16_t scroll = MROWS - index_advset; // Scrolled-up lines - #define ASCROL(L) (scroll + (L)) #else - #define ASCROL(L) (L) + constexpr int16_t scroll = 0; #endif + #define ASCROL(L) (scroll + (L)) + #define AVISI(L) VISI(ADVSET_CASE_TOTAL, L, ASCROL(L)) - #define AVISI(L) WITHIN(ASCROL(L), 0, MROWS) - - Draw_Title(GET_TEXT_F(MSG_ADVANCED_SETTINGS)); + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_ADVANCED_SETTINGS)); + #else + DWIN_Frame_TitleCopy(93, 401, 126, 15); // "Advanced Settings" + #endif if (AVISI(0)) Draw_Back_First(select_advset.now == 0); - if (AVISI(ADVSET_CASE_HOMEOFF)) Draw_Menu_Line(ASCROL(ADVSET_CASE_HOMEOFF), ICON_HomeOff, GET_TEXT(MSG_SET_HOME_OFFSETS),true); // Home Offset > + if (AVISI(ADVSET_CASE_HOMEOFF)) Item_Adv_HomeOffsets(ASCROL(ADVSET_CASE_HOMEOFF)); // Set Home Offsets > #if HAS_ONESTEP_LEVELING - if (AVISI(ADVSET_CASE_PROBEOFF)) Draw_Menu_Line(ASCROL(ADVSET_CASE_PROBEOFF), ICON_ProbeOff, GET_TEXT(MSG_ZPROBE_OFFSETS),true); // Probe Offset > + if (AVISI(ADVSET_CASE_PROBEOFF)) Item_Adv_ProbeOffsets(ASCROL(ADVSET_CASE_PROBEOFF)); // Probe Offsets > #endif - if (AVISI(ADVSET_CASE_HEPID)) Draw_Menu_Line(ASCROL(ADVSET_CASE_HEPID), ICON_PIDNozzle, "Hotend PID", false); // Nozzle PID - if (AVISI(ADVSET_CASE_BEDPID)) Draw_Menu_Line(ASCROL(ADVSET_CASE_BEDPID), ICON_PIDbed, "Bed PID", false); // Bed PID + if (AVISI(ADVSET_CASE_HEPID)) Item_Adv_HotendPID(ASCROL(ADVSET_CASE_HEPID)); // Nozzle PID + if (AVISI(ADVSET_CASE_BEDPID)) Item_Adv_BedPID(ASCROL(ADVSET_CASE_BEDPID)); // Bed PID #if ENABLED(POWER_LOSS_RECOVERY) - if (AVISI(ADVSET_CASE_PWRLOSSR)) { - Draw_Menu_Line(ASCROL(ADVSET_CASE_PWRLOSSR), ICON_Motion, "Power-loss recovery", false); // Power-loss recovery - Draw_Chkb_Line(ASCROL(ADVSET_CASE_PWRLOSSR), recovery.enabled); - } + if (AVISI(ADVSET_CASE_PWRLOSSR)) Item_Adv_PLR(ASCROL(ADVSET_CASE_PWRLOSSR)); // Power-loss recovery #endif if (select_advset.now) Draw_Menu_Cursor(ASCROL(select_advset.now)); } +void Item_HomeOffs_X(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Home Offset X" + } + else { + #ifdef USE_STRING_TITLES + Draw_Menu_Line(row, ICON_HomeOffX, GET_TEXT_F(MSG_HOME_OFFSET_X)); + #else + say_home_offs_en(row); say_x_en(75, row); // "Home Offset X" + #endif + } + Draw_Menu_Line(row, ICON_HomeOff); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffX_scaled); +} + +void Item_HomeOffs_Y(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Home Offset Y" + } + else { + #ifdef USE_STRING_TITLES + Draw_Menu_Line(row, ICON_HomeOffY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); + #else + say_home_offs_en(row); say_y_en(75, row); // "Home Offset X" + #endif + } + Draw_Menu_Line(row, ICON_HomeOff); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffY_scaled); +} + +void Item_HomeOffs_Z(const uint8_t row) { + if (false && HMI_IsChinese()) { + // TODO: Chinese "Home Offset Z" + } + else { + #ifdef USE_STRING_TITLES + Draw_Menu_Line(row, ICON_HomeOffZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); + #else + say_home_offs_en(row); say_z_en(75, row); // "Home Offset Z" + #endif + } + Draw_Menu_Line(row, ICON_HomeOff); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffZ_scaled); +} + void Draw_HomeOff_Menu() { Clear_Main_Window(); - Draw_Title(GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // Home Offsets + if (false && HMI_IsChinese()) { + // TODO: Chinese "Home Offsets" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + #else + DWIN_Frame_TitleCopy(1, 401, 91, 12); // "Home Offsets" + #endif + } Draw_Back_First(select_item.now == 0); - Draw_Menu_Line(1, ICON_HomeOffX, GET_TEXT(MSG_HOME_OFFSET_X)); // Home X Offset - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Home_OffX_scaled); - Draw_Menu_Line(2, ICON_HomeOffY, GET_TEXT(MSG_HOME_OFFSET_Y)); // Home Y Offset - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Home_OffY_scaled); - Draw_Menu_Line(3, ICON_HomeOffZ, GET_TEXT(MSG_HOME_OFFSET_Z)); // Home Y Offset - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Home_OffZ_scaled); + Item_HomeOffs_X(1); // "Home Offset X" + Item_HomeOffs_Y(2); // "Home Offset Y" + Item_HomeOffs_Z(3); // "Home Offset Z" if (select_item.now) Draw_Menu_Cursor(select_item.now); } #if HAS_ONESTEP_LEVELING + void Draw_ProbeOff_Menu() { Clear_Main_Window(); - Draw_Title(GET_TEXT_F(MSG_ZPROBE_OFFSETS)); // Probe Offsets Draw_Back_First(select_item.now == 0); - Draw_Menu_Line(1, ICON_ProbeOffX, GET_TEXT(MSG_ZPROBE_XOFFSET)); // Probe X Offset - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Probe_OffX_scaled); - Draw_Menu_Line(2, ICON_ProbeOffY, GET_TEXT(MSG_ZPROBE_YOFFSET)); // Probe Y Offset - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + if (false && HMI_IsChinese()) { + // TODO: Chinese "Probe Offsets" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_ZPROBE_OFFSETS)); + #else + DWIN_Frame_TitleCopy(124, 431, 91, 12); // "Probe Offsets" + #endif + #ifdef USE_STRING_TITLES + Draw_Menu_Line(1, ICON_ProbeOffX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset + Draw_Menu_Line(2, ICON_ProbeOffY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset + #else + say_probe_offs_en(1); say_x_en(75, 1); // "Probe Offset X" + say_probe_offs_en(2); say_y_en(75, 2); // "Probe Offset Y" + #endif + } + + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Probe_OffX_scaled); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + if (select_item.now) Draw_Menu_Cursor(select_item.now); } #endif @@ -2431,7 +2621,7 @@ void HMI_AudioFeedback(const bool success=true) { #endif } -/* Prepare */ +// Prepare void HMI_Prepare() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2495,12 +2685,12 @@ void HMI_Prepare() { select_axis.reset(); Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(1), current_position.x * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(2), current_position.y * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 216, MBASE(3), current_position.z * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), current_position.x * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), current_position.y * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), current_position.z * MINUNITMULT); #if HAS_HOTEND HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); #endif break; case PREPARE_CASE_DISA: // Disable steppers @@ -2518,7 +2708,7 @@ void HMI_Prepare() { checkkey = Homeoffset; HMI_ValueStruct.show_mode = -4; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 @@ -2559,60 +2749,61 @@ void Draw_Temperature_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 236, 2, 263, 13); // "Temperature" + DWIN_Frame_TitleCopy(236, 2, 28, 12); // "Temperature" #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TEMP_CASE_TEMP)); + Item_AreaCopy(1, 134, 56, 146, TEMP_CASE_TEMP); #endif #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TEMP_CASE_BED)); + Item_AreaCopy(58, 134, 113, 146, TEMP_CASE_BED); #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TEMP_CASE_FAN)); + Item_AreaCopy(115, 134, 170, 146, TEMP_CASE_FAN); #endif #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(TEMP_CASE_PLA)); - DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(TEMP_CASE_ABS)); + Item_AreaCopy(100, 89, 178, 101, TEMP_CASE_PLA); + Item_AreaCopy(180, 89, 260, 100, TEMP_CASE_ABS); #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" + DWIN_Frame_TitleCopy(56, 15, 85, 14); // "Temperature" #endif #ifdef USE_STRING_TITLES #if HAS_HOTEND - DWIN_Draw_Label(MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_Label(TEMP_CASE_TEMP, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); #endif #if HAS_HEATED_BED - DWIN_Draw_Label(MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_Label(TEMP_CASE_BED, GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); #endif #if HAS_FAN - DWIN_Draw_Label(MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_Label(TEMP_CASE_FAN, GET_TEXT_F(MSG_FAN_SPEED)); #endif #if HAS_HOTEND - DWIN_Draw_Label(MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); - DWIN_Draw_Label(MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); + DWIN_Draw_Label(TEMP_CASE_PLA, F(PREHEAT_1_LABEL " Preheat Settings")); + DWIN_Draw_Label(TEMP_CASE_ABS, F(PREHEAT_2_LABEL " Preheat Settings")); #endif #else #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TEMP_CASE_TEMP)); // Nozzle... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TEMP_CASE_TEMP)); // ...Temperature + Item_AreaCopy(197, 104, 238, 114, TEMP_CASE_TEMP); // "Nozzle" + Item_AreaCopy(1, 89, 83, 101, TEMP_CASE_TEMP, 44); // "Temperature" #endif #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TEMP_CASE_BED)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TEMP_CASE_BED)); // ...Temperature + Item_AreaCopy(240, 104, 264, 114, TEMP_CASE_BED); // "Bed" + Item_AreaCopy(1, 89, 83, 101, TEMP_CASE_BED, 27); // "Temperature" #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TEMP_CASE_FAN)); // Fan speed + Item_AreaCopy( 1, 119, 61, 132, TEMP_CASE_FAN); // "Fan speed" #endif #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_PLA)); // Preheat... - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(TEMP_CASE_PLA)); // ...PLA - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(TEMP_CASE_PLA)); // PLA setting - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_ABS)); // Preheat... - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(TEMP_CASE_ABS)); // ...ABS - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(TEMP_CASE_ABS)); // ABS setting + Item_AreaCopy(107, 76, 156, 86, TEMP_CASE_PLA); // "Preheat" + say_pla_en(52, TEMP_CASE_PLA); // "PLA" + Item_AreaCopy(150, 135, 202, 148, TEMP_CASE_PLA, 79); // "Settings" + + Item_AreaCopy(107, 76, 156, 86, TEMP_CASE_ABS); // "Preheat" + say_abs_en(52, TEMP_CASE_ABS); // "ABS" + Item_AreaCopy(150, 135, 202, 148, TEMP_CASE_ABS, 81); // "Settings" #endif #endif } @@ -2625,15 +2816,15 @@ void Draw_Temperature_Menu() { #define _TMENU_ICON(N) Draw_Menu_Line(++i, ICON_SetEndTemp + (N) - 1) #if HAS_HOTEND _TMENU_ICON(TEMP_CASE_TEMP); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.degTargetHotend(0)); + Draw_Edit_Integer3(i, thermalManager.degTargetHotend(0)); #endif #if HAS_HEATED_BED _TMENU_ICON(TEMP_CASE_BED); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.degTargetBed()); + Draw_Edit_Integer3(i, thermalManager.degTargetBed()); #endif #if HAS_FAN _TMENU_ICON(TEMP_CASE_FAN); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); + Draw_Edit_Integer3(i, thermalManager.fan_speed[0]); #endif #if HAS_HOTEND // PLA/ABS items have submenus @@ -2644,7 +2835,7 @@ void Draw_Temperature_Menu() { #endif } -/* Control */ +// Control void HMI_Control() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2659,20 +2850,14 @@ void HMI_Control() { Scroll_Menu(DWIN_SCROLL_UP); switch (index_control) { // Last menu items - case CONTROL_CASE_ADVSET: // Advanced Settings > - Draw_Menu_Item(MROWS, ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), true); - break; - case CONTROL_CASE_INFO: // Info > - Item_Control_Info(MBASE(MROWS)); - Draw_Menu_Icon(MROWS, ICON_Info); - break; + case CONTROL_CASE_ADVSET: Item_Control_Advanced(MROWS); break; + case CONTROL_CASE_INFO: Item_Control_Info(MROWS); break; default: break; } } - else { + else Move_Highlight(1, select_control.now + MROWS - index_control); - } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { @@ -2681,20 +2866,14 @@ void HMI_Control() { index_control--; Scroll_Menu(DWIN_SCROLL_DOWN); switch (index_control) { // First menu items - case MROWS : - Draw_Back_First(); - break; - case MROWS + 1: // Temperature > - Draw_Menu_Line(0, ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), true); - break; - case MROWS + 2: // Move > - Draw_Menu_Line(0, ICON_Motion, GET_TEXT(MSG_MOTION), true); + case MROWS: Draw_Back_First(); break; + case MROWS + 1: Item_Control_Temp(0); break; + case MROWS + 2: Item_Control_Motion(0); break; default: break; } } - else { + else Move_Highlight(-1, select_control.now + MROWS - index_control); - } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { @@ -2731,7 +2910,7 @@ void HMI_Control() { case CONTROL_CASE_ADVSET: // Advanced Settings checkkey = AdvSet; select_advset.reset(); - Draw_AdvSet_Menu(); + Draw_AdvancedSettings_Menu(); break; case CONTROL_CASE_INFO: // Info checkkey = Info; @@ -2746,7 +2925,7 @@ void HMI_Control() { #if HAS_ONESTEP_LEVELING - /* Leveling */ + // Leveling void HMI_Leveling() { Popup_Window_Leveling(); DWIN_UpdateLCD(); @@ -2755,7 +2934,7 @@ void HMI_Control() { #endif -/* Axis Move */ +// Axis Move void HMI_AxisMove() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2767,10 +2946,10 @@ void HMI_AxisMove() { HMI_flag.ETempTooLow_flag = false; HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), 0); DWIN_UpdateLCD(); } return; @@ -2795,19 +2974,19 @@ void HMI_AxisMove() { case 1: // X axis move checkkey = Move_X; HMI_ValueStruct.Move_X_scaled = current_position.x * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); EncoderRate.enabled = true; break; case 2: // Y axis move checkkey = Move_Y; HMI_ValueStruct.Move_Y_scaled = current_position.y * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); EncoderRate.enabled = true; break; case 3: // Z axis move checkkey = Move_Z; HMI_ValueStruct.Move_Z_scaled = current_position.z * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); EncoderRate.enabled = true; break; #if HAS_HOTEND @@ -2823,7 +3002,7 @@ void HMI_AxisMove() { #endif checkkey = Extruder; HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); EncoderRate.enabled = true; break; #endif @@ -2832,7 +3011,7 @@ void HMI_AxisMove() { DWIN_UpdateLCD(); } -/* TemperatureID */ +// TemperatureID void HMI_Temperature() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2856,7 +3035,7 @@ void HMI_Temperature() { case TEMP_CASE_TEMP: // Nozzle temperature checkkey = ETemp; HMI_ValueStruct.E_Temp = thermalManager.degTargetHotend(0); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); + Draw_Edit_Integer3(1, HMI_ValueStruct.E_Temp, true); EncoderRate.enabled = true; break; #endif @@ -2864,7 +3043,7 @@ void HMI_Temperature() { case TEMP_CASE_BED: // Bed temperature checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = thermalManager.degTargetBed(); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); + Draw_Edit_Integer3(2, HMI_ValueStruct.Bed_Temp, true); EncoderRate.enabled = true; break; #endif @@ -2872,7 +3051,7 @@ void HMI_Temperature() { case TEMP_CASE_FAN: // Fan speed checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); + Draw_Edit_Integer3(3, HMI_ValueStruct.Fan_speed, true); EncoderRate.enabled = true; break; #endif @@ -2885,53 +3064,53 @@ void HMI_Temperature() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 59, 16, 139, 29); // "PLA Settings" - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + DWIN_Frame_TitleCopy(59, 16, 81, 14); // "PLA Settings" + Item_AreaCopy(100, 89, 124, 101, PREHEAT_CASE_TEMP); + Item_AreaCopy(1, 134, 56, 146, PREHEAT_CASE_TEMP, 24); // PLA nozzle temp #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_BED)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // PLA bed temp + Item_AreaCopy(100, 89, 124, 101, PREHEAT_CASE_BED); + Item_AreaCopy(58, 134, 113, 146, PREHEAT_CASE_BED, 24); // PLA bed temp #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + Item_AreaCopy(100, 89, 124, 101, PREHEAT_CASE_FAN); + Item_AreaCopy(115, 134, 170, 146, PREHEAT_CASE_FAN, 24); // PLA fan speed #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + Item_AreaCopy(72, 148, 151, 162, PREHEAT_CASE_SAVE); // Save PLA configuration #endif } else { #ifdef USE_STRING_HEADINGS - Draw_Title("PLA Settings"); // TODO: GET_TEXT_F + Draw_Title(PREHEAT_1_LABEL " Settings"); // TODO: GET_TEXT_F #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" + DWIN_Frame_TitleCopy(57, 16, 84, 14); // "PLA Settings" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + DWIN_Draw_Label(PREHEAT_CASE_TEMP, F("Nozzle Temp")); #if HAS_HEATED_BED - DWIN_Draw_Label(MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + DWIN_Draw_Label(PREHEAT_CASE_BED, F("Bed Temp")); #endif #if HAS_FAN - DWIN_Draw_Label(MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_Label(PREHEAT_CASE_FAN, GET_TEXT_F(MSG_FAN_SPEED)); #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_Label(MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_Label(PREHEAT_CASE_SAVE, GET_TEXT_F(MSG_STORE_EEPROM)); #endif #else - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + say_pla_en(0, PREHEAT_CASE_TEMP); // "PLA" + Item_AreaCopy(198, 104, 237, 114, PREHEAT_CASE_TEMP, 27); // "Nozzle" + Item_AreaCopy(1, 89, 81, 102, PREHEAT_CASE_TEMP, 71); // "Temperature" #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // PLA bed temp + say_pla_en(0, PREHEAT_CASE_BED); // "PLA" + Item_AreaCopy(240, 104, 264, 114, PREHEAT_CASE_BED, 27); // "Bed" + Item_AreaCopy(1, 89, 83, 101, PREHEAT_CASE_BED, 54); // "Temperature" #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + say_pla_en(0, PREHEAT_CASE_FAN); // "PLA" + Item_AreaCopy(0, 119, 64, 132, PREHEAT_CASE_FAN, 27); // "Fan speed" #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + Item_AreaCopy(98, 164, 233, 177, PREHEAT_CASE_SAVE); // "Save PLA parameters" #endif #endif } @@ -2940,14 +3119,14 @@ void HMI_Temperature() { uint8_t i = 0; Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); + Draw_Edit_Integer3(i, ui.material_preset[0].hotend_temp); #if HAS_HEATED_BED Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); + Draw_Edit_Integer3(i, ui.material_preset[0].bed_temp); #endif #if HAS_FAN Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); + Draw_Edit_Integer3(i, ui.material_preset[0].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) Draw_Menu_Line(++i, ICON_WriteEEPROM); @@ -2962,56 +3141,56 @@ void HMI_Temperature() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 142, 16, 223, 29); // "ABS Settings" + DWIN_Frame_TitleCopy(142, 16, 82, 14); // "ABS Settings" - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + Item_AreaCopy(180, 89, 204, 100, PREHEAT_CASE_TEMP); + Item_AreaCopy(1, 134, 56, 146, PREHEAT_CASE_TEMP, 24); // ABS nozzle temp #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_BED)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // ABS bed temp + Item_AreaCopy(180, 89, 204, 100, PREHEAT_CASE_BED); + Item_AreaCopy(58, 134, 113, 146, PREHEAT_CASE_BED, 24); // ABS bed temp #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + Item_AreaCopy(180, 89, 204, 100, PREHEAT_CASE_FAN); + Item_AreaCopy(115, 134, 170, 146, PREHEAT_CASE_FAN, 24); // ABS fan speed #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(PREHEAT_CASE_SAVE) + 2); // Save ABS configuration + Item_AreaCopy(72, 148, 151, 162, PREHEAT_CASE_SAVE); + Item_AreaCopy(180, 89, 204, 100, PREHEAT_CASE_SAVE, 28, 2); // Save ABS configuration #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title("ABS Settings"); // TODO: GET_TEXT_F #else - DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" + DWIN_Frame_TitleCopy(57, 16, 84, 14); // "ABS Settings" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + DWIN_Draw_Label(PREHEAT_CASE_TEMP, F("Nozzle Temp")); #if HAS_HEATED_BED - DWIN_Draw_Label(MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + DWIN_Draw_Label(PREHEAT_CASE_BED, F("Bed Temp")); #endif #if HAS_FAN - DWIN_Draw_Label(MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_Label(PREHEAT_CASE_FAN, GET_TEXT_F(MSG_FAN_SPEED)); #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_Label(MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_Label(PREHEAT_CASE_SAVE, GET_TEXT_F(MSG_STORE_EEPROM)); #endif #else - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + say_abs_en(0, PREHEAT_CASE_TEMP); // "ABS" + Item_AreaCopy(197, 104, 238, 114, PREHEAT_CASE_TEMP, 29); // "Nozzle" + Item_AreaCopy(1, 89, 34, 102, PREHEAT_CASE_TEMP, 73); // "Temp" #if HAS_HEATED_BED - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // ABS bed temp + say_abs_en(0, PREHEAT_CASE_BED); // "ABS" + Item_AreaCopy(240, 104, 264, 114, PREHEAT_CASE_BED, 29); // "Bed" + Item_AreaCopy(1, 89, 83, 102, PREHEAT_CASE_BED, 56); // "Temperature" #endif #if HAS_FAN - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + say_abs_en(0, PREHEAT_CASE_FAN); // "ABS" + Item_AreaCopy(0, 119, 64, 132, PREHEAT_CASE_FAN, 29); // "Fan speed" #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(PREHEAT_CASE_SAVE)); // Save ABS configuration + Item_AreaCopy(98, 165, 233, 177, PREHEAT_CASE_SAVE); // "Save PLA parameters" + say_abs_en(33, PREHEAT_CASE_SAVE); // "ABS" #endif #endif } @@ -3020,14 +3199,14 @@ void HMI_Temperature() { uint8_t i = 0; Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); + Draw_Edit_Integer3(i, ui.material_preset[1].hotend_temp); #if HAS_HEATED_BED Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); + Draw_Edit_Integer3(i, ui.material_preset[1].bed_temp); #endif #if HAS_FAN Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); + Draw_Edit_Integer3(i, ui.material_preset[1].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) Draw_Menu_Line(++i, ICON_WriteEEPROM); @@ -3045,63 +3224,53 @@ void Draw_Max_Speed_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Max Speed (mm/s)" - auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" + auto say_max_speed_cn = [](const uint8_t line) { + Item_AreaCopy(173, 133, 228, 147, line); // "Max speed" }; - say_max_speed(MBASE(1)); // "Max speed" - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 58, MBASE(1)); // X - say_max_speed(MBASE(2)); // "Max speed" - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 58, MBASE(2) + 3); // Y - say_max_speed(MBASE(3)); // "Max speed" - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 58, MBASE(3) + 3); // Z + say_max_speed_cn(1); // "Max speed" + Item_AreaCopy(229, 133, 236, 147, 1, 58); // "X" + say_max_speed_cn(2); // "Max speed" + Item_AreaCopy(1, 150, 7, 160, 2, 58, 3); // "Y" + say_max_speed_cn(3); // "Max speed" + Item_AreaCopy(9, 150, 16, 160, 3, 58, 3); // "Z" #if HAS_HOTEND - say_max_speed(MBASE(4)); // "Max speed" - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E + say_max_speed_cn(4); // "Max speed" + Item_AreaCopy(18, 150, 25, 160, 4, 58, 3); // "E" #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" + DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Max Speed (mm/s)" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(1), F("Max Feedrate X")); - DWIN_Draw_Label(MBASE(2), F("Max Feedrate Y")); - DWIN_Draw_Label(MBASE(3), F("Max Feedrate Z")); + DWIN_Draw_Label(1, F("Max Feedrate X")); + DWIN_Draw_Label(2, F("Max Feedrate Y")); + DWIN_Draw_Label(3, F("Max Feedrate Z")); #if HAS_HOTEND - DWIN_Draw_Label(MBASE(4), F("Max Feedrate E")); + DWIN_Draw_Label(4, F("Max Feedrate E")); #endif #else - draw_max_en(MBASE(1)); // "Max" - DWIN_Frame_AreaCopy(1, 184, 119, 234, 132, LBLX + 27, MBASE(1)); // "Speed X" - - draw_max_en(MBASE(2)); // "Max" - draw_speed_en(27, MBASE(2)); // "Speed" - say_y(70, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_speed_en(27, MBASE(3)); // "Speed" - say_z(70, MBASE(3)); // "Z" - + say_max_en(1); say_speed_en(30, 1); say_x_en(73, 1); // "Max Speed X" + say_max_en(2); say_speed_en(30, 2); say_y_en(73, 2); // "Max Speed Y" + say_max_en(3); say_speed_en(30, 3); say_z_en(73, 3); // "Max Speed Z" #if HAS_HOTEND - draw_max_en(MBASE(4)); // "Max" - draw_speed_en(27, MBASE(4)); // "Speed" - say_e(70, MBASE(4)); // "E" + say_max_en(4); say_speed_en(30, 4); say_e_en(73, 4); // "Max Speed E" #endif #endif } Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); + Draw_Edit_Integer4(1, planner.settings.max_feedrate_mm_s[X_AXIS]); + Draw_Edit_Integer4(2, planner.settings.max_feedrate_mm_s[Y_AXIS]); + Draw_Edit_Integer4(3, planner.settings.max_feedrate_mm_s[Z_AXIS]); #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + Draw_Edit_Integer4(4, planner.settings.max_feedrate_mm_s[E_AXIS]); #endif } @@ -3109,53 +3278,53 @@ void Draw_Max_Accel_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Acceleration" + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Acceleration" - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(1)); // Max acceleration X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(2) + 2); // Max acceleration Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(3) + 2); // Max acceleration Z + Item_AreaCopy(173, 133, 200, 147, 1); + Item_AreaCopy( 28, 149, 69, 161, 1, 30, 1); + Item_AreaCopy(229, 133, 236, 147, 1, 74); // Max acceleration X + Item_AreaCopy(173, 133, 200, 147, 2); + Item_AreaCopy( 28, 149, 69, 161, 2, 30, 1); + Item_AreaCopy( 1, 150, 7, 160, 2, 74, 2); // Max acceleration Y + Item_AreaCopy(173, 133, 200, 147, 3); + Item_AreaCopy( 28, 149, 69, 161, 3, 30, 1); + Item_AreaCopy( 9, 150, 16, 160, 3, 74, 2); // Max acceleration Z #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(4) + 2); // Max acceleration E + Item_AreaCopy(173, 133, 200, 147, 4); + Item_AreaCopy( 28, 149, 69, 161, 4, 30, 1); + Item_AreaCopy( 18, 150, 25, 160, 4, 74, 2); // Max acceleration E #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" + DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Acceleration" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(1), F("Max Accel X")); - DWIN_Draw_Label(MBASE(2), F("Max Accel Y")); - DWIN_Draw_Label(MBASE(3), F("Max Accel Z")); + DWIN_Draw_Label(1, F("Max Accel X")); + DWIN_Draw_Label(2, F("Max Accel Y")); + DWIN_Draw_Label(3, F("Max Accel Z")); #if HAS_HOTEND - DWIN_Draw_Label(MBASE(4), F("Max Accel E")); + DWIN_Draw_Label(4, F("Max Accel E")); #endif #else - draw_max_accel_en(MBASE(1)); say_x(108, MBASE(1)); // "Max Acceleration X" - draw_max_accel_en(MBASE(2)); say_y(108, MBASE(2)); // "Max Acceleration Y" - draw_max_accel_en(MBASE(3)); say_z(108, MBASE(3)); // "Max Acceleration Z" + say_max_accel_en(1); say_x_en(112, 1); // "Max Acceleration X" + say_max_accel_en(2); say_y_en(112, 2); // "Max Acceleration Y" + say_max_accel_en(3); say_z_en(112, 3); // "Max Acceleration Z" #if HAS_HOTEND - draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" + say_max_accel_en(4); say_e_en(112, 4); // "Max Acceleration E" #endif #endif } Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + Draw_Edit_Integer4(1, planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + Draw_Edit_Integer4(2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + Draw_Edit_Integer4(3, planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + Draw_Edit_Integer4(4, planner.settings.max_acceleration_mm_per_s2[E_AXIS]); #endif } @@ -3164,72 +3333,57 @@ void Draw_Max_Accel_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Jerk" + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Jerk" - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(1)); // Max Jerk speed X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(2) + 3); // Max Jerk speed Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(3)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(3) + 3); // Max Jerk speed Z + Item_AreaCopy(173, 133, 200, 147, 1); + Item_AreaCopy( 1, 180, 28, 192, 1, 30, 1); + Item_AreaCopy(202, 133, 228, 147, 1, 56); + Item_AreaCopy(229, 133, 236, 147, 1, 86); // Max Jerk speed X + Item_AreaCopy(173, 133, 200, 147, 2); + Item_AreaCopy( 1, 180, 28, 192, 2, 30, 1); + Item_AreaCopy(202, 133, 228, 147, 2, 56); + Item_AreaCopy( 1, 150, 7, 160, 2, 86, 3); // Max Jerk speed Y + Item_AreaCopy(173, 133, 200, 147, 3); + Item_AreaCopy( 1, 180, 28, 192, 3, 30, 1); + Item_AreaCopy(202, 133, 228, 147, 3, 56); + Item_AreaCopy( 9, 150, 16, 160, 3, 86, 3); // Max Jerk speed Z #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(4)); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(4) + 3); // Max Jerk speed E + Item_AreaCopy(173, 133, 200, 147, 4); + Item_AreaCopy( 1, 180, 28, 192, 4, 30, 1); + Item_AreaCopy(202, 133, 228, 147, 4, 56); + Item_AreaCopy( 18, 150, 25, 160, 4, 86, 3); // Max Jerk speed E #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_JERK)); #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" + DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Jerk" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(1), F("Max Jerk X")); - DWIN_Draw_Label(MBASE(2), F("Max Jerk Y")); - DWIN_Draw_Label(MBASE(3), F("Max Jerk Z")); + DWIN_Draw_Label(1, GET_TEXT_F(MSG_VA_JERK)); + DWIN_Draw_Label(2, GET_TEXT_F(MSG_VB_JERK)); + DWIN_Draw_Label(3, GET_TEXT_F(MSG_VC_JERK)); #if HAS_HOTEND - DWIN_Draw_Label(MBASE(4), F("Max Jerk E")); + DWIN_Draw_Label(4, GET_TEXT_F(MSG_VE_JERK)); #endif #else - draw_max_en(MBASE(1)); // "Max" - draw_jerk_en(MBASE(1)); // "Jerk" - draw_speed_en(72, MBASE(1)); // "Speed" - say_x(115, MBASE(1)); // "X" - - draw_max_en(MBASE(2)); // "Max" - draw_jerk_en(MBASE(2)); // "Jerk" - draw_speed_en(72, MBASE(2)); // "Speed" - say_y(115, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_jerk_en(MBASE(3)); // "Jerk" - draw_speed_en(72, MBASE(3)); // "Speed" - say_z(115, MBASE(3)); // "Z" - + say_max_jerk_speed_en(1); say_x_en(102, 1); // Max Jerk speed X + say_max_jerk_speed_en(2); say_y_en(102, 2); // Max Jerk speed Y + say_max_jerk_speed_en(3); say_z_en(102, 3); // Max Jerk speed Z #if HAS_HOTEND - draw_max_en(MBASE(4)); // "Max" - draw_jerk_en(MBASE(4)); // "Jerk" - draw_speed_en(72, MBASE(4)); // "Speed" - say_e(115, MBASE(4)); // "E" + say_max_jerk_speed_en(4); say_e_en(102, 4); // Max Jerk speed E #endif #endif } Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); #endif } #endif @@ -3238,53 +3392,53 @@ void Draw_Steps_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Steps per mm" + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Steps per mm" - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(1)); // Transmission Ratio X - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(2) + 3); // Transmission Ratio Y - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(3) + 3); // Transmission Ratio Z + Item_AreaCopy(153, 148, 194, 161, 1); + Item_AreaCopy(229, 133, 236, 147, 1, 44); // Transmission Ratio X + Item_AreaCopy(153, 148, 194, 161, 2); + Item_AreaCopy( 1, 150, 7, 160, 2, 44, 3); // Transmission Ratio Y + Item_AreaCopy(153, 148, 194, 161, 3); + Item_AreaCopy( 9, 150, 16, 160, 3, 44, 3); // Transmission Ratio Z #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(4) + 3); // Transmission Ratio E + Item_AreaCopy(153, 148, 194, 161, 4); + Item_AreaCopy( 18, 150, 25, 160, 4, 44, 3); // Transmission Ratio E #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" + DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Steps per mm" #endif #ifdef USE_STRING_TITLES - DWIN_Draw_Label(MBASE(1), F("Steps/mm X")); - DWIN_Draw_Label(MBASE(2), F("Steps/mm Y")); - DWIN_Draw_Label(MBASE(3), F("Steps/mm Z")); + DWIN_Draw_Label(1, GET_TEXT_F(MSG_A_STEPS)); + DWIN_Draw_Label(2, GET_TEXT_F(MSG_B_STEPS)); + DWIN_Draw_Label(3, GET_TEXT_F(MSG_C_STEPS)); #if HAS_HOTEND - DWIN_Draw_Label(MBASE(4), F("Steps/mm E")); + DWIN_Draw_Label(4, GET_TEXT_F(MSG_E_STEPS)); #endif #else - draw_steps_per_mm(MBASE(1)); say_x(103, MBASE(1)); // "Steps-per-mm X" - draw_steps_per_mm(MBASE(2)); say_y(103, MBASE(2)); // "Y" - draw_steps_per_mm(MBASE(3)); say_z(103, MBASE(3)); // "Z" + say_steps_per_mm_en(1); say_x_en(101, 1); // "Steps-per-mm X" + say_steps_per_mm_en(2); say_y_en(101, 2); // "Y" + say_steps_per_mm_en(3); say_z_en(101, 3); // "Z" #if HAS_HOTEND - draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" + say_steps_per_mm_en(4); say_e_en(101, 4); // "E" #endif #endif } Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); #endif } -/* Motion */ +// Motion void HMI_Motion() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3332,7 +3486,7 @@ void HMI_Motion() { DWIN_UpdateLCD(); } -/* Advanced Settings */ +// Advanced Settings void HMI_AdvSet() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3418,7 +3572,7 @@ void HMI_AdvSet() { #if ENABLED(POWER_LOSS_RECOVERY) case ADVSET_CASE_PWRLOSSR: // Power-loss recovery recovery.enable(!recovery.enabled); - Draw_Chkb_Line(ADVSET_CASE_PWRLOSSR + MROWS - index_advset, recovery.enabled); + Draw_Checkbox_Line(ADVSET_CASE_PWRLOSSR + MROWS - index_advset, recovery.enabled); break; #endif default: break; @@ -3429,7 +3583,7 @@ void HMI_AdvSet() { #if HAS_HOME_OFFSET - /* Home Offset */ + // Home Offset void HMI_HomeOff() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3446,21 +3600,21 @@ void HMI_AdvSet() { case 0: // Back checkkey = AdvSet; select_advset.set(ADVSET_CASE_HOMEOFF); - Draw_AdvSet_Menu(); + Draw_AdvancedSettings_Menu(); break; case 1: // Home Offset X checkkey = HomeOffX; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Home_OffX_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Home_OffX_scaled); EncoderRate.enabled = true; break; case 2: // Home Offset Y checkkey = HomeOffY; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Home_OffY_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Home_OffY_scaled); EncoderRate.enabled = true; break; case 3: // Home Offset Z checkkey = HomeOffZ; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Home_OffZ_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Home_OffZ_scaled); EncoderRate.enabled = true; break; default: break; @@ -3471,17 +3625,17 @@ void HMI_AdvSet() { void HMI_HomeOffN(const AxisEnum axis, float &posScaled, const_float_t lo, const_float_t hi) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, posScaled)) { - checkkey = HomeOff; - EncoderRate.enabled = false; - set_home_offset(axis, posScaled / 10); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(select_item.now), posScaled); - return; - } - LIMIT(posScaled, lo, hi); - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 216, MBASE(select_item.now), posScaled); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (Apply_Encoder(encoder_diffState, posScaled)) { + checkkey = HomeOff; + EncoderRate.enabled = false; + set_home_offset(axis, posScaled / 10); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + return; } + LIMIT(posScaled, lo, hi); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); } void HMI_HomeOffX() { HMI_HomeOffN(X_AXIS, HMI_ValueStruct.Home_OffX_scaled, -500, 500); } @@ -3491,7 +3645,7 @@ void HMI_AdvSet() { #endif // HAS_HOME_OFFSET #if HAS_ONESTEP_LEVELING - /*Probe Offset */ + // Probe Offset void HMI_ProbeOff() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3508,16 +3662,16 @@ void HMI_AdvSet() { case 0: // Back checkkey = AdvSet; select_advset.set(ADVSET_CASE_PROBEOFF); - Draw_AdvSet_Menu(); + Draw_AdvancedSettings_Menu(); break; case 1: // Probe Offset X checkkey = ProbeOffX; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Probe_OffX_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Probe_OffX_scaled); EncoderRate.enabled = true; break; case 2: // Probe Offset X checkkey = ProbeOffY; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Probe_OffY_scaled); EncoderRate.enabled = true; break; } @@ -3527,17 +3681,17 @@ void HMI_AdvSet() { void HMI_ProbeOffN(float &posScaled, float &offset_ref) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, posScaled)) { - checkkey = ProbeOff; - EncoderRate.enabled = false; - offset_ref = posScaled / 10; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(select_item.now), posScaled); - return; - } - LIMIT(posScaled, -500, 500); - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 216, MBASE(select_item.now), posScaled); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (Apply_Encoder(encoder_diffState, posScaled)) { + checkkey = ProbeOff; + EncoderRate.enabled = false; + offset_ref = posScaled / 10; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + return; } + LIMIT(posScaled, -500, 500); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); } void HMI_ProbeOffX() { HMI_ProbeOffN(HMI_ValueStruct.Probe_OffX_scaled, probe.offset.x); } @@ -3545,7 +3699,7 @@ void HMI_AdvSet() { #endif // HAS_ONESTEP_LEVELING -/* Info */ +// Info void HMI_Info() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3562,7 +3716,7 @@ void HMI_Info() { DWIN_UpdateLCD(); } -/* Tune */ +// Tune void HMI_Tune() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3574,9 +3728,8 @@ void HMI_Tune() { index_tune = select_tune.now; Scroll_Menu(DWIN_SCROLL_UP); } - else { + else Move_Highlight(1, select_tune.now + MROWS - index_tune); - } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { @@ -3586,9 +3739,8 @@ void HMI_Tune() { Scroll_Menu(DWIN_SCROLL_DOWN); if (index_tune == MROWS) Draw_Back_First(); } - else { + else Move_Highlight(-1, select_tune.now + MROWS - index_tune); - } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { @@ -3601,14 +3753,14 @@ void HMI_Tune() { case TUNE_CASE_SPEED: // Print speed checkkey = PrintSpeed; HMI_ValueStruct.print_speed = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), HMI_ValueStruct.print_speed); + Draw_Edit_Integer3(TUNE_CASE_SPEED + MROWS - index_tune, HMI_ValueStruct.print_speed, true); EncoderRate.enabled = true; break; #if HAS_HOTEND case TUNE_CASE_TEMP: // Nozzle temp checkkey = ETemp; HMI_ValueStruct.E_Temp = thermalManager.degTargetHotend(0); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), HMI_ValueStruct.E_Temp); + Draw_Edit_Integer3(TUNE_CASE_TEMP + MROWS - index_tune, HMI_ValueStruct.E_Temp, true); EncoderRate.enabled = true; break; #endif @@ -3616,7 +3768,7 @@ void HMI_Tune() { case TUNE_CASE_BED: // Bed temp checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = thermalManager.degTargetBed(); - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); + Draw_Edit_Integer3(TUNE_CASE_BED + MROWS - index_tune, HMI_ValueStruct.Bed_Temp, true); EncoderRate.enabled = true; break; #endif @@ -3624,7 +3776,7 @@ void HMI_Tune() { case TUNE_CASE_FAN: // Fan speed checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), HMI_ValueStruct.Fan_speed); + Draw_Edit_Integer3(TUNE_CASE_FAN + MROWS - index_tune, HMI_ValueStruct.Fan_speed, true); EncoderRate.enabled = true; break; #endif @@ -3633,7 +3785,7 @@ void HMI_Tune() { #if EITHER(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 @@ -3650,7 +3802,7 @@ void HMI_Tune() { #if HAS_PREHEAT - /* PLA Preheat */ + // PLA Preheat void HMI_PLAPreheatSetting() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3674,7 +3826,7 @@ void HMI_Tune() { case PREHEAT_CASE_TEMP: // Nozzle temperature checkkey = ETemp; HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[0].hotend_temp); + Draw_Edit_Integer3(PREHEAT_CASE_TEMP, ui.material_preset[0].hotend_temp, true); EncoderRate.enabled = true; break; #endif @@ -3682,7 +3834,7 @@ void HMI_Tune() { case PREHEAT_CASE_BED: // Bed temperature checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[0].bed_temp); + Draw_Edit_Integer3(PREHEAT_CASE_BED, ui.material_preset[0].bed_temp, true); EncoderRate.enabled = true; break; #endif @@ -3690,7 +3842,7 @@ void HMI_Tune() { case PREHEAT_CASE_FAN: // Fan speed checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[0].fan_speed); + Draw_Edit_Integer3(PREHEAT_CASE_FAN, ui.material_preset[0].fan_speed, true); EncoderRate.enabled = true; break; #endif @@ -3706,7 +3858,7 @@ void HMI_Tune() { DWIN_UpdateLCD(); } - /* ABS Preheat */ + // ABS Preheat void HMI_ABSPreheatSetting() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3730,7 +3882,7 @@ void HMI_Tune() { case PREHEAT_CASE_TEMP: // Set nozzle temperature checkkey = ETemp; HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[1].hotend_temp); + Draw_Edit_Integer3(PREHEAT_CASE_TEMP, ui.material_preset[1].hotend_temp, true); EncoderRate.enabled = true; break; #endif @@ -3738,7 +3890,7 @@ void HMI_Tune() { case PREHEAT_CASE_BED: // Set bed temperature checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[1].bed_temp); + Draw_Edit_Integer3(PREHEAT_CASE_BED, ui.material_preset[1].bed_temp, true); EncoderRate.enabled = true; break; #endif @@ -3746,7 +3898,7 @@ void HMI_Tune() { case PREHEAT_CASE_FAN: // Set fan speed checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[1].fan_speed); + Draw_Edit_Integer3(PREHEAT_CASE_FAN, ui.material_preset[1].fan_speed, true); EncoderRate.enabled = true; break; #endif @@ -3764,7 +3916,7 @@ void HMI_Tune() { #endif -/* Max Speed */ +// Max Speed void HMI_MaxSpeed() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3781,7 +3933,7 @@ void HMI_MaxSpeed() { checkkey = MaxSpeed_value; HMI_flag.feedspeed_axis = AxisEnum(select_speed.now - 1); HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_axis]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed, true); EncoderRate.enabled = true; } else { // Back @@ -3793,7 +3945,7 @@ void HMI_MaxSpeed() { DWIN_UpdateLCD(); } -/* Max Acceleration */ +// Max Acceleration void HMI_MaxAcceleration() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3810,7 +3962,7 @@ void HMI_MaxAcceleration() { checkkey = MaxAcceleration_value; HMI_flag.acc_axis = AxisEnum(select_acc.now - 1); HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_axis]; - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration, true); EncoderRate.enabled = true; } else { // Back @@ -3823,7 +3975,7 @@ void HMI_MaxAcceleration() { } #if HAS_CLASSIC_JERK - /* Max Jerk */ + // Max Jerk void HMI_MaxJerk() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3840,7 +3992,7 @@ void HMI_MaxAcceleration() { checkkey = MaxJerk_value; HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); HMI_ValueStruct.Max_Jerk_scaled = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); EncoderRate.enabled = true; } else { // Back @@ -3853,7 +4005,7 @@ void HMI_MaxAcceleration() { } #endif // HAS_CLASSIC_JERK -/* Step */ +// Step void HMI_Step() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3870,7 +4022,7 @@ void HMI_Step() { checkkey = Step_value; HMI_flag.step_axis = AxisEnum(select_step.now - 1); HMI_ValueStruct.Max_Step_scaled = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); EncoderRate.enabled = true; } else { // Back @@ -3934,7 +4086,7 @@ void EachMomentUpdate() { else if (HMI_flag.pause_flag != printingIsPaused()) { // print status update HMI_flag.pause_flag = printingIsPaused(); - if (HMI_flag.pause_flag) ICON_Continue(); else ICON_Pause(); + ICON_ResumeOrPause(); } } @@ -4005,9 +4157,6 @@ void EachMomentUpdate() { Popup_Window_Resume(); update_selection(true); - // TODO: Get the name of the current file from someplace - // - //(void)recovery.interrupted_file_exists(); char * const name = card.longest_filename(); const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); @@ -4137,10 +4286,4 @@ void DWIN_StatusChanged_P(PGM_P const pstr) { DWIN_StatusChanged(str); } -// GUI extension -void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode=false) { - DWIN_Draw_String(true, font8x16, Select_Color, bcolor, x + 4, y, F(mode ? "x" : " ")); - DWIN_Draw_Rectangle(0, color, x + 2, y + 2, x + 17, y + 17); -} - #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index 2808fea99c..69fe0d6bd6 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -163,18 +163,6 @@ typedef struct { extern HMI_value_t HMI_ValueStruct; extern HMI_Flag_t HMI_flag; -// Show ICO -void ICON_Print(bool show); -void ICON_Prepare(bool show); -void ICON_Control(bool show); -void ICON_Leveling(bool show); -void ICON_StartInfo(bool show); - -void ICON_Setting(bool show); -void ICON_Pause(bool show); -void ICON_Continue(bool show); -void ICON_Stop(bool show); - #if HAS_HOTEND || HAS_HEATED_BED // Popup message window void DWIN_Popup_Temperature(const bool toohigh); @@ -261,7 +249,6 @@ void EachMomentUpdate(); void DWIN_HandleScreen(); void DWIN_StatusChanged(const char *text); void DWIN_StatusChanged_P(PGM_P const pstr); -void DWIN_Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool mode /* = false*/); inline void DWIN_StartHoming() { HMI_flag.home_flag = true; } diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h index e5e79df0fd..262276f590 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -31,6 +31,9 @@ #include +//#define USE_STRING_HEADINGS +//#define USE_STRING_TITLES + #define RECEIVED_NO_DATA 0x00 #define RECEIVED_SHAKE_HAND_ACK 0x01 @@ -42,17 +45,12 @@ #define DWIN_WIDTH 272 #define DWIN_HEIGHT 480 -// Character matrix width x height -//#define LCD_WIDTH ((DWIN_WIDTH) / 8) -//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) - // Picture ID -#define DWIN_Boot_Screen 0 #define Language_English 1 #define Language_Chinese 2 // ICON ID -#define ICON 0x09 +#define ICON 7 // Icon set file 7.ICO #define ICON_LOGO 0 #define ICON_Print_0 1 @@ -258,8 +256,7 @@ inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, ui // color: Rectangle color // xStart/yStart: upper left point // xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); // Draw a box // mode: 0=frame, 1=fill, 2=XOR fill diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index cd204eef59..85ddcb4bc4 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -273,8 +273,8 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); + PROGMEM Language_Str MSG_MOVE_E = _UxGT("Move Extruder"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Move E*"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Move %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); @@ -336,13 +336,13 @@ namespace Language_en { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Select *"); PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 8630f48b37..1866426a65 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -126,7 +126,7 @@ void menu_media_filelist() { #endif } else if (card.isMounted()) - ACTION_ITEM_P(PSTR(LCD_STR_FOLDER ".."), lcd_sd_updir); + ACTION_ITEM_P(PSTR(LCD_STR_FOLDER " .."), lcd_sd_updir); if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { if (_menuLineNr == _thisItemNr) { diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index 8c4177b907..ad88225807 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -11,7 +11,7 @@ set -e # use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING -exec_test $1 $2 "Ender 3 v2" "$3" +exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_disable CLASSIC_JERK From ab8e212c2d66d806e0fb8ca32f9bd333949728d7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 18 Aug 2021 00:58:27 +0000 Subject: [PATCH 0554/2168] [cron] Bump distribution date (2021-08-18) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 092d76f71d..4c60042208 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-17" +//#define STRING_DISTRIBUTION_DATE "2021-08-18" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4cc068511e..7856073c30 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 "2021-08-17" + #define STRING_DISTRIBUTION_DATE "2021-08-18" #endif /** From 6464601411346c1da7bf15016b07c0fa9558a28c Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 17 Aug 2021 20:27:21 -0700 Subject: [PATCH 0555/2168] =?UTF-8?q?=E2=8F=AA=EF=B8=8F=20Revert=20ABL=20G?= =?UTF-8?q?29=20feedrate=20(#22574)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Reverts 9130f58 --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 -- Marlin/src/module/motion.cpp | 2 +- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 18e3862128..29009c6e2d 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -363,8 +363,6 @@ G29_TYPE GcodeSuite::G29() { #if ABL_USES_GRID xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE)); - if (!xy_probe_feedrate_mm_s) xy_probe_feedrate_mm_s = PLANNER_XY_FEEDRATE(); - NOLESS(xy_probe_feedrate_mm_s, planner.settings.min_feedrate_mm_s); const float x_min = probe.min_x(), x_max = probe.max_x(), y_min = probe.min_y(), y_max = probe.max_y(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 838605cd54..eb6dc6597c 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -483,7 +483,7 @@ void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS()); - const feedRate_t xy_feedrate = fr_mm_s ?: PLANNER_XY_FEEDRATE(); + const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); #if HAS_Z_AXIS const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); From c05de6cbf8b914c9198091423fe19415e802de6e Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Tue, 17 Aug 2021 20:35:12 -0700 Subject: [PATCH 0556/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Simplify=20PROBI?= =?UTF-8?q?NG=5FSTEPPERS=5FOFF=20(#22581)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 7 +++---- Marlin/src/module/probe.cpp | 19 +++++++------------ 2 files changed, 10 insertions(+), 16 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 0f33b4799d..04848bd0d6 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2932,10 +2932,9 @@ #endif #if !BOTH(HAS_BED_PROBE, HAS_EXTRUDERS) #undef PROBING_ESTEPPERS_OFF -#endif -#if BOTH(PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF) - #undef PROBING_ESTEPPERS_OFF - #warning "PROBING_STEPPERS_OFF includes PROBING_ESTEPPERS_OFF. Disabling PROBING_ESTEPPERS_OFF." +#elif ENABLED(PROBING_STEPPERS_OFF) + // PROBING_STEPPERS_OFF implies PROBING_ESTEPPERS_OFF, make sure it is defined + #define PROBING_ESTEPPERS_OFF #endif #if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index d0f32a32c0..ded5d43893 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -250,21 +250,16 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); TERN_(PROBING_ESTEPPERS_OFF, if (dopause) disable_e_steppers()); - #if ENABLED(PROBING_STEPPERS_OFF) - IF_DISABLED(DELTA, static uint8_t old_trusted); + #if ENABLED(PROBING_STEPPERS_OFF) && DISABLED(DELTA) + static uint8_t old_trusted; if (dopause) { - #if DISABLED(DELTA) - old_trusted = axis_trusted; - DISABLE_AXIS_X(); - DISABLE_AXIS_Y(); - #endif - IF_DISABLED(PROBING_ESTEPPERS_OFF, disable_e_steppers()); + old_trusted = axis_trusted; + DISABLE_AXIS_X(); + DISABLE_AXIS_Y(); } else { - #if DISABLED(DELTA) - if (TEST(old_trusted, X_AXIS)) ENABLE_AXIS_X(); - if (TEST(old_trusted, Y_AXIS)) ENABLE_AXIS_Y(); - #endif + if (TEST(old_trusted, X_AXIS)) ENABLE_AXIS_X(); + if (TEST(old_trusted, Y_AXIS)) ENABLE_AXIS_Y(); axis_trusted = old_trusted; } #endif From f8c67c48101c3456c301461fbb9013107f20f182 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Wed, 18 Aug 2021 05:37:27 +0200 Subject: [PATCH 0557/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Longer3D=20PWM/t?= =?UTF-8?q?imer=20pins=20(#22583)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../MARLIN_F103VE_LONGER/PeripheralPins.c | 30 ++----------------- ini/stm32f1.ini | 2 +- 2 files changed, 3 insertions(+), 29 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c index ba4046d5f9..99226a739d 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c @@ -79,9 +79,6 @@ WEAK const PinMap PinMap_PWM[] = { //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 3, 0)}, // TIM2_CH3 #if defined(STM32F103xE) || defined(STM32F103xG) //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM5_CH3 -#endif -#ifdef STM32F103xG - //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM9_CH1 #endif //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 4, 0)}, // TIM2_CH4 #if defined(STM32F103xE) || defined(STM32F103xG) @@ -89,20 +86,11 @@ WEAK const PinMap PinMap_PWM[] = { {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM5_CH4 #else {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM2_CH4 -#endif -#if defined(STM32F103xG) - //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM9_CH2 #endif {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM3_CH1 -#if defined(STM32F103xG) - //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM13_CH1 -#endif {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 1)}, // TIM1_CH1N //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM3_CH2 //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM8_CH1N -#if defined(STM32F103xG) - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM14_CH1 -#endif {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM1_CH1 //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_PARTIAL, 1, 0)}, // TIM1_CH1 {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM1_CH2 @@ -132,26 +120,14 @@ WEAK const PinMap PinMap_PWM[] = { {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM4_CH1 {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM4_CH2 {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 0)}, // TIM4_CH3 -#if defined(STM32F103xG) - //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM10_CH1 -#endif {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 4, 0)}, // TIM4_CH4 -#if defined(STM32F103xG) - //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM11_CH1 -#endif {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 3, 0)}, // TIM2_CH3 //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 3, 0)}, // TIM2_CH3 {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_2, 4, 0)}, // TIM2_CH4 //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_ENABLE, 4, 0)}, // TIM2_CH4 {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 1)}, // TIM1_CH1N {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 1)}, // TIM1_CH2N -#if defined(STM32F103xG) - //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM12_CH1 -#endif {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 3, 1)}, // TIM1_CH3N -#if defined(STM32F103xG) - //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 2, 0)}, // TIM12_CH2 -#endif {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM3_ENABLE, 1, 0)}, // TIM3_CH1 #if defined(STM32F103xE) || defined(STM32F103xG) //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_NONE, 1, 0)}, // TIM8_CH1 @@ -170,10 +146,6 @@ WEAK const PinMap PinMap_PWM[] = { {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 3, 0)}, // TIM4_CH3 {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 4, 0)}, // TIM4_CH4 -#if defined(STM32F103xG) - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM9_ENABLE, 1, 0)}, // TIM9_CH1 - {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM9_ENABLE, 2, 0)}, // TIM9_CH2 -#endif {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 1)}, // TIM1_CH1N {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 1, 0)}, // TIM1_CH1 {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 2, 1)}, // TIM1_CH2N @@ -182,6 +154,8 @@ WEAK const PinMap PinMap_PWM[] = { {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 0)}, // TIM1_CH3 {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 4, 0)}, // TIM1_CH4 #endif // if 0 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 TFT Backlight + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 Servo connector {NC, NP, 0} }; #endif diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index f1cb078fd8..dc9607ef84 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -338,7 +338,7 @@ board_build.variant = MARLIN_F103VE_LONGER board_build.rename = project.bin board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 -build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 +build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103VE -DSTEP_TIMER=5 -DU20 -DTS_V12 build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED extra_scripts = ${stm32_variant.extra_scripts} monitor_speed = 250000 From 6a8385624f4a5d75bb9beeec5c5420415b7dcea8 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Wed, 18 Aug 2021 05:39:08 +0200 Subject: [PATCH 0558/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STM32=20delay,?= =?UTF-8?q?=20double=20reset=20in=20FSMC=20TFT=20init=20(#22584)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 10 ---------- Marlin/src/lcd/tft_io/tft_io.cpp | 8 ++++---- 2 files changed, 4 insertions(+), 14 deletions(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index e9e712d5a3..dacf533224 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -36,16 +36,6 @@ LCD_CONTROLLER_TypeDef *TFT_FSMC::LCD; void TFT_FSMC::Init() { uint32_t controllerAddress; - - #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RESET_PIN, HIGH); - HAL_Delay(100); - #endif - - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - #endif - FSMC_NORSRAM_TimingTypeDef Timing, ExtTiming; uint32_t NSBank = (uint32_t)pinmap_peripheral(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS); diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index 29c7da235c..ded711b577 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -65,13 +65,13 @@ if (lcd_id != 0xFFFFFFFF) return; #if PIN_EXISTS(TFT_RESET) OUT_WRITE(TFT_RESET_PIN, HIGH); delay(10); - OUT_WRITE(TFT_RESET_PIN, LOW); + WRITE(TFT_RESET_PIN, LOW); delay(10); - OUT_WRITE(TFT_RESET_PIN, HIGH); + WRITE(TFT_RESET_PIN, HIGH); #endif #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); + WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); #endif // io.Init(); @@ -149,7 +149,7 @@ if (lcd_id != 0xFFFFFFFF) return; #endif #if PIN_EXISTS(TFT_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); + WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } From 11e8cd9db938fcc5ee5c5234f148655a8f19c20d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 18 Aug 2021 02:32:37 -0500 Subject: [PATCH 0559/2168] =?UTF-8?q?=F0=9F=A9=B9=20Followup=20to=20Creali?= =?UTF-8?q?tyUI=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Followup to #22586 fixing `Draw_Menu_Line` with `GET_TEXT_F`. - More number drawing convenience functions. - Return on `ENCODER_DIFF_NO` to reduce indent. - Put Main Menu buttons closer to the top. - Move status message up slightly. - Fix some indentation. --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 758 +++++++++++++------------- 1 file changed, 383 insertions(+), 375 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index f008a7a2b4..9e8ceed368 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -95,7 +95,7 @@ #define PAUSE_HEAT #define MENU_CHAR_LIMIT 24 -#define STATUS_Y 360 +#define STATUS_Y 354 // Print speed limit #define MIN_PRINT_SPEED 10 @@ -216,17 +216,6 @@ void HMI_ToggleLanguage() { #endif } -void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - if (value < 0) { - DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F("-")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); - } - else { - DWIN_Draw_String(true, size, Color_White, bColor, x - 6, y, F(" ")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); - } -} - typedef struct { uint16_t x, y, w, h; } icon_info_t; typedef struct { uint16_t x, y[2], w, h; } text_info_t; @@ -241,7 +230,7 @@ void ICON_Button(const bool here, const int iconid, const icon_info_t &ico, cons // Main Menu: "Print" // void ICON_Print() { - constexpr icon_info_t ico = { 17, 130, 110, 100 }; + constexpr icon_info_t ico = { 17, 110, 110, 100 }; constexpr text_info_t txt[2] = { { 1, { 417, 449 }, 30, 14 }, { 1, { 405, 447 }, 27, 15 } @@ -253,7 +242,7 @@ void ICON_Print() { // Main Menu: "Prepare" // void ICON_Prepare() { - constexpr icon_info_t ico = { 145, 130, 110, 100 }; + constexpr icon_info_t ico = { 145, 110, 110, 100 }; constexpr text_info_t txt[2] = { { 33, { 417, 449 }, 51, 14 }, { 31, { 405, 447 }, 27, 15 } @@ -265,7 +254,7 @@ void ICON_Prepare() { // Main Menu: "Control" // void ICON_Control() { - constexpr icon_info_t ico = { 17, 246, 110, 100 }; + constexpr icon_info_t ico = { 17, 226, 110, 100 }; constexpr text_info_t txt[2] = { { 85, { 417, 449 }, 46, 14 }, { 61, { 405, 447 }, 27, 15 } @@ -277,7 +266,7 @@ void ICON_Control() { // Main Menu: "Info" // void ICON_StartInfo() { - constexpr icon_info_t ico = { 145, 246, 110, 100 }; + constexpr icon_info_t ico = { 145, 226, 110, 100 }; constexpr text_info_t txt[2] = { { 133, { 417, 449 }, 23, 14 }, { 91, { 405, 447 }, 27, 15 } @@ -289,7 +278,7 @@ void ICON_StartInfo() { // Main Menu: "Level" // void ICON_Leveling() { - constexpr icon_info_t ico = { 145, 246, 110, 100 }; + constexpr icon_info_t ico = { 145, 226, 110, 100 }; constexpr text_info_t txt[2] = { { 88, { 433, 464 }, 36, 14 }, { 211, { 405, 447 }, 27, 15 } @@ -301,7 +290,7 @@ void ICON_Leveling() { // Printing: "Tune" // void ICON_Tune() { - constexpr icon_info_t ico = { 8, 252, 80, 100 }; + constexpr icon_info_t ico = { 8, 232, 80, 100 }; constexpr text_info_t txt[2] = { { 0, { 433, 464 }, 32, 14 }, { 121, { 405, 447 }, 27, 15 } @@ -313,7 +302,7 @@ void ICON_Tune() { // Printing: "Pause" // void ICON_Pause() { - constexpr icon_info_t ico = { 96, 252, 80, 100 }; + constexpr icon_info_t ico = { 96, 232, 80, 100 }; constexpr text_info_t txt[2] = { { 157, { 417, 449 }, 39, 14 }, { 181, { 405, 447 }, 27, 15 } @@ -325,7 +314,7 @@ void ICON_Pause() { // Printing: "Resume" // void ICON_Resume() { - constexpr icon_info_t ico = { 96, 252, 80, 100 }; + constexpr icon_info_t ico = { 96, 232, 80, 100 }; constexpr text_info_t txt[2] = { { 33, { 433, 464 }, 53, 14 }, { 1, { 405, 447 }, 27, 15 } @@ -333,11 +322,18 @@ void ICON_Resume() { ICON_Button(select_print.now == 1, ICON_Continue_0, ico, txt); } +void ICON_ResumeOrPause() { + if (printingIsPaused() || HMI_flag.pause_flag || HMI_flag.pause_action) + ICON_Resume(); + else + ICON_Pause(); +} + // // Printing: "Stop" // void ICON_Stop() { - constexpr icon_info_t ico = { 184, 252, 80, 100 }; + constexpr icon_info_t ico = { 184, 232, 80, 100 }; constexpr text_info_t txt[2] = { { 196, { 417, 449 }, 29, 14 }, { 151, { 405, 447 }, 27, 12 } @@ -429,10 +425,14 @@ void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } +void Draw_Menu_LineF(const uint8_t line, const uint8_t icon=0, const __FlashStringHelper *label=nullptr, bool more=false) { + Draw_Menu_Line(line, icon, (char*)label, more); +} + void Draw_Checkbox_Line(const uint8_t line, const bool ison) { const uint16_t x = 225, y = EBASE(line) - 2; DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x + 5, y, F(ison ? "X" : " ")); - DWIN_Draw_Rectangle(0, Color_White, x + 2, y + 2, x + 17, y + 17); + DWIN_Draw_Rectangle(0, Color_White, x + 2, y + 2, x + 16, y + 16); } // AreaCopy for a Menu Item @@ -578,6 +578,45 @@ void DWIN_Draw_Label(const uint8_t row, const __FlashStringHelper *title) { DWIN_Draw_Label(row, (char*)title); } +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + if (value < 0) { + DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, F("-")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); + } + else { + DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, F(" ")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); + } +} + +void Draw_Edit_Integer3(const uint8_t row, const uint16_t value, const bool active=false) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, 220, EBASE(row), value); +} + +void Draw_Edit_Integer4(const uint8_t row, const uint16_t value, const bool active=false) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 4, 220 - 1 * 8, EBASE(row), value); +} + +void Draw_Edit_Float3(const uint8_t row, const uint16_t value, const bool active=false) { + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, UNITFDIGITS, 220 - UNITFDIGITS * 8, EBASE(row), value); +} + +void Draw_Edit_Signed_Float2(const uint8_t row, const float value, const bool active=false) { + DWIN_Draw_Signed_Float(font8x16, active ? Select_Color : Color_Bg_Black, 2, UNITFDIGITS, 220 + 8 - UNITFDIGITS * 8, EBASE(row), value); +} + +void Draw_Edit_Signed_Float3(const uint8_t row, const float value, const bool active=false) { + DWIN_Draw_Signed_Float(font8x16, active ? Select_Color : Color_Bg_Black, 3, UNITFDIGITS, 220 - UNITFDIGITS * 8, EBASE(row), value); +} + +void Draw_Stat_Int(const uint16_t xpos, const uint16_t ypos, const uint16_t value) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, xpos, ypos, value); +} + +void Draw_Stat_Float(const uint16_t xpos, const uint16_t ypos, const float value) { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, xpos, ypos, value); +} + // // Prepare Menu // @@ -623,7 +662,6 @@ void Item_Prepare_Home(const uint8_t row) { if (HMI_IsChinese()) { #if HAS_BED_PROBE Item_AreaCopy(174, 164, 223, 177, row); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(row), probe.offset.z * 100); #else Item_AreaCopy(43, 89, 98, 101, row); #endif @@ -633,17 +671,17 @@ void Item_Prepare_Home(const uint8_t row) { #ifdef USE_STRING_TITLES DWIN_Draw_Label(row, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else - Item_AreaCopy(94, 179, 143, 190, row); // "Z-Offset" + Item_AreaCopy( 94, 179, 143, 190, row); // "Z-Offset" #endif - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(row), probe.offset.z * 100); #else #ifdef USE_STRING_TITLES DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); #else - Item_AreaCopy(1, 76, 103, 87, row); // "Set home offsets" + Item_AreaCopy( 1, 76, 103, 87, row); // "Set home offsets" #endif #endif } + Draw_Edit_Signed_Float2(row, BABY_Z_VAR * 100); Draw_Menu_Line(row, ICON_SetHome); } @@ -658,7 +696,7 @@ void Item_Prepare_Home(const uint8_t row) { DWIN_Draw_Label(row, GET_TEXT_F(MSG_PREHEAT_1)); #else Item_AreaCopy(108, 76, 155, 87, row); // "Preheat" - say_pla_en(52, row); // "PLA" + say_pla_en(52, row); // "PLA" #endif } Draw_Menu_Line(row, ICON_PLAPreheat); @@ -672,7 +710,7 @@ void Item_Prepare_Home(const uint8_t row) { DWIN_Draw_Label(row, F("Preheat " PREHEAT_2_LABEL)); #else Item_AreaCopy(108, 76, 155, 87, row); // "Preheat" - say_abs_en(52, row); // "ABS" + say_abs_en(52, row); // "ABS" #endif } Draw_Menu_Line(row, ICON_ABSPreheat); @@ -829,9 +867,9 @@ void Draw_Control_Menu() { #endif } - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back - if (CVISI(CONTROL_CASE_TEMP)) Item_Control_Temp(CSCROL(CONTROL_CASE_TEMP)); // Temperature > - if (CVISI(CONTROL_CASE_MOVE)) Item_Control_Motion(CSCROL(CONTROL_CASE_MOVE)); // Motion > + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + if (CVISI(CONTROL_CASE_TEMP)) Item_Control_Temp(CSCROL(CONTROL_CASE_TEMP)); // Temperature > + if (CVISI(CONTROL_CASE_MOVE)) Item_Control_Motion(CSCROL(CONTROL_CASE_MOVE)); // Motion > if (HMI_IsChinese()) { #if ENABLED(EEPROM_SETTINGS) @@ -886,14 +924,6 @@ void Draw_Control_Menu() { #endif } -void Draw_Edit_Integer3(const uint8_t line, const uint16_t value, const bool active=false) { - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, 220, EBASE(line), value); -} - -void Draw_Edit_Integer4(const uint8_t line, const uint16_t value, const bool active=false) { - DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 4, 210, EBASE(line), value); -} - // // Tune Menu // @@ -974,7 +1004,7 @@ void Draw_Tune_Menu() { #endif #if HAS_ZOFFSET_ITEM Draw_Menu_Line(TUNE_CASE_ZOFF, ICON_Zoffset); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + Draw_Edit_Signed_Float2(TUNE_CASE_ZOFF, BABY_Z_VAR * 100); #endif } @@ -1156,9 +1186,9 @@ void Popup_window_PauseOrStop() { Clear_Main_Window(); Draw_Popup_Bkgd_60(); if (HMI_IsChinese()) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause Print - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop Print - DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); + if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause + else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop + DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); // Print DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); } @@ -1172,43 +1202,40 @@ void Popup_window_PauseOrStop() { } void Draw_Printing_Screen() { + const uint16_t y = 168; if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(30, 1, 42, 14); // "Printing" - DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // "Printing Time" - DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // "Remain" + DWIN_Frame_TitleCopy(30, 1, 42, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 43, y); // "Printing Time" + DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 178, y); // "Remain" } else { - DWIN_Frame_TitleCopy(42, 0, 47, 14); // "Printing" - DWIN_Frame_AreaCopy(1, 1, 43, 97, 59, 41, 188); // "Printing Time" - DWIN_Frame_AreaCopy(1, 100, 43, 152, 56, 176, 188); // "Remain" + DWIN_Frame_TitleCopy(42, 0, 47, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 1, 43, 97, 59, 43, y); // "Printing Time" + DWIN_Frame_AreaCopy(1, 100, 43, 152, 56, 178, y); // "Remain" } } void Draw_Print_ProgressBar() { + constexpr uint16_t y = 93, h = 21; DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); - DWIN_Draw_Rectangle(1, BarFill_Color, 16 + _card_percent * 240 / 100, 93, 256, 113); - DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, _card_percent); - DWIN_Draw_String(false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); + DWIN_Draw_Rectangle(1, BarFill_Color, 16 + _card_percent * 240 / 100, y, 256, y + h - 1); + DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, y + 40, _card_percent); + DWIN_Draw_String(false, font8x16, Percent_Color, Color_Bg_Black, 133, y + 40, F("%")); } void Draw_Print_ProgressElapsed() { + constexpr uint16_t x = 45, y = 192; duration_t elapsed = print_job_timer.duration(); // print timer - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 66, 212, (elapsed.value % 3600) / 60); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, x, y, elapsed.value / 3600); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, x + 8 * 2, y, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, x + 8 * 3, y, (elapsed.value % 3600) / 60); } void Draw_Print_ProgressRemain() { - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 176, 212, _remain_time / 3600); - DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (_remain_time % 3600) / 60); -} - -void ICON_ResumeOrPause() { - if (printingIsPaused() || HMI_flag.pause_flag || HMI_flag.pause_action) - ICON_Resume(); - else - ICON_Pause(); + constexpr uint16_t x = 179, y = 192; + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, x, y, _remain_time / 3600); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, x + 8 * 2, y, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, x + 8 * 3, y, (_remain_time % 3600) / 60); } void Goto_PrintProcess() { @@ -1226,8 +1253,8 @@ void Goto_PrintProcess() { const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); - DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); - DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); + DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 163); + DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 161); Draw_Print_ProgressBar(); Draw_Print_ProgressElapsed(); @@ -1283,47 +1310,44 @@ void HMI_Move_Done(const AxisEnum axis) { void HMI_Move_X() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) { - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); - return HMI_Move_Done(X_AXIS); - } - LIMIT(HMI_ValueStruct.Move_X_scaled, (X_MIN_POS) * MINUNITMULT, (X_MAX_POS) * MINUNITMULT); - current_position.x = HMI_ValueStruct.Move_X_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); - DWIN_UpdateLCD(); - HMI_Plan_Move(homing_feedrate(X_AXIS)); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) { + Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled); + return HMI_Move_Done(X_AXIS); } + LIMIT(HMI_ValueStruct.Move_X_scaled, (X_MIN_POS) * MINUNITMULT, (X_MAX_POS) * MINUNITMULT); + current_position.x = HMI_ValueStruct.Move_X_scaled / MINUNITMULT; + Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled, true); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(X_AXIS)); } void HMI_Move_Y() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) { - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); - return HMI_Move_Done(Y_AXIS); - } - LIMIT(HMI_ValueStruct.Move_Y_scaled, (Y_MIN_POS) * MINUNITMULT, (Y_MAX_POS) * MINUNITMULT); - current_position.y = HMI_ValueStruct.Move_Y_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); - DWIN_UpdateLCD(); - HMI_Plan_Move(homing_feedrate(Y_AXIS)); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) { + Draw_Edit_Float3(2, HMI_ValueStruct.Move_Y_scaled); + return HMI_Move_Done(Y_AXIS); } + LIMIT(HMI_ValueStruct.Move_Y_scaled, (Y_MIN_POS) * MINUNITMULT, (Y_MAX_POS) * MINUNITMULT); + current_position.y = HMI_ValueStruct.Move_Y_scaled / MINUNITMULT; + Draw_Edit_Float3(2, HMI_ValueStruct.Move_Y_scaled, true); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(Y_AXIS)); } void HMI_Move_Z() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) { - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); - return HMI_Move_Done(Z_AXIS); - } - LIMIT(HMI_ValueStruct.Move_Z_scaled, (Z_MIN_POS) * MINUNITMULT, (Z_MAX_POS) * MINUNITMULT); - current_position.z = HMI_ValueStruct.Move_Z_scaled / MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); - DWIN_UpdateLCD(); - HMI_Plan_Move(homing_feedrate(Z_AXIS)); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) { + Draw_Edit_Float3(3, HMI_ValueStruct.Move_Z_scaled); + return HMI_Move_Done(Z_AXIS); } + LIMIT(HMI_ValueStruct.Move_Z_scaled, (Z_MIN_POS) * MINUNITMULT, (Z_MAX_POS) * MINUNITMULT); + current_position.z = HMI_ValueStruct.Move_Z_scaled / MINUNITMULT; + Draw_Edit_Float3(3, HMI_ValueStruct.Move_Z_scaled, true); + DWIN_UpdateLCD(); + HMI_Plan_Move(homing_feedrate(Z_AXIS)); } #if HAS_HOTEND @@ -1331,18 +1355,17 @@ void HMI_Move_Z() { void HMI_Move_E() { static float last_E_scaled = 0; ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scaled)) { - last_E_scaled = HMI_ValueStruct.Move_E_scaled; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), last_E_scaled); - return HMI_Move_Done(E_AXIS); - } - LIMIT(HMI_ValueStruct.Move_E_scaled, last_E_scaled - (EXTRUDE_MAXLENGTH) * MINUNITMULT, last_E_scaled + (EXTRUDE_MAXLENGTH) * MINUNITMULT); - current_position.e = HMI_ValueStruct.Move_E_scaled / MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); - DWIN_UpdateLCD(); - HMI_Plan_Move(MMM_TO_MMS(FEEDRATE_E)); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scaled)) { + last_E_scaled = HMI_ValueStruct.Move_E_scaled; + Draw_Edit_Signed_Float3(4, last_E_scaled); + return HMI_Move_Done(E_AXIS); } + LIMIT(HMI_ValueStruct.Move_E_scaled, last_E_scaled - (EXTRUDE_MAXLENGTH) * MINUNITMULT, last_E_scaled + (EXTRUDE_MAXLENGTH) * MINUNITMULT); + current_position.e = HMI_ValueStruct.Move_E_scaled / MINUNITMULT; + Draw_Edit_Signed_Float3(4, HMI_ValueStruct.Move_E_scaled, true); + DWIN_UpdateLCD(); + HMI_Plan_Move(MMM_TO_MMS(FEEDRATE_E)); } #endif @@ -1353,32 +1376,31 @@ void HMI_Move_Z() { void HMI_Zoffset() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t zoff_line; - switch (HMI_ValueStruct.show_mode) { - case -4: zoff_line = PREPARE_CASE_ZOFF + MROWS - index_prepare; break; - default: zoff_line = TUNE_CASE_ZOFF + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.offset_value)) { - EncoderRate.enabled = false; - #if HAS_BED_PROBE - probe.offset.z = dwin_zoffset; - TERN_(EEPROM_SETTINGS, settings.save()); - #endif - checkkey = HMI_ValueStruct.show_mode == -4 ? Prepare : Tune; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, EBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); - DWIN_UpdateLCD(); - return; - } - LIMIT(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100, (Z_PROBE_OFFSET_RANGE_MAX) * 100); - last_zoffset = dwin_zoffset; - dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); - #endif - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(zoff_line), HMI_ValueStruct.offset_value); - DWIN_UpdateLCD(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + uint8_t zoff_line; + switch (HMI_ValueStruct.show_mode) { + case -4: zoff_line = PREPARE_CASE_ZOFF + MROWS - index_prepare; break; + default: zoff_line = TUNE_CASE_ZOFF + MROWS - index_tune; } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.offset_value)) { + EncoderRate.enabled = false; + #if HAS_BED_PROBE + probe.offset.z = dwin_zoffset; + TERN_(EEPROM_SETTINGS, settings.save()); + #endif + checkkey = HMI_ValueStruct.show_mode == -4 ? Prepare : Tune; + Draw_Edit_Signed_Float2(zoff_line, TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + DWIN_UpdateLCD(); + return; + } + LIMIT(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100, (Z_PROBE_OFFSET_RANGE_MAX) * 100); + last_zoffset = dwin_zoffset; + dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + #endif + Draw_Edit_Signed_Float2(zoff_line, HMI_ValueStruct.offset_value, true); + DWIN_UpdateLCD(); } #endif // HAS_ZOFFSET_ITEM @@ -1387,41 +1409,40 @@ void HMI_Move_Z() { void HMI_ETemp() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t temp_line; - switch (HMI_ValueStruct.show_mode) { - case -1: temp_line = TEMP_CASE_TEMP; break; - case -2: temp_line = PREHEAT_CASE_TEMP; break; - case -3: temp_line = PREHEAT_CASE_TEMP; break; - default: temp_line = TUNE_CASE_TEMP + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.E_Temp)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; - Draw_Edit_Integer3(temp_line, ui.material_preset[0].hotend_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; - Draw_Edit_Integer3(temp_line, ui.material_preset[1].hotend_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -1) // Temperature - checkkey = TemperatureID; - else - checkkey = Tune; - Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp); - thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); + if (encoder_diffState == ENCODER_DIFF_NO) return; + uint8_t temp_line; + switch (HMI_ValueStruct.show_mode) { + case -1: temp_line = TEMP_CASE_TEMP; break; + case -2: temp_line = PREHEAT_CASE_TEMP; break; + case -3: temp_line = PREHEAT_CASE_TEMP; break; + default: temp_line = TUNE_CASE_TEMP + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.E_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; + Draw_Edit_Integer3(temp_line, ui.material_preset[0].hotend_temp); return; } - // E_Temp limit - LIMIT(HMI_ValueStruct.E_Temp, HEATER_0_MINTEMP, thermalManager.hotend_max_target(0)); - // E_Temp value - Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp, true); + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; + Draw_Edit_Integer3(temp_line, ui.material_preset[1].hotend_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -1) // Temperature + checkkey = TemperatureID; + else + checkkey = Tune; + Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp); + thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); + return; } + // E_Temp limit + LIMIT(HMI_ValueStruct.E_Temp, HEATER_0_MINTEMP, thermalManager.hotend_max_target(0)); + // E_Temp value + Draw_Edit_Integer3(temp_line, HMI_ValueStruct.E_Temp, true); } #endif // HAS_HOTEND @@ -1430,41 +1451,40 @@ void HMI_Move_Z() { void HMI_BedTemp() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t bed_line; - switch (HMI_ValueStruct.show_mode) { - case -1: bed_line = TEMP_CASE_BED; break; - case -2: bed_line = PREHEAT_CASE_BED; break; - case -3: bed_line = PREHEAT_CASE_BED; break; - default: bed_line = TUNE_CASE_BED + MROWS - index_tune; - } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Bed_Temp)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; - Draw_Edit_Integer3(bed_line, ui.material_preset[0].bed_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; - Draw_Edit_Integer3(bed_line, ui.material_preset[1].bed_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -1) - checkkey = TemperatureID; - else - checkkey = Tune; - Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp); - thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); + if (encoder_diffState == ENCODER_DIFF_NO) return; + uint8_t bed_line; + switch (HMI_ValueStruct.show_mode) { + case -1: bed_line = TEMP_CASE_BED; break; + case -2: bed_line = PREHEAT_CASE_BED; break; + case -3: bed_line = PREHEAT_CASE_BED; break; + default: bed_line = TUNE_CASE_BED + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Bed_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; + Draw_Edit_Integer3(bed_line, ui.material_preset[0].bed_temp); return; } - // Bed_Temp limit - LIMIT(HMI_ValueStruct.Bed_Temp, BED_MINTEMP, BED_MAX_TARGET); - // Bed_Temp value - Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp, true); + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; + Draw_Edit_Integer3(bed_line, ui.material_preset[1].bed_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -1) + checkkey = TemperatureID; + else + checkkey = Tune; + Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp); + thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); + return; } + // Bed_Temp limit + LIMIT(HMI_ValueStruct.Bed_Temp, BED_MINTEMP, BED_MAX_TARGET); + // Bed_Temp value + Draw_Edit_Integer3(bed_line, HMI_ValueStruct.Bed_Temp, true); } #endif // HAS_HEATED_BED @@ -1473,147 +1493,141 @@ void HMI_Move_Z() { void HMI_FanSpeed() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - uint8_t fan_line; - switch (HMI_ValueStruct.show_mode) { - case -1: fan_line = TEMP_CASE_FAN; break; - case -2: fan_line = PREHEAT_CASE_FAN; break; - case -3: fan_line = PREHEAT_CASE_FAN; break; - default: fan_line = TUNE_CASE_FAN + MROWS - index_tune; - } + if (encoder_diffState == ENCODER_DIFF_NO) return; + uint8_t fan_line; + switch (HMI_ValueStruct.show_mode) { + case -1: fan_line = TEMP_CASE_FAN; break; + case -2: fan_line = PREHEAT_CASE_FAN; break; + case -3: fan_line = PREHEAT_CASE_FAN; break; + default: fan_line = TUNE_CASE_FAN + MROWS - index_tune; + } - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Fan_speed)) { - EncoderRate.enabled = false; - if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; - Draw_Edit_Integer3(fan_line, ui.material_preset[0].fan_speed); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; - Draw_Edit_Integer3(fan_line, ui.material_preset[1].fan_speed); - return; - } - else if (HMI_ValueStruct.show_mode == -1) - checkkey = TemperatureID; - else - checkkey = Tune; - Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed); - thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Fan_speed)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; + Draw_Edit_Integer3(fan_line, ui.material_preset[0].fan_speed); return; } - // Fan_speed limit - LIMIT(HMI_ValueStruct.Fan_speed, 0, 255); - // Fan_speed value - Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed, true); + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; + Draw_Edit_Integer3(fan_line, ui.material_preset[1].fan_speed); + return; + } + else if (HMI_ValueStruct.show_mode == -1) + checkkey = TemperatureID; + else + checkkey = Tune; + Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed); + thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); + return; } + // Fan_speed limit + LIMIT(HMI_ValueStruct.Fan_speed, 0, 255); + // Fan_speed value + Draw_Edit_Integer3(fan_line, HMI_ValueStruct.Fan_speed, true); } #endif // HAS_PREHEAT && HAS_FAN void HMI_PrintSpeed() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { - checkkey = Tune; - EncoderRate.enabled = false; - feedrate_percentage = HMI_ValueStruct.print_speed; - Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed); - return; - } - // print_speed limit - LIMIT(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED, MAX_PRINT_SPEED); - // print_speed value - Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed, true); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { + checkkey = Tune; + EncoderRate.enabled = false; + feedrate_percentage = HMI_ValueStruct.print_speed; + Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed); + return; } + // print_speed limit + LIMIT(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED, MAX_PRINT_SPEED); + // print_speed value + Draw_Edit_Integer3(select_tune.now + MROWS - index_tune, HMI_ValueStruct.print_speed, true); } #define LAST_AXIS TERN(HAS_HOTEND, E_AXIS, Z_AXIS) void HMI_MaxFeedspeedXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { - checkkey = MaxSpeed; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) - planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); - Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed); - return; - } - // MaxFeedspeed limit + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { + checkkey = MaxSpeed; + EncoderRate.enabled = false; if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) - NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); - if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; - // MaxFeedspeed value - Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed, true); + planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); + Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed); + return; } + // MaxFeedspeed limit + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); + if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; + // MaxFeedspeed value + Draw_Edit_Integer4(select_speed.now, HMI_ValueStruct.Max_Feedspeed, true); } void HMI_MaxAccelerationXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { - checkkey = MaxAcceleration; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) - planner.set_max_acceleration(HMI_flag.acc_axis, HMI_ValueStruct.Max_Acceleration); - Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration); - return; - } - // MaxAcceleration limit + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { + checkkey = MaxAcceleration; + EncoderRate.enabled = false; if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) - NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); - if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; - // MaxAcceleration value - Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration, true); + planner.set_max_acceleration(HMI_flag.acc_axis, HMI_ValueStruct.Max_Acceleration); + Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration); + return; } + // MaxAcceleration limit + if (WITHIN(HMI_flag.acc_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); + if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; + // MaxAcceleration value + Draw_Edit_Integer4(select_acc.now, HMI_ValueStruct.Max_Acceleration, true); } #if HAS_CLASSIC_JERK void HMI_MaxJerkXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk_scaled)) { - checkkey = MaxJerk; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) - planner.set_max_jerk(HMI_flag.jerk_axis, HMI_ValueStruct.Max_Jerk_scaled / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); - return; - } - // MaxJerk limit + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk_scaled)) { + checkkey = MaxJerk; + EncoderRate.enabled = false; if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) - NOMORE(HMI_ValueStruct.Max_Jerk_scaled, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Jerk_scaled, (MIN_MAXJERK) * MINUNITMULT); - // MaxJerk value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + planner.set_max_jerk(HMI_flag.jerk_axis, HMI_ValueStruct.Max_Jerk_scaled / 10); + Draw_Edit_Float3(select_jerk.now, HMI_ValueStruct.Max_Jerk_scaled); + return; } + // MaxJerk limit + if (WITHIN(HMI_flag.jerk_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Jerk_scaled, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk_scaled, (MIN_MAXJERK) * MINUNITMULT); + // MaxJerk value + Draw_Edit_Float3(select_jerk.now, HMI_ValueStruct.Max_Jerk_scaled, true); } #endif // HAS_CLASSIC_JERK void HMI_StepXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step_scaled)) { - checkkey = Step; - EncoderRate.enabled = false; - if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) - planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step_scaled / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); - return; - } - // Step limit + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step_scaled)) { + checkkey = Step; + EncoderRate.enabled = false; if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) - NOMORE(HMI_ValueStruct.Max_Step_scaled, 999.9 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Step_scaled, MIN_STEP); - // Step value - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step_scaled / 10; + Draw_Edit_Float3(select_step.now, HMI_ValueStruct.Max_Step_scaled); + return; } + // Step limit + if (WITHIN(HMI_flag.step_axis, X_AXIS, LAST_AXIS)) + NOMORE(HMI_ValueStruct.Max_Step_scaled, 999.9 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Step_scaled, MIN_STEP); + // Step value + Draw_Edit_Float3(select_step.now, HMI_ValueStruct.Max_Step_scaled, true); } // Draw X, Y, Z and blink if in an un-homed or un-trusted state @@ -1708,34 +1722,34 @@ void update_variable() { #if HAS_HOTEND if (_new_hotend_temp) - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 384, _hotendtemp); + Draw_Stat_Int(28, 384, _hotendtemp); if (_new_hotend_target) - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, _hotendtarget); + Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 384, _hotendtarget); static int16_t _flow = planner.flow_percentage[0]; if (_flow != planner.flow_percentage[0]) { _flow = planner.flow_percentage[0]; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, _flow); + Draw_Stat_Int(116 + 2 * STAT_CHR_W, 417, _flow); } #endif #if HAS_HEATED_BED if (_new_bed_temp) - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 417, _bedtemp); + Draw_Stat_Int(28, 417, _bedtemp); if (_new_bed_target) - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, _bedtarget); + Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 417, _bedtarget); #endif static int16_t _feedrate = 100; if (_feedrate != feedrate_percentage) { _feedrate = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, _feedrate); + Draw_Stat_Int(116 + 2 * STAT_CHR_W, 384, _feedrate); } #if HAS_FAN if (_new_fanspeed) { _fanspeed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, _fanspeed); + Draw_Stat_Int(195 + 2 * STAT_CHR_W, 384, _fanspeed); } #endif @@ -1743,11 +1757,11 @@ void update_variable() { if (BABY_Z_VAR != _offset) { _offset = BABY_Z_VAR; if (BABY_Z_VAR < 0) { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -_offset * 100); + Draw_Stat_Float(207, 417, -_offset * 100); DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); } else { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, _offset * 100); + Draw_Stat_Float(207, 417, _offset * 100); DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); } } @@ -1948,29 +1962,29 @@ void Draw_Status_Area(const bool with_update) { #if HAS_HOTEND DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 384, thermalManager.wholeDegHotend(0)); + Draw_Stat_Int(28, 384, thermalManager.wholeDegHotend(0)); DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.degTargetHotend(0)); + Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 384, thermalManager.degTargetHotend(0)); DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); + Draw_Stat_Int(116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); #endif #if HAS_HEATED_BED DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 28, 417, thermalManager.wholeDegBed()); + Draw_Stat_Int(28, 417, thermalManager.wholeDegBed()); DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); + Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); #endif DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); + Draw_Stat_Int(116 + 2 * STAT_CHR_W, 384, feedrate_percentage); DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); #if HAS_FAN DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); - DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); + Draw_Stat_Int(195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); #endif #if HAS_ZOFFSET_ITEM @@ -1978,11 +1992,11 @@ void Draw_Status_Area(const bool with_update) { #endif if (BABY_Z_VAR < 0) { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, -BABY_Z_VAR * 100); + Draw_Stat_Float(207, 417, -BABY_Z_VAR * 100); DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F("-")); } else { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 2, 2, 207, 417, BABY_Z_VAR * 100); + Draw_Stat_Float(207, 417, BABY_Z_VAR * 100); DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, 205, 419, F(" ")); } @@ -2366,9 +2380,7 @@ void Draw_Move_Menu() { Item_AreaCopy(58, 118, 106, 132, 1); Item_AreaCopy(109, 118, 157, 132, 2); Item_AreaCopy(160, 118, 209, 132, 3); - #if HAS_HOTEND - Item_AreaCopy(212, 118, 253, 131, 4); - #endif + TERN_(HAS_HOTEND, Item_AreaCopy(212, 118, 253, 131, 4)); } else { #ifdef USE_STRING_HEADINGS @@ -2381,16 +2393,12 @@ void Draw_Move_Menu() { DWIN_Draw_Label(1, GET_TEXT_F(MSG_MOVE_X)); DWIN_Draw_Label(2, GET_TEXT_F(MSG_MOVE_Y)); DWIN_Draw_Label(3, GET_TEXT_F(MSG_MOVE_Z)); - #if HAS_HOTEND - DWIN_Draw_Label(4, GET_TEXT_F(MSG_MOVE_E)); - #endif + TERN_(HAS_HOTEND, DWIN_Draw_Label(4, GET_TEXT_F(MSG_MOVE_E))); #else say_move_en(1); say_x_en(38, 1); // "Move X" say_move_en(2); say_y_en(38, 2); // "Move Y" say_move_en(3); say_z_en(38, 3); // "Move Z" - #if HAS_HOTEND - say_move_en(4); Item_AreaCopy(99, 194, 151, 204, 4, 38); // "Move Extruder" - #endif + TERN_(HAS_HOTEND, (say_move_en(4), Item_AreaCopy(99, 194, 151, 204, 4, 38))); // "Move Extruder" #endif } @@ -2519,13 +2527,13 @@ void Item_HomeOffs_X(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_Line(row, ICON_HomeOffX, GET_TEXT_F(MSG_HOME_OFFSET_X)); + Draw_Menu_LineF(row, ICON_HomeOffX, GET_TEXT_F(MSG_HOME_OFFSET_X)); #else say_home_offs_en(row); say_x_en(75, row); // "Home Offset X" #endif } Draw_Menu_Line(row, ICON_HomeOff); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffX_scaled); + Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffX_scaled); } void Item_HomeOffs_Y(const uint8_t row) { @@ -2534,13 +2542,13 @@ void Item_HomeOffs_Y(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_Line(row, ICON_HomeOffY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); + Draw_Menu_LineF(row, ICON_HomeOffY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); #else say_home_offs_en(row); say_y_en(75, row); // "Home Offset X" #endif } Draw_Menu_Line(row, ICON_HomeOff); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffY_scaled); + Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffY_scaled); } void Item_HomeOffs_Z(const uint8_t row) { @@ -2549,13 +2557,13 @@ void Item_HomeOffs_Z(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_Line(row, ICON_HomeOffZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); + Draw_Menu_LineF(row, ICON_HomeOffZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); #else say_home_offs_en(row); say_z_en(75, row); // "Home Offset Z" #endif } Draw_Menu_Line(row, ICON_HomeOff); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(row), HMI_ValueStruct.Home_OffZ_scaled); + Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffZ_scaled); } void Draw_HomeOff_Menu() { @@ -2592,16 +2600,16 @@ void Draw_HomeOff_Menu() { DWIN_Frame_TitleCopy(124, 431, 91, 12); // "Probe Offsets" #endif #ifdef USE_STRING_TITLES - Draw_Menu_Line(1, ICON_ProbeOffX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset - Draw_Menu_Line(2, ICON_ProbeOffY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset + Draw_Menu_LineF(1, ICON_ProbeOffX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset + Draw_Menu_LineF(2, ICON_ProbeOffY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset #else say_probe_offs_en(1); say_x_en(75, 1); // "Probe Offset X" say_probe_offs_en(2); say_y_en(75, 2); // "Probe Offset Y" #endif } - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Probe_OffX_scaled); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + Draw_Edit_Signed_Float3(1, HMI_ValueStruct.Probe_OffX_scaled); + Draw_Edit_Signed_Float3(2, HMI_ValueStruct.Probe_OffY_scaled); if (select_item.now) Draw_Menu_Cursor(select_item.now); } @@ -2685,12 +2693,12 @@ void HMI_Prepare() { select_axis.reset(); Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), current_position.x * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), current_position.y * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), current_position.z * MINUNITMULT); + Draw_Edit_Float3(1, current_position.x * MINUNITMULT); + Draw_Edit_Float3(2, current_position.y * MINUNITMULT); + Draw_Edit_Float3(3, current_position.z * MINUNITMULT); #if HAS_HOTEND HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); + Draw_Edit_Signed_Float3(4, HMI_ValueStruct.Move_E_scaled); #endif break; case PREPARE_CASE_DISA: // Disable steppers @@ -2708,7 +2716,7 @@ void HMI_Prepare() { checkkey = Homeoffset; HMI_ValueStruct.show_mode = -4; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); + Draw_Edit_Signed_Float2(PREPARE_CASE_ZOFF + MROWS - index_prepare, HMI_ValueStruct.offset_value, true); EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 @@ -2946,10 +2954,10 @@ void HMI_AxisMove() { HMI_flag.ETempTooLow_flag = false; HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(4), 0); + Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled); + Draw_Edit_Float3(2, HMI_ValueStruct.Move_Y_scaled); + Draw_Edit_Float3(3, HMI_ValueStruct.Move_Z_scaled); + Draw_Edit_Signed_Float3(4, 0); DWIN_UpdateLCD(); } return; @@ -2974,19 +2982,19 @@ void HMI_AxisMove() { case 1: // X axis move checkkey = Move_X; HMI_ValueStruct.Move_X_scaled = current_position.x * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Move_X_scaled); + Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled, true); EncoderRate.enabled = true; break; case 2: // Y axis move checkkey = Move_Y; HMI_ValueStruct.Move_Y_scaled = current_position.y * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Move_Y_scaled); + Draw_Edit_Float3(2, HMI_ValueStruct.Move_Y_scaled, true); EncoderRate.enabled = true; break; case 3: // Z axis move checkkey = Move_Z; HMI_ValueStruct.Move_Z_scaled = current_position.z * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Move_Z_scaled); + Draw_Edit_Float3(3, HMI_ValueStruct.Move_Z_scaled, true); EncoderRate.enabled = true; break; #if HAS_HOTEND @@ -3002,7 +3010,7 @@ void HMI_AxisMove() { #endif checkkey = Extruder; HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(4), HMI_ValueStruct.Move_E_scaled); + Draw_Edit_Signed_Float3(4, HMI_ValueStruct.Move_E_scaled, true); EncoderRate.enabled = true; break; #endif @@ -3083,7 +3091,7 @@ void HMI_Temperature() { #ifdef USE_STRING_HEADINGS Draw_Title(PREHEAT_1_LABEL " Settings"); // TODO: GET_TEXT_F #else - DWIN_Frame_TitleCopy(57, 16, 84, 14); // "PLA Settings" + DWIN_Frame_TitleCopy(56, 15, 85, 14); // "Temperature" TODO: "PLA Settings" #endif #ifdef USE_STRING_TITLES DWIN_Draw_Label(PREHEAT_CASE_TEMP, F("Nozzle Temp")); @@ -3162,7 +3170,7 @@ void HMI_Temperature() { #ifdef USE_STRING_HEADINGS Draw_Title("ABS Settings"); // TODO: GET_TEXT_F #else - DWIN_Frame_TitleCopy(57, 16, 84, 14); // "ABS Settings" + DWIN_Frame_TitleCopy(56, 15, 85, 14); // "Temperature" TODO: "ABS Settings" #endif #ifdef USE_STRING_TITLES DWIN_Draw_Label(PREHEAT_CASE_TEMP, F("Nozzle Temp")); @@ -3278,17 +3286,17 @@ void Draw_Max_Accel_Menu() { Clear_Main_Window(); if (HMI_IsChinese()) { - DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Acceleration" + DWIN_Frame_TitleCopy(1, 16, 28, 13); // "Acceleration" Item_AreaCopy(173, 133, 200, 147, 1); Item_AreaCopy( 28, 149, 69, 161, 1, 30, 1); - Item_AreaCopy(229, 133, 236, 147, 1, 74); // Max acceleration X + Item_AreaCopy(229, 133, 236, 147, 1, 74); // Max acceleration X Item_AreaCopy(173, 133, 200, 147, 2); Item_AreaCopy( 28, 149, 69, 161, 2, 30, 1); - Item_AreaCopy( 1, 150, 7, 160, 2, 74, 2); // Max acceleration Y + Item_AreaCopy( 1, 150, 7, 160, 2, 74, 2); // Max acceleration Y Item_AreaCopy(173, 133, 200, 147, 3); Item_AreaCopy( 28, 149, 69, 161, 3, 30, 1); - Item_AreaCopy( 9, 150, 16, 160, 3, 74, 2); // Max acceleration Z + Item_AreaCopy( 9, 150, 16, 160, 3, 74, 2); // Max acceleration Z #if HAS_HOTEND Item_AreaCopy(173, 133, 200, 147, 4); Item_AreaCopy( 28, 149, 69, 161, 4, 30, 1); @@ -3379,11 +3387,11 @@ void Draw_Max_Accel_Menu() { Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); + Draw_Edit_Float3(1, planner.max_jerk[X_AXIS] * MINUNITMULT); + Draw_Edit_Float3(2, planner.max_jerk[Y_AXIS] * MINUNITMULT); + Draw_Edit_Float3(3, planner.max_jerk[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + Draw_Edit_Float3(4, planner.max_jerk[E_AXIS] * MINUNITMULT); #endif } #endif @@ -3430,11 +3438,11 @@ void Draw_Steps_Menu() { Draw_Back_First(); LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); + Draw_Edit_Float3(1, planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); + Draw_Edit_Float3(2, planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); + Draw_Edit_Float3(3, planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, UNITFDIGITS, 210, EBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + Draw_Edit_Float3(4, planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); #endif } @@ -3604,17 +3612,17 @@ void HMI_AdvSet() { break; case 1: // Home Offset X checkkey = HomeOffX; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Home_OffX_scaled); + Draw_Edit_Signed_Float3(1, HMI_ValueStruct.Home_OffX_scaled, true); EncoderRate.enabled = true; break; case 2: // Home Offset Y checkkey = HomeOffY; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Home_OffY_scaled); + Draw_Edit_Signed_Float3(2, HMI_ValueStruct.Home_OffY_scaled, true); EncoderRate.enabled = true; break; case 3: // Home Offset Z checkkey = HomeOffZ; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(3), HMI_ValueStruct.Home_OffZ_scaled); + Draw_Edit_Signed_Float3(3, HMI_ValueStruct.Home_OffZ_scaled, true); EncoderRate.enabled = true; break; default: break; @@ -3631,11 +3639,11 @@ void HMI_AdvSet() { checkkey = HomeOff; EncoderRate.enabled = false; set_home_offset(axis, posScaled / 10); - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + Draw_Edit_Signed_Float3(select_item.now, posScaled); return; } LIMIT(posScaled, lo, hi); - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + Draw_Edit_Signed_Float3(select_item.now, posScaled, true); } void HMI_HomeOffX() { HMI_HomeOffN(X_AXIS, HMI_ValueStruct.Home_OffX_scaled, -500, 500); } @@ -3666,12 +3674,12 @@ void HMI_AdvSet() { break; case 1: // Probe Offset X checkkey = ProbeOffX; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(1), HMI_ValueStruct.Probe_OffX_scaled); + Draw_Edit_Signed_Float3(1, HMI_ValueStruct.Probe_OffX_scaled, true); EncoderRate.enabled = true; break; case 2: // Probe Offset X checkkey = ProbeOffY; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(2), HMI_ValueStruct.Probe_OffY_scaled); + Draw_Edit_Signed_Float3(2, HMI_ValueStruct.Probe_OffY_scaled, true); EncoderRate.enabled = true; break; } @@ -3687,11 +3695,11 @@ void HMI_AdvSet() { checkkey = ProbeOff; EncoderRate.enabled = false; offset_ref = posScaled / 10; - DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + Draw_Edit_Signed_Float3(select_item.now, posScaled); return; } LIMIT(posScaled, -500, 500); - DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, UNITFDIGITS, 220, EBASE(select_item.now), posScaled); + Draw_Edit_Signed_Float3(select_item.now, posScaled, true); } void HMI_ProbeOffX() { HMI_ProbeOffN(HMI_ValueStruct.Probe_OffX_scaled, probe.offset.x); } @@ -3785,7 +3793,7 @@ void HMI_Tune() { #if EITHER(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, EBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); + Draw_Edit_Signed_Float2(TUNE_CASE_ZOFF + MROWS - index_tune, HMI_ValueStruct.offset_value, true); EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 @@ -3992,7 +4000,7 @@ void HMI_MaxAcceleration() { checkkey = MaxJerk_value; HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); HMI_ValueStruct.Max_Jerk_scaled = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk_scaled); + Draw_Edit_Float3(select_jerk.now, HMI_ValueStruct.Max_Jerk_scaled, true); EncoderRate.enabled = true; } else { // Back @@ -4022,7 +4030,7 @@ void HMI_Step() { checkkey = Step_value; HMI_flag.step_axis = AxisEnum(select_step.now - 1); HMI_ValueStruct.Max_Step_scaled = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, UNITFDIGITS, 210, EBASE(select_step.now), HMI_ValueStruct.Max_Step_scaled); + Draw_Edit_Float3(select_step.now, HMI_ValueStruct.Max_Step_scaled, true); EncoderRate.enabled = true; } else { // Back @@ -4274,9 +4282,9 @@ void DWIN_CompletedLeveling() { } void DWIN_StatusChanged(const char *text) { - DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 24); const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(text) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 2, F(text)); + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 3, F(text)); DWIN_UpdateLCD(); } From e2297d82f2721466daf180e8c4034b040ac4cc69 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 18 Aug 2021 14:54:56 -0500 Subject: [PATCH 0560/2168] =?UTF-8?q?=F0=9F=93=8C=20Disregard=20TMCStepper?= =?UTF-8?q?=200.7.2?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index e5b0fb3f66..b94c3fb9bc 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -17,7 +17,7 @@ HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/L POSTMORTEM_DEBUGGING = src_filter=+ + build_flags=-funwind-tables MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip -HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.1 +HAS_TRINAMIC_CONFIG = TMCStepper@0.7.1 src_filter=+ + + + + HAS_STEALTHCHOP = src_filter=+ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip From 368a12a8ac687af85ea726bc54dabb5076ca55e2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 19 Aug 2021 00:51:33 +0000 Subject: [PATCH 0561/2168] [cron] Bump distribution date (2021-08-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4c60042208..c33d333660 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-18" +//#define STRING_DISTRIBUTION_DATE "2021-08-19" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7856073c30..8fbdc5ed1d 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 "2021-08-18" + #define STRING_DISTRIBUTION_DATE "2021-08-19" #endif /** From 033e65ec854e68fb189fa1c23d0277daf2417301 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 19 Aug 2021 17:38:05 -0500 Subject: [PATCH 0562/2168] =?UTF-8?q?=F0=9F=90=9B=20Show=20bed=20size=20as?= =?UTF-8?q?=20'work:'=20in=20M115?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22598 --- Marlin/src/gcode/host/M115.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 3b88c6905e..e4f412406f 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -166,9 +166,11 @@ void GcodeSuite::M115() { // Machine Geometry #if ENABLED(M115_GEOMETRY_REPORT) - const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + const xyz_pos_t bmin = { 0, 0, 0 }, + bmax = { X_BED_SIZE , Y_BED_SIZE, Z_MAX_POS }, + dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; - xyz_pos_t cmin = dmin, cmax = dmax; + xyz_pos_t cmin = bmin, cmax = bmax; apply_motion_limits(cmin); apply_motion_limits(cmax); const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(), From 737d2dd56438ba02f07e3693e9138fc9816d143b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 19 Aug 2021 19:16:46 -0500 Subject: [PATCH 0563/2168] Followup to CrealityUI cleanup Followup to #22586 --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 9e8ceed368..1bbdc326be 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -2434,7 +2434,7 @@ void Item_Adv_HomeOffsets(const uint8_t row) { #ifdef USE_STRING_TITLES DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); #else - say_probe_offs_en(0, row); + say_probe_offs_en(row); #endif } Draw_Menu_Line(row, ICON_ProbeOff); From 9db5805c8fbd417d1fa388533ee13eceff13eda9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 20 Aug 2021 00:56:15 +0000 Subject: [PATCH 0564/2168] [cron] Bump distribution date (2021-08-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c33d333660..db5a6e1524 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-19" +//#define STRING_DISTRIBUTION_DATE "2021-08-20" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8fbdc5ed1d..dcad270c26 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 "2021-08-19" + #define STRING_DISTRIBUTION_DATE "2021-08-20" #endif /** From 193205a40dd6b756bd69cab6fcb1af63ddd6d452 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 19 Aug 2021 21:11:10 -0500 Subject: [PATCH 0565/2168] Followup to CrealityUI cleanup Followup to #22586 --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 24 ++++++++++++++---------- 1 file changed, 14 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 1bbdc326be..5ddc231817 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -856,9 +856,8 @@ void Draw_Control_Menu() { #define CLINE(L) MBASE(CSCROL(L)) #define CVISI(L) VISI(CONTROL_CASE_TOTAL, L, CSCROL(L)) - // "Control" Title if (HMI_IsChinese()) - DWIN_Frame_TitleCopy(103, 1, 28, 14); + DWIN_Frame_TitleCopy(103, 1, 28, 14); // "Control" else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); @@ -2028,8 +2027,8 @@ void Draw_Info_Menu() { DWIN_Frame_TitleCopy(30, 17, 28, 13); // "Info" DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); // "Size" - DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" - DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" + DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" + DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" } else { #ifdef USE_STRING_HEADINGS @@ -2432,7 +2431,7 @@ void Item_Adv_HomeOffsets(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - DWIN_Draw_Label(row, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); + DWIN_Draw_Label(row, GET_TEXT_F(MSG_ZPROBE_OFFSETS)); #else say_probe_offs_en(row); #endif @@ -2502,11 +2501,16 @@ void Draw_AdvancedSettings_Menu() { #define ASCROL(L) (scroll + (L)) #define AVISI(L) VISI(ADVSET_CASE_TOTAL, L, ASCROL(L)) - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_ADVANCED_SETTINGS)); - #else - DWIN_Frame_TitleCopy(93, 401, 126, 15); // "Advanced Settings" - #endif + if (false && HMI_IsChinese()) { + // TODO: Chinese "Advanced Settings" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_ADVANCED_SETTINGS)); + #else + DWIN_Frame_TitleCopy(93, 401, 126, 15); // "Advanced Settings" + #endif + } if (AVISI(0)) Draw_Back_First(select_advset.now == 0); if (AVISI(ADVSET_CASE_HOMEOFF)) Item_Adv_HomeOffsets(ASCROL(ADVSET_CASE_HOMEOFF)); // Set Home Offsets > From 9046254a14b92b6bdf1696b1ed839b71615a0772 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 20 Aug 2021 15:40:17 -0500 Subject: [PATCH 0566/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20menu=20titles?= =?UTF-8?q?,=20add=20more=20IJK=20(#22605)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #19112 --- Marlin/src/lcd/language/language_an.h | 14 +- Marlin/src/lcd/language/language_bg.h | 9 +- Marlin/src/lcd/language/language_ca.h | 9 +- Marlin/src/lcd/language/language_cz.h | 62 ++- Marlin/src/lcd/language/language_da.h | 9 +- Marlin/src/lcd/language/language_de.h | 32 +- Marlin/src/lcd/language/language_el.h | 12 + Marlin/src/lcd/language/language_el_gr.h | 12 + Marlin/src/lcd/language/language_en.h | 63 +-- Marlin/src/lcd/language/language_es.h | 44 +- Marlin/src/lcd/language/language_eu.h | 15 +- Marlin/src/lcd/language/language_fr.h | 14 +- Marlin/src/lcd/language/language_gl.h | 52 ++- Marlin/src/lcd/language/language_hu.h | 14 +- Marlin/src/lcd/language/language_it.h | 31 +- Marlin/src/lcd/language/language_jp_kana.h | 21 +- Marlin/src/lcd/language/language_pl.h | 31 +- Marlin/src/lcd/language/language_pt.h | 3 + Marlin/src/lcd/language/language_pt_br.h | 6 + Marlin/src/lcd/language/language_ro.h | 30 +- Marlin/src/lcd/language/language_ru.h | 6 +- Marlin/src/lcd/language/language_sk.h | 32 +- Marlin/src/lcd/language/language_sv.h | 24 +- Marlin/src/lcd/language/language_tr.h | 24 +- Marlin/src/lcd/language/language_uk.h | 12 +- Marlin/src/lcd/language/language_vi.h | 57 ++- Marlin/src/lcd/language/language_zh_CN.h | 358 ++++++++------- Marlin/src/lcd/language/language_zh_TW.h | 508 +++++++++++---------- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- 29 files changed, 882 insertions(+), 624 deletions(-) diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 787096994f..e5fc965ed1 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -106,10 +106,13 @@ namespace Language_an { PROGMEM Language_Str MSG_ACC = _UxGT("Aceleracion"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viache min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Acel. max") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Acel. max ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Acel. max ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Acel. max ") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Acel. max ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Acel. max *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acel. retrac."); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acel. Viaje"); @@ -117,6 +120,9 @@ namespace Language_an { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" trangos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" trangos/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" trangos/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" trangos/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" trangos/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" trangos/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E trangos/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* trangos/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 0d4291b835..37d896f60d 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -99,9 +99,12 @@ namespace Language_bg { PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-откат"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-travel"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Стъпки/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("стъпки/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("стъпки/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("стъпки/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" стъпки/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" стъпки/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" стъпки/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" стъпки/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" стъпки/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" стъпки/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E стъпки/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* стъпки/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index f97a783d01..19ba9acab7 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -104,9 +104,12 @@ namespace Language_ca { PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Accel. retracc"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Accel. Viatge"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passos/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("passos/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("passos/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("passos/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passos/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passos/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passos/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passos/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passos/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passos/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("Epassos/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*passos/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index fa6a8e21a3..a6e97ea40c 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -268,33 +268,45 @@ namespace Language_cz { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Vybrat *"); PROGMEM Language_Str MSG_ACC = _UxGT("Zrychl"); PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Odchylka spoje"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Rychlost"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Rychlost"); + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Rychlost"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Akcelerace"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Akcel"); + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Akcel"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-přejezd"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Kroků/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("kroků/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("kroků/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("kroků/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Ekroků/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*kroků/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" kroků/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroků/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroků/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); PROGMEM Language_Str MSG_MOTION = _UxGT("Pohyb"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); @@ -475,9 +487,12 @@ namespace Language_cz { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Nap. zdroj"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Buzení motorů"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Motor %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC uložit EEPROM"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CHYBA SPOJENÍ"); @@ -590,6 +605,9 @@ namespace Language_cz { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekce"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Vyhlazení"); } diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 95c2573ae1..ef312f1334 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -176,9 +176,12 @@ namespace Language_da { PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Strømfors."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driv Styrke"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driv %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driv %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driv %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index f06370078a..0fa895638b 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -271,15 +271,21 @@ namespace Language_de { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Auswählen *"); PROGMEM Language_Str MSG_ACC = _UxGT("Beschleunigung"); PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("V E Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Geschwindigkeit"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("V max ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("V max ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("V max ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("V max ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("V max ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("V max ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("V max ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("V max *"); PROGMEM Language_Str MSG_VMIN = _UxGT("V min "); @@ -289,6 +295,9 @@ namespace Language_de { PROGMEM Language_Str MSG_AMAX_A = _UxGT("A max ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("A max ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("A max ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("A max ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("A max ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("A max ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("A max ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("A max *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A Einzug"); @@ -299,6 +308,9 @@ namespace Language_de { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_E_STEPS = LCD_STR_E _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); @@ -499,9 +511,12 @@ namespace Language_de { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Netzteil"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Motorleistung"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Treiber %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Treiber %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Treiber %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC Verbindungsfehler"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Werte speichern"); @@ -618,6 +633,9 @@ namespace Language_de { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index b69b4695d3..824b90a232 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -108,10 +108,16 @@ namespace Language_el { PROGMEM Language_Str MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; PROGMEM Language_Str MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Vαντίδραση E"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("V Μέγιστο") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("V Μέγιστο") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("V Μέγιστο") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("V Μέγιστο") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("V Μέγιστο") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("V Μέγιστο") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("V Μέγιστο") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("V Μέγιστο *"); PROGMEM Language_Str MSG_VMIN = _UxGT("V Ελάχιστο"); @@ -120,6 +126,9 @@ namespace Language_el { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Aμεγ *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); @@ -128,6 +137,9 @@ namespace Language_el { PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index 208d7c2363..e5c169446b 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -110,10 +110,16 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; PROGMEM Language_Str MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Vαντίδραση E"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vμεγ ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vμεγ ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vμεγ ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vμεγ ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vμεγ ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vμεγ ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vμεγ ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vμεγ *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vελαχ"); @@ -122,6 +128,9 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Aμεγ *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); @@ -130,6 +139,9 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); + PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 85ddcb4bc4..ede6904627 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -139,8 +139,8 @@ namespace Language_en { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bed Leveling"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Level Bed"); PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bed Tramming"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Adjust bed until the probe triggers."); + PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Corners within tolerance. Bed trammed."); PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Next Corner"); @@ -318,6 +318,7 @@ namespace Language_en { 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_CYCLE = _UxGT("PID Cycle"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); @@ -345,29 +346,29 @@ namespace Language_en { PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Min Velocity"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Travel Vel"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleration"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Travel"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Retract Accel"); + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Travel Accel"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("XY Freq Limit"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min FR Factor"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); @@ -423,7 +424,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Start Host Print"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop Print"); PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Printing Object"); @@ -588,12 +589,12 @@ namespace Language_en { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 8fdf0bd47e..46e4e262e7 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -105,7 +105,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover ejes"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Recorrido asistido"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Recorrido Cama"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); @@ -269,23 +269,32 @@ namespace Language_es { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleccionar *"); PROGMEM Language_Str MSG_ACC = _UxGT("Aceleración"); PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidad"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleración"); PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Acel. max") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Acel. max") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Acel. max") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Acel. max") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Acel. max *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acel. retrac."); @@ -294,6 +303,9 @@ namespace Language_es { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pasos/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pasos/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -473,9 +485,12 @@ namespace Language_es { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("F. Aliment."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERROR CONEX. TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); @@ -575,6 +590,9 @@ namespace Language_es { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 530742d6d3..30cc4931d8 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -167,6 +167,9 @@ namespace Language_eu { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-astindua"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-astindua"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-astindua"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-astindua"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-astindua"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-astindua"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-astindua"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VBidaia min"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); @@ -175,6 +178,9 @@ namespace Language_eu { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pausoak/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pausoak/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pausoak/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pausoak/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pausoak/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pausoak/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pausoak/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pausoak/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Tenperatura"); @@ -294,9 +300,12 @@ namespace Language_eu { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Tenp. Maximoa"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Elikadura-iturria"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driver-aren potentzia"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Idatzi DAC EEPROM"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("HARIZPIA ALDATU"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 6032937e0f..e0f13356ba 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -110,7 +110,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Assistant Molettes"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Niveau des coins"); PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Coin suivant"); @@ -521,12 +521,12 @@ namespace Language_fr { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alim."); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver " AXIS4_STR " %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver " AXIS5_STR " %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver " AXIS6_STR " %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 8defd2b01f..f657d5e34d 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -271,25 +271,34 @@ namespace Language_gl { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Escolla *"); PROGMEM Language_Str MSG_ACC = _UxGT("Acel"); PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("V-viaxe min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Aceleración"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrac."); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-viaxe"); PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frecuencia max"); @@ -298,6 +307,9 @@ namespace Language_gl { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pasos/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pasos/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -490,9 +502,12 @@ namespace Language_gl { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte Alimentación"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); @@ -593,6 +608,9 @@ namespace Language_gl { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 6fb41f90ff..444c29560b 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -132,7 +132,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek mozgatása"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy szintezés"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ágy szintezése"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Elektromos segéd"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Sarok szint"); PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Ágy emelése a szonda váltásig"); PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Jó pontok: "); @@ -582,12 +582,12 @@ namespace Language_hu { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Meghajtó %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Meghajtó %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 32bc7ff7c7..4ae85e7bbe 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -346,14 +346,14 @@ namespace Language_it { PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accelerazione"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Spostamento"); PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); @@ -577,12 +577,12 @@ namespace Language_it { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alimentatore"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") AXIS4_STR _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") AXIS5_STR _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") AXIS6_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); @@ -701,6 +701,9 @@ namespace Language_it { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 61740e3b40..c0fe2451b0 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -119,14 +119,20 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_A; // "Va-jerk" PROGMEM Language_Str MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_B; // "Vb-jerk" PROGMEM Language_Str MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_C; // "Vc-jerk" + PROGMEM Language_Str MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_I; // "Va-jerk" + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_J; // "Vb-jerk" + PROGMEM Language_Str MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_K; // "Vc-jerk" PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("ステップ/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("ステップ/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("ステップ/mm"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("エクストルーダー ヤクド"); // "Ve-jerk" PROGMEM Language_Str MSG_VMAX_A = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax A" - PROGMEM Language_Str MSG_VMAX_B = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax B" - PROGMEM Language_Str MSG_VMAX_C = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax C" - PROGMEM Language_Str MSG_VMAX_E = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax E" + PROGMEM Language_Str MSG_VMAX_B = _UxGT("サイダイオクリソクド ") LCD_STR_B; // "Vmax B" + PROGMEM Language_Str MSG_VMAX_C = _UxGT("サイダイオクリソクド ") LCD_STR_C; // "Vmax C" + PROGMEM Language_Str MSG_VMAX_I = _UxGT("サイダイオクリソクド ") LCD_STR_I; // "Vmax I" + PROGMEM Language_Str MSG_VMAX_J = _UxGT("サイダイオクリソクド ") LCD_STR_J; // "Vmax J" + PROGMEM Language_Str MSG_VMAX_K = _UxGT("サイダイオクリソクド ") LCD_STR_K; // "Vmax K" + PROGMEM Language_Str MSG_VMAX_E = _UxGT("サイダイオクリソクド ") LCD_STR_E; // "Vmax E" PROGMEM Language_Str MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" PROGMEM Language_Str MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" @@ -214,9 +220,12 @@ namespace Language_jp_kana { 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 DACシュツリョク %"); // "X Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y DACシュツリョク %"); // "Y Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z DACシュツリョク %"); // "Z Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E DACシュツリョク %"); // "E Driver %" PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("EEPROMヘホゾン"); // "Store memory" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("イチジテイシ"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index e467178f6a..b55777717d 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -327,22 +327,16 @@ namespace Language_pl { PROGMEM Language_Str MSG_VA_JERK = _UxGT("Zryw V") LCD_STR_A; PROGMEM Language_Str MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Zryw V") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Zryw V") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Zryw V") LCD_STR_K; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Zryw Ve"); //PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Prędkość (V)"); - //PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - //PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - //PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - //PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - //PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - //PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vskok min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); - //PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - //PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - //PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - //PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - //PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-wycofanie"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-przesuń."); PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); @@ -351,6 +345,9 @@ namespace Language_pl { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" kroki/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroki/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroki/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -561,9 +558,12 @@ namespace Language_pl { //PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Zasilacz"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Siła %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Siła %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Siła %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC BŁĄD POŁĄCZENIA"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); @@ -678,9 +678,6 @@ namespace Language_pl { //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("Korekcja"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 4bec74558e..630f38e2d9 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -105,6 +105,9 @@ namespace Language_pt { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passo/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passo/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passo/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passo/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passo/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passo/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passo/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passo/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 12904aa7ea..4b52ee97b8 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -244,6 +244,9 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_VA_JERK = _UxGT("arrancada V") LCD_STR_A; PROGMEM Language_Str MSG_VB_JERK = _UxGT("arrancada V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("arrancada V") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("arrancada V") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("arrancada V") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("arrancada V") LCD_STR_K; PROGMEM Language_Str MSG_VE_JERK = _UxGT("arrancada VE"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desv. Junção"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); @@ -255,6 +258,9 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_A_STEPS = _UxGT("Passo ") LCD_STR_A _UxGT("/mm"); PROGMEM Language_Str MSG_B_STEPS = _UxGT("Passo ") LCD_STR_B _UxGT("/mm"); PROGMEM Language_Str MSG_C_STEPS = _UxGT("Passo ") LCD_STR_C _UxGT("/mm"); + PROGMEM Language_Str MSG_I_STEPS = _UxGT("Passo ") LCD_STR_I _UxGT("/mm"); + PROGMEM Language_Str MSG_J_STEPS = _UxGT("Passo ") LCD_STR_J _UxGT("/mm"); + PROGMEM Language_Str MSG_K_STEPS = _UxGT("Passo ") LCD_STR_K _UxGT("/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 3d21e1a58d..aedc8c4173 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -273,12 +273,18 @@ namespace Language_ro { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-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("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -287,6 +293,9 @@ namespace Language_ro { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); @@ -294,9 +303,12 @@ namespace Language_ro { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("steps/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("steps/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("steps/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" steps/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" steps/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" steps/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" steps/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" steps/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" steps/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("Esteps/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*steps/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); @@ -497,9 +509,12 @@ namespace Language_ro { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temperatura Maxima"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); @@ -606,6 +621,9 @@ namespace Language_ro { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corectare"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 6ccfe5f47a..e7eab72f6c 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -714,9 +714,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; PROGMEM Language_Str MSG_INFO_PSU = _UxGT("БП"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Сила привода"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 717fa49b33..079bcf55c8 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -132,7 +132,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunúť osy"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Asist. vyrovnanie"); + PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Vyrovnať rohy"); PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); @@ -319,12 +319,18 @@ namespace Language_sk { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-skok"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-skok"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-skok"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-skok"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-skok"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-skok"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-skok"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Rýchlosť"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -333,6 +339,9 @@ namespace Language_sk { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); @@ -340,9 +349,12 @@ namespace Language_sk { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Kroky/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("krokov/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("krokov/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("krokov/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" krokov/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" krokov/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" krokov/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" krokov/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" krokov/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" krokov/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("Ekrokov/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*krokov/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); @@ -553,9 +565,12 @@ namespace Language_sk { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Nap. zdroj"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Budenie motorov"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Motor %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("CHYBA KOMUNIKÁ. TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Uložiť do EEPROM"); @@ -673,6 +688,9 @@ namespace Language_sk { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekcia"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Vyhladzovanie"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index baa0f64506..cb33db5dfd 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -303,12 +303,18 @@ namespace Language_sv { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Ryck"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Ryck"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Ryck"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Ryck"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Ryck"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Hastighet"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -317,6 +323,9 @@ namespace Language_sv { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); @@ -327,6 +336,9 @@ namespace Language_sv { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steg/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steg/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steg/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steg/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E Steg/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steg/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); @@ -533,9 +545,12 @@ namespace Language_sv { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); @@ -653,6 +668,9 @@ namespace Language_sv { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrigering"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glättning"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index bf218f136f..66c7c1c1a2 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -266,12 +266,18 @@ namespace Language_tr { 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"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Sarsım"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Sarsım"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Sarsım"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Sarsım"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Sarsım"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Jonksiyon Sapması"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Hız Vektörü"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("HızVektör.max ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("HızVektör.max ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("HızVektör.max ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("HızVektör.max ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("HızVektör.max ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("HızVektör.max ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("HızVektör.max ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("HızVektör.max *"); PROGMEM Language_Str MSG_VMIN = _UxGT("HızVektör.min"); @@ -280,6 +286,9 @@ namespace Language_tr { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max. ivme ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max. ivme ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max. ivme ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max. ivme ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max. ivme ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max. ivme ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max. ivme ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max. ivme *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ivme-geri çekme"); @@ -288,6 +297,9 @@ namespace Language_tr { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" adım/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" adım/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" adım/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" adım/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" adım/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" adım/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E adım/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* adım/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Sıcaklık"); @@ -464,9 +476,12 @@ namespace Language_tr { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Sıc."); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Güç Kaynağı"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Sürücü Gücü"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Sürücü %"); - 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_A = LCD_STR_A _UxGT(" Sürücü %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Sürücü %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Sürücü %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Sürücü %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Sürücü %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 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"); @@ -571,6 +586,9 @@ namespace Language_tr { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Düzeltme"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Yumuşatma"); } diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 2e4a1b068c..e0ee2e3929 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -719,12 +719,12 @@ namespace Language_uk { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Блок жив-ня"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Сила мотору"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Драйвер X, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Драйвер Y, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Драйвер Z, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") AXIS4_STR _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") AXIS5_STR _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") AXIS6_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Драйвер ") LCD_STR_A _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Драйвер ") LCD_STR_B _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Драйвер ") LCD_STR_C _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") LCD_STR_I _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") LCD_STR_J _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") LCD_STR_K _UxGT(", %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 013a915921..9ee93a56bb 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -52,9 +52,9 @@ namespace Language_vi { PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu gỡ lỗi"); // Debug Menu PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Kiểm tra tiến độ"); // Progress bar test PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Về nhà tự động"); // Auto home - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Về nhà X"); // home x - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Về nhà Y"); // home y - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Về nhà Z"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Về nhà X"); // home X + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Về nhà Y"); // home Y + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Về nhà Z"); // home Z PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Chỉnh canh Z tự động"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Đang về nhà XYZ"); // Homing XYZ PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Nhấn để bắt đầu"); // Click to Begin @@ -160,7 +160,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Khe nhớ"); // Memory Slot PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Tải lưới bàn"); // Load Bed Mesh PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Lưu lưới bàn"); // Save Bed Mesh - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("%i lưới được nạp"); // Mesh %i loaded + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("%i lưới được nạp"); // Mesh %i loaded PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("%i lưới đã lưu"); PROGMEM Language_Str MSG_NO_STORAGE = _UxGT("Không lưu trữ"); // No Storage PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Điều sai: Lưu UBL"); // Err: UBL Save @@ -200,7 +200,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Di chuyển Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Di chuyển Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Máy đùn"); // Extruder - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Máy đùn *"); // Extruder + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Máy đùn *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Đầu nóng quá lạnh"); // Hotend too cold PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm @@ -209,12 +209,12 @@ namespace Language_vi { PROGMEM Language_Str MSG_SPEED = _UxGT("Tốc độ"); // Speed PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Bàn"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Đầu phun ~"); // Nozzle + PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Đầu phun ~"); PROGMEM Language_Str MSG_BED = _UxGT("Bàn"); // bed PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Tốc độ quạt"); // fan speed - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Tốc độ quạt ~"); // fan speed + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Tốc độ quạt ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Tốc độ quạt phụ"); // Extra fan speed - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Tốc độ quạt phụ ~"); // Extra fan speed + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Tốc độ quạt phụ ~"); PROGMEM Language_Str MSG_FLOW = _UxGT("Lưu Lượng"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Lưu Lượng ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Điều khiển"); // Control @@ -231,28 +231,40 @@ namespace Language_vi { PROGMEM Language_Str MSG_VA_JERK = _UxGT("Giật-V") LCD_STR_A; PROGMEM Language_Str MSG_VB_JERK = _UxGT("Giật-V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Giật-V") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("Giật-V") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Giật-V") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("Giật-V") LCD_STR_K; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Giật-Ve"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Độ Lệch Chỗ Giao"); // Junction Dev PROGMEM Language_Str MSG_VELOCITY = _UxGT("Vận tốc"); // velocity PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vđa") LCD_STR_A; // Vmax - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vđa") LCD_STR_B; // Vmax - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vđa") LCD_STR_C; // Vmax - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vđa") LCD_STR_E; // Vmax - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vđa *"); // Vmax + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vđa") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vđa") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vđa") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vđa") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vđa") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vđa") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vđa *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vthiểu"); // Vmin PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vchuyển thiểu"); // VTrav min PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Sự tăng tốc"); // Acceleration PROGMEM Language_Str MSG_AMAX_A = _UxGT("Tăng tốc ca") LCD_STR_A; // Amax - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Tăng tốc ca") LCD_STR_B; // Amax - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Tăng tốc ca") LCD_STR_C; // Amax - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Tăng tốc ca") LCD_STR_E; // Amax - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); // Amax + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Tăng tốc ca") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Tăng tốc ca") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Tăng tốc ca") LCD_STR_I; // Amax + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Tăng tốc ca") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Tăng tốc ca") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Tăng tốc ca") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("TT-Rút"); // A-retract PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("TT-Chuyển"); // A-travel PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Bước/mm"); // Steps - PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bước") LCD_STR_A _UxGT("/mm"); // Asteps/mm + PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bước") LCD_STR_A _UxGT("/mm"); // Steps/mm PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bước") LCD_STR_B _UxGT("/mm"); PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bước") LCD_STR_C _UxGT("/mm"); + PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bước") LCD_STR_I _UxGT("/mm"); // Steps/mm + PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bước") LCD_STR_J _UxGT("/mm"); + PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bước") LCD_STR_K _UxGT("/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("BướcE/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bước */mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature @@ -388,10 +400,13 @@ namespace Language_vi { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Nhiệt độ tối đa"); // Max temp PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Bộ nguồn"); // PSU PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Sức mạnh ổ đĩa"); // Drive Strength - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X % trình điều khiển"); // X Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y % trình điều khiển"); // Y Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z % trình điều khiển"); // Z Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); // E Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" % trình điều khiển"); // X Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" % trình điều khiển"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" % trình điều khiển"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" % trình điều khiển"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" % trình điều khiển"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" % trình điều khiển"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Ghi DAC EEPROM"); // DAC EEPROM Write PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("In tạm dừng"); // PRINT PAUSED PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("Nạp dây nhựa"); diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 31d2623604..d3883ac88d 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -33,52 +33,52 @@ namespace Language_zh_CN { constexpr uint8_t CHARSIZE = 3; PROGMEM Language_Str LANGUAGE = _UxGT("Simplified Chinese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); //" ready." + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); // " ready." PROGMEM Language_Str MSG_MARLIN = _UxGT("马林"); PROGMEM Language_Str MSG_YES = _UxGT("是"); PROGMEM Language_Str MSG_NO = _UxGT("否"); PROGMEM Language_Str MSG_BACK = _UxGT("返回"); // ”Back“ PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("放弃中..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); //"Card inserted" - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); //"Card removed" + PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); // "Card inserted" + PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); // "Card removed" PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("等待存储器"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("存储器读取错误"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB设备已弹出"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB启动错误"); PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("挡块"); //"Endstops" // Max length 8 characters + PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块"); - PROGMEM Language_Str MSG_MAIN = _UxGT("主菜单"); //"Main" + PROGMEM Language_Str MSG_MAIN = _UxGT("主菜单"); // "Main" PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("高级设置"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("配置"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自动开始"); //"Autostart" - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("关闭步进电机"); //"Disable steppers" + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自动开始"); // "Autostart" + PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("关闭步进电机"); // "Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("调试菜单"); // "Debug Menu" PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("进度条测试"); // "Progress Bar Test" - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("自动回原点"); //"Auto home" - 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_HOME = _UxGT("自动回原点"); // "Auto home" + 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对齐"); - 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" - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成热床调平"); //"Leveling Done!" + 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" + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成热床调平"); // "Leveling Done!" PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("设置原点偏移"); //"Set home offsets" - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已启用"); //"Offsets applied" - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("设置原点"); //"Set origin" + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("设置原点偏移"); // "Set home offsets" + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已启用"); // "Offsets applied" + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("设置原点"); // "Set origin" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("预热 ") PREHEAT_1_LABEL; //"Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("预热 ") PREHEAT_1_LABEL " ~"; //"Preheat PREHEAT_2_LABEL" + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("预热 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_2_LABEL" + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("预热 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_2_LABEL" PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴 ~"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 热床"); //MSG_PREHEAT_1 " Bed" PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 设置"); //MSG_PREHEAT_1 " conf" - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("预热 $"); //"Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("预热 $ ~"); //"Preheat PREHEAT_2_LABEL" + PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("预热 $"); // "Preheat PREHEAT_2_LABEL" + PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("预热 $ ~"); // "Preheat PREHEAT_2_LABEL" PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("预热 $ 喷嘴"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("预热 $ 喷嘴 ~"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("预热 $ 全部"); //MSG_PREHEAT_1 " All" @@ -86,20 +86,20 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("预热 $ 设置"); //MSG_PREHEAT_1 " conf" #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("预热自定义"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降温"); //"Cooldown" + PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降温"); // "Cooldown" PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("切割频率"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("激光控制"); PROGMEM Language_Str MSG_LASER_POWER = _UxGT("激光电源"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主轴控制"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("主轴电源"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("主轴反转"); - 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" - PROGMEM Language_Str MSG_RETRACT = _UxGT("回抽"); //"Retract" - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移动轴"); //"Move axis" - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("调平热床"); //"Bed leveling" - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("调平热床"); //"Level bed" + 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" + PROGMEM Language_Str MSG_RETRACT = _UxGT("回抽"); // "Retract" + PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移动轴"); // "Move axis" + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("调平热床"); // "Bed leveling" + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("调平热床"); // "Level bed" PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("调平边角"); // "Bed Tramming" PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下个边角"); // "Next corner" PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("网格编辑器"); @@ -220,27 +220,27 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVING = _UxGT("移动..."); // "Moving...") PROGMEM Language_Str MSG_FREE_XY = _UxGT("释放 XY"); // "Free XY") - PROGMEM Language_Str MSG_MOVE_X = _UxGT("移动X"); //"Move X" - 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("挤出机 *"); //"Extruder" + PROGMEM Language_Str MSG_MOVE_X = _UxGT("移动X"); // "Move X" + 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("挤出机 *"); // "Extruder" PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); - PROGMEM Language_Str MSG_MOVE_N_MM = _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" - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); //"Move 10mm" - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); //"Move 100mm" - PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" - PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); //"Bed Z" - PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); //"Nozzle" 噴嘴 - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("喷嘴 ~"); //"Nozzle" 噴嘴 + PROGMEM Language_Str MSG_MOVE_N_MM = _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" + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); // "Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); // "Move 100mm" + PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); // "Speed" + PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); // "Bed Z" + PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); // "Nozzle" 噴嘴 + PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("喷嘴 ~"); // "Nozzle" 噴嘴 PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("喷嘴已停靠"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("喷嘴待命中"); - PROGMEM Language_Str MSG_BED = _UxGT("热床"); //"Bed" + PROGMEM Language_Str MSG_BED = _UxGT("热床"); // "Bed" PROGMEM Language_Str MSG_CHAMBER = _UxGT("机箱壳"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("风扇速率"); //"Fan speed" - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("风扇速率 ~"); //"Fan speed" + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("风扇速率"); // "Fan speed" + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("风扇速率 ~"); // "Fan speed" PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("存储的风扇 ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("额外风扇速率"); // "Extra fan speed" PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("额外风扇速率 ~"); // "Extra fan speed" @@ -249,70 +249,82 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("自动模式"); PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("工作速度"); PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("空闲周期"); - PROGMEM Language_Str MSG_FLOW = _UxGT("挤出速率"); //"Flow" - PROGMEM Language_Str MSG_FLOW_N = _UxGT("挤出速率 ~"); //"Flow" - PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); //"Control" - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); //" " LCD_STR_THERMOMETER " Min" - 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_FLOW = _UxGT("挤出速率"); // "Flow" + PROGMEM Language_Str MSG_FLOW_N = _UxGT("挤出速率 ~"); // "Flow" + PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); // "Control" + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" + 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_PID_AUTOTUNE = _UxGT("自动PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("自动PID *"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID调整完成"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败. 坏的挤出机"); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败. 温度太高"); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("自动调失败! 超时"); - PROGMEM Language_Str MSG_SELECT = _UxGT("选择"); //"Select" + PROGMEM Language_Str MSG_SELECT = _UxGT("选择"); // "Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("选择 *"); - PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); //"Accel" acceleration + PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); // "Accel" acceleration PROGMEM Language_Str MSG_JERK = _UxGT("抖动速率"); // "Jerk" - PROGMEM Language_Str MSG_VA_JERK = _UxGT("轴抖动速率") LCD_STR_A; //"Va-jerk" - 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_VA_JERK = _UxGT("轴抖动速率") LCD_STR_A; // "Va-jerk" + 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_VI_JERK = _UxGT("轴抖动速率") LCD_STR_I; // "Vi-jerk" + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("轴抖动速率") LCD_STR_J; // "Vj-jerk" + PROGMEM Language_Str MSG_VK_JERK = _UxGT("轴抖动速率") LCD_STR_K; // "Vk-jerk" + PROGMEM Language_Str MSG_VE_JERK = _UxGT("挤出机抖动速率"); // "Ve-jerk" PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("接点差"); 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; //"Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMAX_C = _UxGT("最大进料速率") LCD_STR_C; //"Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMAX_E = _UxGT("最大进料速率") LCD_STR_E; //"Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大进料速率 *"); //"Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMIN = _UxGT("最小进料速率"); //"Vmin" min_feedrate_mm_s - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移动速率"); //"VTrav min" min_travel_feedrate_mm_s, (target) speed of the move + 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; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("最大进料速率") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("最大进料速率") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("最大进料速率") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("最大进料速率") LCD_STR_K; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("最大进料速率") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大进料速率 *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("最小进料速率"); // "Vmin" min_feedrate_mm_s + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移动速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move PROGMEM Language_Str MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大打印加速度") LCD_STR_A; //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_B = _UxGT("最大打印加速度") LCD_STR_B; //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_C = _UxGT("最大打印加速度") LCD_STR_C; //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_E = _UxGT("最大打印加速度") LCD_STR_E; //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大打印加速度 *"); //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("收进加速度"); //"A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非打印移动加速度"); //"A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves + PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大打印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + PROGMEM Language_Str MSG_AMAX_B = _UxGT("最大打印加速度") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("最大打印加速度") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("最大打印加速度") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("最大打印加速度") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("最大打印加速度") LCD_STR_K; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("最大打印加速度") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大打印加速度 *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("收进加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非打印移动加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("频率最大"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("进给速度"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("轴步数/mm"); //"Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("步数/mm"); //"Asteps/mm" - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("步数/mm"); //"Bsteps/mm" - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("步数/mm"); //"Csteps/mm" - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E 步数/mm"); //"Esteps/mm" + PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("轴步数/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" 步数/mm"); // "Asteps/mm" + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" 步数/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" 步数/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" 步数/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" 步数/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" 步数/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E 步数/mm"); // "Esteps/mm" PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* 步数/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("温度"); //"Temperature" - PROGMEM Language_Str MSG_MOTION = _UxGT("运动"); //"Motion" - PROGMEM Language_Str MSG_FILAMENT = _UxGT("料丝"); //"Filament" menu_advanced_filament - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm") SUPERSCRIPT_THREE; //"E in mm3" volumetric_enabled + PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("温度"); // "Temperature" + PROGMEM Language_Str MSG_MOTION = _UxGT("运动"); // "Motion" + PROGMEM Language_Str MSG_FILAMENT = _UxGT("料丝"); // "Filament" menu_advanced_filament + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E 限制 在 mm") SUPERSCRIPT_THREE; PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E 限制 *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("丝料直径"); //"Fil. Dia." + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("丝料直径"); // "Fil. Dia." 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_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_INIT_EEPROM = _UxGT("初始化设置"); // "Initialize EEPROM" PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC 错误"); PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index 错误"); @@ -321,9 +333,9 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("存储器更新"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("复位打印机"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("刷新"); - 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_INFO_SCREEN = _UxGT("信息屏"); // "Info screen" + PROGMEM Language_Str MSG_PREPARE = _UxGT("准备"); // "Prepare" + PROGMEM Language_Str MSG_TUNE = _UxGT("调整"); // "Tune" PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("电源监控"); PROGMEM Language_Str MSG_CURRENT = _UxGT("电流"); PROGMEM Language_Str MSG_VOLTAGE = _UxGT("电压"); @@ -340,33 +352,33 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("返回"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("继续"); PROGMEM Language_Str MSG_PAUSING = _UxGT("暂停中..."); - 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_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("打印物体"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("取消物体"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("取消物体 ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("中断恢复"); - 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_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("打印中..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("已取消打印"); //"Print aborted" + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("已取消打印"); // "Print aborted" PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("打印已完成"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("无移动"); //"No move." - PROGMEM Language_Str MSG_KILLED = _UxGT("已杀掉"); //"KILLED. " - PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); //"STOPPED. " - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回抽长度mm"); //"Retract mm" retract_length, retract length (positive mm) - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("换手回抽长度mm"); //"Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回抽速率mm/s"); //"Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); //"Hop mm" retract_zraise, retract Z-lift - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回抽恢复长度mm"); //"UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("换手回抽恢复长度mm"); //"S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回抽恢复后进料速率mm/s"); //"Unretract V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) + PROGMEM Language_Str MSG_NO_MOVE = _UxGT("无移动"); // "No move." + PROGMEM Language_Str MSG_KILLED = _UxGT("已杀掉"); // "KILLED. " + PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回抽长度mm"); // "Retract mm" retract_length, retract length (positive mm) + PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("换手回抽长度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回抽速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) + PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回抽恢复长度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("换手回抽恢复长度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回抽恢复后进料速率mm/s"); // "Unretract 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("自动抽回"); //"Auto-Retract" autoretract_enabled, + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("自动抽回"); // "Auto-Retract" autoretract_enabled, PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("交换长度"); PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("额外的交换"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("清洗长度"); @@ -384,17 +396,17 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("自动迁移"); PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("上一个挤出机"); PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("迁移至 *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("更换丝料"); //"Change filament" - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更换丝料 *"); //"Change filament" + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("更换丝料"); // "Change filament" + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更换丝料 *"); // "Change filament" PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("装载丝料"); // "Load filament" PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("装载丝料 *"); // "Load filament" 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_CHANGE_MEDIA = _UxGT("更换存储卡"); //"Change SD card" + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("初始化存储卡"); // "Init. SD card" + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("更换存储卡"); // "Change SD card" PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("释放存储卡"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z探针在热床之外"); //"Z probe out. bed" Z probe is not within the physical limits + 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("自检"); @@ -416,39 +428,39 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("部署TouchMI"); PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("部署Z探针"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("收好Z探针"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("归位 %s%s%s 先"); //"Home ... first" + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("归位 %s%s%s 先"); // "Home ... first" PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("探针偏移量"); PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("探针X偏移"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("探针Y偏移"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("探针Z偏移"); //"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_ZPROBE_ZOFFSET = _UxGT("探针Z偏移"); // "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("总计"); - 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("错误:冗余温度"); //"Err: REDUNDANT TEMP" - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("温控失控"); //"THERMAL RUNAWAY" + 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("错误:冗余温度"); // "Err: REDUNDANT TEMP" + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("温控失控"); // "THERMAL RUNAWAY" PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("热床热量失控"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("机箱热量失控"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("错误:最高温度"); //"Err: MAXTEMP" - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("错误:最低温度"); //"Err: MINTEMP" - PROGMEM Language_Str MSG_HALTED = _UxGT("打印停机"); //"PRINTER HALTED" - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("请重置"); //"Please reset" - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); //"d" // One character only - 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_ERR_MAXTEMP = _UxGT("错误:最高温度"); // "Err: MAXTEMP" + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("错误:最低温度"); // "Err: MINTEMP" + PROGMEM Language_Str MSG_HALTED = _UxGT("打印停机"); // "PRINTER HALTED" + PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("请重置"); // "Please reset" + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only + 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("冷却中 ..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("加热热床中 ..."); //"Bed Heating..." + PROGMEM Language_Str MSG_BED_HEATING = _UxGT("加热热床中 ..."); // "Bed Heating..." PROGMEM Language_Str MSG_BED_COOLING = _UxGT("热床冷却中 ..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("机箱加热中 ..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("机箱冷却中 ..."); - 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" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校准Z"); //"Calibrate Z" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校准中心"); //"Calibrate Center" + 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" + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校准Z"); // "Calibrate Z" + PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校准中心"); // "Calibrate Center" 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" @@ -456,19 +468,19 @@ namespace Language_zh_CN { 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" - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("关于打印机"); //"About Printer" - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("打印机信息"); //"Printer Info" + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("关于打印机"); // "About Printer" + 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_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_BAUDRATE = _UxGT("波特率"); //"Baud" - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("协议"); //"Protocol" + 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_BAUDRATE = _UxGT("波特率"); // "Baud" + PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("协议"); // "Protocol" PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("监控温度失控:关"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("监控温度失控:开"); PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("热端空闲超时"); @@ -479,26 +491,29 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); //"Print Count" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成了"); //"Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总打印时间"); //"Total print time" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长工作时间"); //"Longest job time" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("总计挤出"); //"Extruded total" + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); // "Print Count" + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成了"); // "Completed" + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总打印时间"); // "Total print time" + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长工作时间"); // "Longest job time" + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("总计挤出"); // "Extruded total" #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印数"); //"Prints" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); //"Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总共"); //"Total" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长"); //"Longest" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已挤出"); //"Extruded" + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印数"); // "Prints" + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总共"); // "Total" + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长"); // "Longest" + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已挤出"); // "Extruded" #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低温度"); //"Min Temp" - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("最高温度"); //"Max Temp" - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("电源供应"); //"Power Supply" + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低温度"); // "Min Temp" + 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_A = LCD_STR_A _UxGT(" 驱动 %"); // "X Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驱动 %"); + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驱动 %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驱动 %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驱动 %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驱动 %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E 驱动 %"); // "E Driver %" PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC 连接错误"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("保存驱动设置"); // "DAC EEPROM Write" @@ -508,7 +523,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("卸载丝料"); // "UNLOAD FILAMENT" PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢复选项:"); // "RESUME OPTIONS:" 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_OPTION_RESUME = _UxGT("恢复打印"); // "Resume print" PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 喷嘴: "); // " Nozzle: " PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("断料传感器"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("断料距离mm"); @@ -583,15 +598,15 @@ namespace Language_zh_CN { #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下继续")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停靠中...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("请等待 ...")); //"Please wait..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入并单击")); //"Insert and Click" + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("请等待 ...")); // "Please wait..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入并单击")); // "Insert and Click" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加热")); 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_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_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢复中 ...")); //"Resuming..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢复中 ...")); // "Resuming..." #endif PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC驱动器"); PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("驱动电流"); @@ -605,6 +620,9 @@ namespace Language_zh_CN { 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_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("校正"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("平滑的"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index f162536132..2c7d1bf69f 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -33,84 +33,84 @@ namespace Language_zh_TW { constexpr uint8_t CHARSIZE = 3; PROGMEM Language_Str LANGUAGE = _UxGT("Traditional Chinese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); //" ready." + PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); // " ready." 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_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_WAITING = _UxGT("等待記憶卡"); //"Waiting for media" + 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_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_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_RUN_AUTO_FILES = _UxGT("自動開始"); //"Autostart" - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); //"Disable steppers" + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自動開始"); // "Autostart" + PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); // "Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("除錯選單"); // "Debug Menu" PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("進度條測試"); // "Progress Bar Test" - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("自動回原點"); //"Auto home" - 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" - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成熱床調平"); //"Leveling Done!" + PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("自動回原點"); // "Auto home" + 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" + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成熱床調平"); // "Leveling Done!" PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("設置原點偏移"); //"Set home offsets" - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已啟用"); //"Offsets applied" - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("設置原點"); //"Set origin" + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("設置原點偏移"); // "Set home offsets" + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已啟用"); // "Offsets applied" + PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("設置原點"); // "Set origin" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("預熱 ") PREHEAT_1_LABEL; //"Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("預熱 ") PREHEAT_1_LABEL " ~"; //"Preheat PREHEAT_1_LABEL" + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("預熱 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_1_LABEL" + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("預熱 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_1_LABEL" PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴 ~"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 熱床"); //MSG_PREHEAT_1 " Bed" PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 設置"); //MSG_PREHEAT_1 " conf" - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("預熱 $"); //"Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("預熱 $ ~"); //"Preheat PREHEAT_1_LABEL" + PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("預熱 $"); // "Preheat PREHEAT_1_LABEL" + PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("預熱 $ ~"); // "Preheat PREHEAT_1_LABEL" PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("預熱 $ 噴嘴"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("預熱 $ 噴嘴 ~"); //MSG_PREHEAT_1 " " PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("預熱 $ 全部"); //MSG_PREHEAT_1 " All" PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("預熱 $ 熱床"); //MSG_PREHEAT_1 " Bed" PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("預熱 $ 設置"); //MSG_PREHEAT_1 " conf" #endif - 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_POWER = _UxGT("激光電源"); //"Laser Power" - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主軸控告制"); //"Spindle Control" - 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" - PROGMEM Language_Str MSG_RETRACT = _UxGT("回縮"); //"Retract" - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移動軸"); //"Move axis" - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("調平熱床"); //"Bed leveling" - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("調平熱床"); //"Level bed" + 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_POWER = _UxGT("激光電源"); // "Laser Power" + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主軸控告制"); // "Spindle Control" + 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" + PROGMEM Language_Str MSG_RETRACT = _UxGT("回縮"); // "Retract" + PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移動軸"); // "Move axis" + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("調平熱床"); // "Bed leveling" + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("調平熱床"); // "Level bed" PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("調平邊角"); // "Bed Tramming" PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下個邊角"); // "Next corner" - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("網格編輯器"); //"Mesh Editor" + 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_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_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_CUSTOM_COMMANDS = _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_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"); @@ -123,7 +123,7 @@ namespace Language_zh_TW { 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_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" @@ -132,9 +132,9 @@ namespace Language_zh_TW { 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_BED_TEMP_CUSTOM = _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_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" @@ -150,13 +150,13 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("高度合計"); // "Height Amount" PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("批准網格"); // "Validate 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_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_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" @@ -186,7 +186,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 = _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. 創設冷網格"); @@ -218,148 +218,160 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVING = _UxGT("移動 ..."); // "Moving...") PROGMEM Language_Str MSG_FREE_XY = _UxGT("釋放 XY"); // "Free XY") - PROGMEM Language_Str MSG_MOVE_X = _UxGT("移動X"); //"Move X" - 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("擠出機 *"); //"Extruder *" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" - PROGMEM Language_Str MSG_MOVE_N_MM = _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" - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); //"Move 10mm" - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); //"Move 100mm" - PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" - PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); //"Bed Z" - PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); //"Nozzle" 噴嘴 + PROGMEM Language_Str MSG_MOVE_X = _UxGT("移動X"); // "Move X" + 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("擠出機 *"); // "Extruder *" + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); // "Hotend too cold" + PROGMEM Language_Str MSG_MOVE_N_MM = _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" + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); // "Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); // "Move 100mm" + PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); // "Speed" + PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); // "Bed Z" + 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_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 = _UxGT("風扇速率"); // "Fan speed" 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_FLOW = _UxGT("擠出速率"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("擠出速率 ~"); //"Flow" - PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); //"Control" - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); //" " LCD_STR_THERMOMETER " Min" - 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_FLOW_N = _UxGT("擠出速率 ~"); // "Flow" + PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); // "Control" + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" + 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_SELECT = _UxGT("選擇"); //"Select" + PROGMEM Language_Str MSG_SELECT = _UxGT("選擇"); // "Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("選擇 *"); - PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); //"Accel" acceleration - PROGMEM Language_Str MSG_JERK = _UxGT("抖動速率"); //"Jerk" - PROGMEM Language_Str MSG_VA_JERK = _UxGT("軸抖動速率") LCD_STR_A; //"Va-jerk" - 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_ACC = _UxGT("加速度"); // "Accel" acceleration + PROGMEM Language_Str MSG_JERK = _UxGT("抖動速率"); // "Jerk" + PROGMEM Language_Str MSG_VA_JERK = _UxGT("軸抖動速率") LCD_STR_A; // "Va-jerk" + PROGMEM Language_Str MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; + PROGMEM Language_Str MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; + PROGMEM Language_Str MSG_VI_JERK = _UxGT("軸抖動速率") LCD_STR_I; + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("軸抖動速率") LCD_STR_J; + PROGMEM Language_Str MSG_VK_JERK = _UxGT("軸抖動速率") LCD_STR_K; + PROGMEM Language_Str MSG_VE_JERK = _UxGT("擠出機抖動速率"); 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_A = _UxGT("最大進料速率") LCD_STR_A; // "Vmax " max_feedrate_mm_s PROGMEM Language_Str MSG_VMAX_B = _UxGT("最大進料速率") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("最大進料速率") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("最大進料速率") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("最大進料速率") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("最大進料速率") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("最大進料速率") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大進料速率 *"); //"Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMIN = _UxGT("最小進料速率"); //"Vmin" min_feedrate_mm_s - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移動速率"); //"VTrav min" min_travel_feedrate_mm_s, (target) speed of the move + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大進料速率 *"); // "Vmax " max_feedrate_mm_s + PROGMEM Language_Str MSG_VMIN = _UxGT("最小進料速率"); // "Vmin" min_feedrate_mm_s + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移動速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move PROGMEM Language_Str MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大列印加速度") LCD_STR_A; //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大列印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves PROGMEM Language_Str MSG_AMAX_B = _UxGT("最大列印加速度") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("最大列印加速度") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("最大列印加速度") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("最大列印加速度") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("最大列印加速度") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("最大列印加速度") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大列印加速度 *"); //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("回縮加速度"); //"A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非列印移動加速度"); //"A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("軸步數/mm"); //"Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("軸步數/mm"); //"Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("軸步數/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("軸步數/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("擠出機步數/mm"); //"Esteps/mm" + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大列印加速度 *"); // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("回縮加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非列印移動加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves + PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("軸步數/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" 軸步數/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" 軸步數/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" 軸步數/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" 軸步數/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" 軸步數/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("擠出機步數/mm"); // "Esteps/mm" PROGMEM Language_Str MSG_EN_STEPS = _UxGT("擠出機~步數/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("溫度"); //"Temperature" - PROGMEM Language_Str MSG_MOTION = _UxGT("運作"); //"Motion" - PROGMEM Language_Str MSG_FILAMENT = _UxGT("絲料測容"); //"Filament" menu_control_volumetric - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm") SUPERSCRIPT_THREE; //"E in mm3" volumetric_enabled - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("絲料直徑"); //"Fil. Dia." + PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("溫度"); // "Temperature" + PROGMEM Language_Str MSG_MOTION = _UxGT("運作"); // "Motion" + PROGMEM Language_Str MSG_FILAMENT = _UxGT("絲料測容"); // "Filament" menu_control_volumetric + PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled + PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("絲料直徑"); // "Fil. Dia." 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 failsafe" + 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 failsafe" PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("初始化設置"); // "Initialize EEPROM" - 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_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. " - PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); //"STOPPED. " - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回縮長度mm"); //"Retract mm" retract_length, retract length (positive mm) - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("換手回抽長度mm"); //"Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回縮速率mm/s"); //"Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); //"Hop mm" retract_zraise, retract Z-lift - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回縮恢復長度mm"); //"UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("換手回縮恢復長度mm"); //"S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回縮恢復後進料速率mm/s"); //"Unretract V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) + 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. " + PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回縮長度mm"); // "Retract mm" retract_length, retract length (positive mm) + PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("換手回抽長度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回縮速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) + PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回縮恢復長度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("換手回縮恢復長度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回縮恢復後進料速率mm/s"); // "Unretract 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("自動回縮"); //"Auto-Retract" 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_AUTORETRACT = _UxGT("自動回縮"); // "Auto-Retract" 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_SPEED = _UxGT("最高速度"); //"Prime Speed" - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("收回速度"); //"Retract Speed" + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z軸提昇"); // "Z Raise" + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("最高速度"); // "Prime Speed" + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _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 = _UxGT("更換絲料"); // "Change filament" PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更換絲料 *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("裝載絲料"); // "Load filament" PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("裝載絲料 *"); 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_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_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_SELFTEST = _UxGT("BLTouch 自檢"); // "BLTouch Self-Test" @@ -367,39 +379,39 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("裝載BLTouch"); // "Stow BLTouch" PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); //"Home ... first" + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); // "Home ... first" 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("錯誤:冗餘溫度"); //"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_HALTED = _UxGT("印表機停機"); //"PRINTER HALTED" - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); //"Please reset" - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); //"d" // One character only - 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_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("錯誤:冗餘溫度"); // "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_HALTED = _UxGT("印表機停機"); // "PRINTER HALTED" + PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); // "Please reset" + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only + 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" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校準Z"); //"Calibrate Z" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校準中心"); //"Calibrate Center" + 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" + PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校準Z"); // "Calibrate Z" + PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校準中心"); // "Calibrate Center" 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" @@ -407,61 +419,63 @@ namespace Language_zh_TW { 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" - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("關於印表機"); //"About Printer" - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("印表機訊息"); //"Printer Info" + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("關於印表機"); // "About Printer" + 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_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_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_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_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_KILL_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); //"Print Count" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("已完成"); //"Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總列印時間"); //"Total print time" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長工作時間"); //"Longest job time" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("總計擠出"); //"Extruded total" + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); // "Print Count" + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("已完成"); // "Completed" + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總列印時間"); // "Total print time" + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長工作時間"); // "Longest job time" + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("總計擠出"); // "Extruded total" #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印數"); //"Prints" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); //"Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總共"); //"Total" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長"); //"Longest" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已擠出"); //"Extruded" + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印數"); // "Prints" + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總共"); // "Total" + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長"); // "Longest" + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已擠出"); // "Extruded" #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低溫度"); //"Min Temp" - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("最高溫度"); //"Max Temp" - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("電源供應"); //"Power Supply" + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低溫度"); // "Min Temp" + 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 = _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_A = LCD_STR_A _UxGT(" 驅動 %"); // X Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驅動 %"); // Y Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驅動 %"); // Z Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驅動 %"); // I Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驅動 %"); // J Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驅動 %"); // K 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_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 = _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" PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢複選項:"); // "RESUME OPTIONS:" 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_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_RUNOUT_SENSOR = _UxGT("斷絲偵測"); // "Runout Sensor" + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("絲距離mm"); // "Runout Dist mm" PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" @@ -471,28 +485,28 @@ namespace Language_zh_TW { // #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_PARKING = _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_PAUSE_PRINT_PARKING = _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_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_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" + 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_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); //"Please wait..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); //"Insert and Click" - 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_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成..")); //"Click to finish" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢復中 ...")); //"Resuming..." + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下繼續..")); // "Click to continue" + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); // "Parking..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); // "Please wait..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); // "Insert and Click" + 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_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 } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 4ae38edf24..467aa9a4eb 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -68,7 +68,7 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }) - LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(X), EDIT_DAC_PERCENT(Y), EDIT_DAC_PERCENT(Z), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K)); + LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(A), EDIT_DAC_PERCENT(B), EDIT_DAC_PERCENT(C), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K)); ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom); END_MENU(); } From 1903cc23c6a6a004b342503006ae9d51a5ea86c8 Mon Sep 17 00:00:00 2001 From: Fjederhaek Date: Sat, 21 Aug 2021 00:45:05 +0200 Subject: [PATCH 0567/2168] =?UTF-8?q?=F0=9F=90=9B=20Update=20H-bot=20/=20C?= =?UTF-8?q?ore=20for=206-axis=20(#22600)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #19112 --- Marlin/src/module/planner.cpp | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 7bf672a85d..e4649b9410 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2002,15 +2002,15 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Number of steps for each axis // See https://www.corexy.com/theory.html #if CORE_IS_XY - block->steps.set(ABS(da + db), ABS(da - db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da + db), ABS(da - db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #elif CORE_IS_XZ - block->steps.set(ABS(da + dc), ABS(db), ABS(da - dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da + dc), ABS(db), ABS(da - dc), ABS(di), ABS(dj), ABS(dk))); #elif CORE_IS_YZ - block->steps.set(ABS(da), ABS(db + dc), ABS(db - dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db + dc), ABS(db - dc), ABS(di), ABS(dj), ABS(dk))); #elif ENABLED(MARKFORGED_XY) - block->steps.set(ABS(da + db), ABS(db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da + db), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #elif IS_SCARA - block->steps.set(ABS(da), ABS(db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #else // default non-h-bot planning block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); @@ -2208,6 +2208,17 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (block->steps.k) ENABLE_AXIS_K() ); #endif + #if EITHER(IS_CORE, MARKFORGED_XY) + #if LINEAR_AXES >= 4 + if (block->steps.i) ENABLE_AXIS_I(); + #endif + #if LINEAR_AXES >= 5 + if (block->steps.j) ENABLE_AXIS_J(); + #endif + #if LINEAR_AXES >= 6 + if (block->steps.k) ENABLE_AXIS_K(); + #endif + #endif // Enable extruder(s) #if HAS_EXTRUDERS From 0d854d332d10a2f8123eefa0f0d367b984de36b3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 21 Aug 2021 00:55:55 +0000 Subject: [PATCH 0568/2168] [cron] Bump distribution date (2021-08-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index db5a6e1524..21efff8495 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-20" +//#define STRING_DISTRIBUTION_DATE "2021-08-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index dcad270c26..abebd0742b 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 "2021-08-20" + #define STRING_DISTRIBUTION_DATE "2021-08-21" #endif /** From 104acd9e5997e16ad327340a205d6611517fa65e Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 21 Aug 2021 12:19:02 -0700 Subject: [PATCH 0569/2168] =?UTF-8?q?=E2=AC=86=EF=B8=8F=20TMCStepper=200.7?= =?UTF-8?q?.3=20(#22608)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index b94c3fb9bc..2d2363ccd1 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -17,7 +17,7 @@ HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/L POSTMORTEM_DEBUGGING = src_filter=+ + build_flags=-funwind-tables MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip -HAS_TRINAMIC_CONFIG = TMCStepper@0.7.1 +HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.3 src_filter=+ + + + + HAS_STEALTHCHOP = src_filter=+ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip From 2e3b13133159669ecb9682079f60972d0ff5b3c8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Aug 2021 15:07:52 -0500 Subject: [PATCH 0570/2168] =?UTF-8?q?=F0=9F=8E=A8=20Tweak=20TMC=20software?= =?UTF-8?q?=20serial=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 3 -- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 13 +++----- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 6 ++-- Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 17 ++++++---- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 3 ++ Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 4 --- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 11 +++---- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 13 +++----- Marlin/src/pins/lpc1769/pins_FLY_CDY.h | 12 +++---- Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 15 +++++---- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 17 +++++----- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 4 ++- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 26 +++++++-------- Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 17 ++++++---- Marlin/src/pins/ramps/pins_ORTUR_4.h | 21 ++++++------ Marlin/src/pins/ramps/pins_RAMPS.h | 4 --- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 4 --- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 4 --- Marlin/src/pins/samd/pins_RAMPS_144.h | 20 +++++------ Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 11 +++---- .../pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h | 11 +++---- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 23 ++++++++----- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 6 ++-- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 11 +++---- .../pins/stm32f1/pins_FYSETC_CHEETAH_V12.h | 3 -- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 6 ++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 4 --- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 3 -- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 4 --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 3 -- Marlin/src/pins/stm32f4/pins_ARMED.h | 3 -- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 11 +++---- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 15 ++++----- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 25 +++++++------- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 25 +++++++------- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 15 ++++----- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 13 +++----- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 19 +++++------ Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 3 -- Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h | 1 - Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h | 33 +++++++++++-------- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 12 +++---- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 16 ++++----- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 10 +++--- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 14 +++----- Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h | 3 -- Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h | 10 +++--- Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h | 13 +++----- 48 files changed, 238 insertions(+), 302 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 42c6f4d029..b922f057f1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -164,9 +164,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN P4_29 #define X_SERIAL_RX_PIN P1_17 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 43e954a4f1..2c9e608e49 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -220,23 +220,20 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN P1_10 - #define X_SERIAL_RX_PIN P1_10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN P1_09 - #define Y_SERIAL_RX_PIN P1_09 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN P1_08 - #define Z_SERIAL_RX_PIN P1_08 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN P1_04 - #define E0_SERIAL_RX_PIN P1_04 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN P1_01 - #define E1_SERIAL_RX_PIN P1_01 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index cb3d3242e2..9e04fc0479 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -172,7 +172,7 @@ #define E2_CS_PIN EXP1_05_PIN #if HAS_TMC_UART #define E2_SERIAL_TX_PIN EXP1_05_PIN - #define E2_SERIAL_RX_PIN EXP1_05_PIN + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #endif #endif @@ -185,7 +185,7 @@ #define E3_CS_PIN EXP1_07_PIN #if HAS_TMC_UART #define E3_SERIAL_TX_PIN EXP1_07_PIN - #define E3_SERIAL_RX_PIN EXP1_07_PIN + #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN #endif #else #define E3_ENABLE_PIN EXP2_04_PIN @@ -200,7 +200,7 @@ #define E4_CS_PIN EXP1_09_PIN #if HAS_TMC_UART #define E4_SERIAL_TX_PIN EXP1_09_PIN - #define E4_SERIAL_RX_PIN EXP1_09_PIN + #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #endif #else #define E4_ENABLE_PIN EXP2_04_PIN diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 1ec1131b45..1feaeb13b5 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -82,17 +82,22 @@ // #if HAS_TMC_UART #define X_SERIAL_TX_PIN P1_00 - #define X_SERIAL_RX_PIN P1_00 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN P1_09 - #define Y_SERIAL_RX_PIN P1_09 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN P1_16 - #define Z_SERIAL_RX_PIN P1_16 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN P0_04 - #define E0_SERIAL_RX_PIN P0_04 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E1_SERIAL_TX_PIN P2_02 - #define E1_SERIAL_RX_PIN P2_02 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN + #define E2_SERIAL_TX_PIN P2_06 - #define E2_SERIAL_RX_PIN P2_06 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 44dbaacb73..a2235dc28a 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -327,10 +327,13 @@ */ #define X_SERIAL_TX_PIN P1_22 // J8-2 #define X_SERIAL_RX_PIN P2_12 // J8-4 Interrupt Capable + #define Y_SERIAL_TX_PIN P1_23 // J8-3 #define Y_SERIAL_RX_PIN P2_11 // J8-5 Interrupt Capable + #define Z_SERIAL_TX_PIN P2_12 // J8-4 #define Z_SERIAL_RX_PIN P0_25 // TH3 + #define E0_SERIAL_TX_PIN P4_28 // J8-6 #define E0_SERIAL_RX_PIN P0_26 // TH4 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 8808c3a228..449d9a93ce 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -163,10 +163,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #define X_SERIAL_TX_PIN P1_04 #define X_SERIAL_RX_PIN P1_01 diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index fe7daa8cda..62127f5504 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -119,9 +119,6 @@ * If undefined software serial is used according to the pins below */ - // - // Software serial - // // P2_08 E1-Step // P2_13 E1-Dir @@ -130,28 +127,28 @@ #define X_SERIAL_TX_PIN P0_01 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN P0_01 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #endif #ifndef Y_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN P0_00 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN P0_00 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #endif #ifndef Z_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN P2_13 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN P2_13 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #endif #ifndef E0_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN P2_08 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN P2_08 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #endif // Reduce baud rate to improve software serial reliability diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index cecb44efbe..44ceb9b7cc 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -129,23 +129,20 @@ * If undefined software serial is used according to the pins below */ - // - // Software serial - // #define X_SERIAL_TX_PIN P1_01 - #define X_SERIAL_RX_PIN P1_01 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN P1_10 - #define Y_SERIAL_RX_PIN P1_10 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN P1_17 - #define Z_SERIAL_RX_PIN P1_17 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN P0_05 - #define E0_SERIAL_RX_PIN P0_05 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN P0_22 - #define E1_SERIAL_RX_PIN P0_22 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index b90443403c..535fb32e3e 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -104,22 +104,22 @@ #if HAS_TMC_UART #define X_SERIAL_TX_PIN P1_04 - #define X_SERIAL_RX_PIN P1_04 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN P1_10 - #define Y_SERIAL_RX_PIN P1_10 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN P1_16 - #define Z_SERIAL_RX_PIN P1_16 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN P4_28 - #define E0_SERIAL_RX_PIN P4_28 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN P2_12 - #define E1_SERIAL_RX_PIN P2_12 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN P0_10 - #define E2_SERIAL_RX_PIN P0_10 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index ddfee63cd0..f5c158162c 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -38,17 +38,20 @@ /** * TMC2208/TMC2209 stepper drivers */ - #define X_SERIAL_TX_PIN P1_22 // J8-2 - #define X_SERIAL_RX_PIN P1_22 // J8-2 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN P1_23 // J8-3 - #define Y_SERIAL_RX_PIN P1_23 // J8-3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN P2_12 // J8-4 - #define Z_SERIAL_RX_PIN P2_12 // J8-4 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN P2_11 // J8-5 - #define E0_SERIAL_RX_PIN P2_11 // J8-5 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E1_SERIAL_TX_PIN P4_28 // J8-6 - #define E1_SERIAL_RX_PIN P4_28 // J8-6 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 7547279bbd..ff7aa11daf 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -173,19 +173,20 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN P1_01 - #define X_SERIAL_RX_PIN P1_01 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN P1_08 - #define Y_SERIAL_RX_PIN P1_08 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN P1_10 - #define Z_SERIAL_RX_PIN P1_10 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN P1_15 - #define E0_SERIAL_RX_PIN P1_15 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E1_SERIAL_TX_PIN P1_17 - #define E1_SERIAL_RX_PIN P1_17 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 4d725bc7d1..e45f5dbd95 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -75,14 +75,16 @@ #if HAS_TMC_UART // // TMC220x stepper drivers - // Software serial // #define X_SERIAL_TX_PIN P0_04 #define X_SERIAL_RX_PIN P0_05 + #define Y_SERIAL_TX_PIN P0_10 #define Y_SERIAL_RX_PIN P0_11 + #define Z_SERIAL_TX_PIN P0_19 #define Z_SERIAL_RX_PIN P0_20 + #define E0_SERIAL_TX_PIN P0_22 #define E0_SERIAL_RX_PIN P0_21 diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 8756a33218..9c6b74f126 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -124,42 +124,42 @@ * Software serial communication pins. * At the moment, F6 rx pins are not pc interrupt pins */ - #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN -1 // 71 - #endif #ifndef X_SERIAL_TX_PIN #define X_SERIAL_TX_PIN 72 #endif - #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN -1 // 73 + #ifndef X_SERIAL_RX_PIN + #define X_SERIAL_RX_PIN -1 // 71 #endif #ifndef Y_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN 75 #endif - #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN -1 // 78 + #ifndef Y_SERIAL_RX_PIN + #define Y_SERIAL_RX_PIN -1 // 73 #endif #ifndef Z_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN 79 #endif - #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN -1 // 76 + #ifndef Z_SERIAL_RX_PIN + #define Z_SERIAL_RX_PIN -1 // 78 #endif #ifndef E0_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN 77 #endif - #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 // 80 + #ifndef E0_SERIAL_RX_PIN + #define E0_SERIAL_RX_PIN -1 // 76 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN 81 #endif - #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN -1 // 22 + #ifndef E1_SERIAL_RX_PIN + #define E1_SERIAL_RX_PIN -1 // 80 #endif #ifndef E2_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN 82 #endif + #ifndef E2_SERIAL_RX_PIN + #define E2_SERIAL_RX_PIN -1 // 22 + #endif #endif // diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index 4280204b99..1fc24154b7 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -33,18 +33,23 @@ /** * TMC2208/TMC2209 stepper drivers */ - #define X_SERIAL_RX_PIN 72 #define X_SERIAL_TX_PIN 71 - #define Y_SERIAL_RX_PIN 73 + #define X_SERIAL_RX_PIN 72 + #define Y_SERIAL_TX_PIN 78 - #define Z_SERIAL_RX_PIN 75 + #define Y_SERIAL_RX_PIN 73 + #define Z_SERIAL_TX_PIN 79 - #define E0_SERIAL_RX_PIN 77 + #define Z_SERIAL_RX_PIN 75 + #define E0_SERIAL_TX_PIN 81 - #define E1_SERIAL_RX_PIN 76 + #define E0_SERIAL_RX_PIN 77 + #define E1_SERIAL_TX_PIN 80 - #define E2_SERIAL_RX_PIN 62 + #define E1_SERIAL_RX_PIN 76 + #define E2_SERIAL_TX_PIN 82 + #define E2_SERIAL_RX_PIN 62 #endif #include "pins_FYSETC_F6_13.h" diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h index e79973e06f..428279c92a 100644 --- a/Marlin/src/pins/ramps/pins_ORTUR_4.h +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -54,20 +54,19 @@ #define TEMP_0_PIN 15 // Analog Input #define TEMP_1_PIN 13 // Analog Input -// -// Software serial -// -#define X_SERIAL_TX_PIN 59 -#define X_SERIAL_RX_PIN 63 +#if HAS_TMC_UART + #define X_SERIAL_TX_PIN 59 + #define X_SERIAL_RX_PIN 63 -#define Y_SERIAL_TX_PIN 64 -#define Y_SERIAL_RX_PIN 40 + #define Y_SERIAL_TX_PIN 64 + #define Y_SERIAL_RX_PIN 40 -#define Z_SERIAL_TX_PIN 44 -#define Z_SERIAL_RX_PIN 42 + #define Z_SERIAL_TX_PIN 44 + #define Z_SERIAL_RX_PIN 42 -#define E0_SERIAL_TX_PIN 66 -#define E0_SERIAL_RX_PIN 65 + #define E0_SERIAL_TX_PIN 66 + #define E0_SERIAL_RX_PIN 65 +#endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 2c271408b0..b141fdbf85 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -321,10 +321,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #ifndef X_SERIAL_TX_PIN #define X_SERIAL_TX_PIN 40 #endif diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 57a9a560d3..a43f10fc93 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -117,10 +117,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E3_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #define X_SERIAL_TX_PIN -1 // 59 #define X_SERIAL_RX_PIN -1 // 63 #define X2_SERIAL_TX_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 26ad5fd658..feaa4ba98b 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -213,10 +213,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #ifndef X_SERIAL_TX_PIN #define X_SERIAL_TX_PIN 40 #endif diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index fbd9d7c864..449ae0273e 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -194,60 +194,56 @@ //#define E0_HARDWARE_SERIAL Serial1 //#define E1_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #ifndef X_SERIAL_TX_PIN #define X_SERIAL_TX_PIN 47 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 47 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 #endif #ifndef X2_SERIAL_RX_PIN - #define X2_SERIAL_RX_PIN -1 + #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN #endif #ifndef Y_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN 45 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 45 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 #endif #ifndef Y2_SERIAL_RX_PIN - #define Y2_SERIAL_RX_PIN -1 + #define Y2_SERIAL_RX_PIN Y2_SERIAL_TX_PIN #endif #ifndef Z_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN 32 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 32 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN 22 #endif #ifndef Z2_SERIAL_RX_PIN - #define Z2_SERIAL_RX_PIN 22 + #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN #endif #ifndef E0_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN 43 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 43 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN -1 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 9b71570b08..6ed2869141 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -120,20 +120,17 @@ //#define Z_HARDWARE_SERIAL MSerial1 //#define E0_HARDWARE_SERIAL MSerial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PC10 - #define X_SERIAL_RX_PIN PC10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PC11 - #define Y_SERIAL_RX_PIN PC11 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PC12 - #define Z_SERIAL_RX_PIN PC12 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD2 - #define E0_SERIAL_RX_PIN PD2 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h index 4951d697a7..44d4f23435 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h @@ -33,20 +33,17 @@ * TMC2208/TMC2209 stepper drivers */ #if HAS_TMC_UART - // - // Software serial - // #define X_SERIAL_TX_PIN PB15 - #define X_SERIAL_RX_PIN PB15 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PC6 - #define Y_SERIAL_RX_PIN PC6 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PC10 - #define Z_SERIAL_RX_PIN PC10 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PC11 - #define E0_SERIAL_RX_PIN PC11 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index dc8b8c50f1..7b61f55d4f 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -84,15 +84,20 @@ #define E0_STEP_PIN PA6 #define E0_DIR_PIN PA5 -// Stepper drivers Serial UART -#define X_SERIAL_TX_PIN PB3 -#define X_SERIAL_RX_PIN PD2 -#define Y_SERIAL_TX_PIN PA15 -#define Y_SERIAL_RX_PIN PC6 -#define Z_SERIAL_TX_PIN PB11 -#define Z_SERIAL_RX_PIN PB10 -#define E0_SERIAL_TX_PIN PC5 -#define E0_SERIAL_RX_PIN PC4 +#if HAS_TMC_UART + // Stepper drivers Serial UART + #define X_SERIAL_TX_PIN PB3 + #define X_SERIAL_RX_PIN PD2 + + #define Y_SERIAL_TX_PIN PA15 + #define Y_SERIAL_RX_PIN PC6 + + #define Z_SERIAL_TX_PIN PB11 + #define Z_SERIAL_RX_PIN PB10 + + #define E0_SERIAL_TX_PIN PC5 + #define E0_SERIAL_RX_PIN PC4 +#endif // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index 21bbd23ca9..f850b4a90b 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -124,11 +124,11 @@ // SoftwareSerial with one pin per driver // Compatible with TMC2208 and TMC2209 drivers #define X_SERIAL_TX_PIN PA10 // RXD1 - #define X_SERIAL_RX_PIN PA10 // RXD1 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PA9 // TXD1 - #define Y_SERIAL_RX_PIN PA9 // TXD1 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PC7 // IO1 - #define Z_SERIAL_RX_PIN PC7 // IO1 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define TMC_BAUD_RATE 19200 #else // Motor current PWM pins diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index be0a622b1d..08efa9a04e 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -94,17 +94,14 @@ #endif #if HAS_TMC_UART - // - // Software serial - // #define X_SERIAL_TX_PIN PB0 - #define X_SERIAL_RX_PIN PB0 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PA7 - #define Y_SERIAL_RX_PIN PA7 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PA4 - #define Z_SERIAL_RX_PIN PA4 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PC2 - #define E0_SERIAL_RX_PIN PC2 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h index ba35265d10..120d6d6f0a 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h @@ -42,9 +42,6 @@ * TMC2208/TMC2209 stepper drivers */ - // - // Software serial - // #define X_SERIAL_TX_PIN PA11 #define X_SERIAL_RX_PIN PA12 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 889e1f5e07..29baeba934 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -258,12 +258,12 @@ //#define TMC_SOFTWARE_SERIAL #if ENABLED(TMC_SOFTWARE_SERIAL) #define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6 - #define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5 - #define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6 - #define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5 #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN -- XS2 - 5 #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN -- XS1 - 6 #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN -- XS1 - 5 #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define TMC_BAUD_RATE 19200 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index ba51980065..2cfb71380d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -145,10 +145,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #define X_SERIAL_TX_PIN PD5 #define X_SERIAL_RX_PIN PD5 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 5a35932801..c568e42df2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -92,9 +92,6 @@ //#define Z_HARDWARE_SERIAL MSerial1 //#define E0_HARDWARE_SERIAL MSerial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PC7 #define X_SERIAL_RX_PIN PC7 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 49d5476fec..e83bcb0a5c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -146,10 +146,6 @@ //#define E0_HARDWARE_SERIAL MSerial1 //#define E1_HARDWARE_SERIAL MSerial1 - // - // Software serial - // - #define X_SERIAL_TX_PIN PD5 #define X_SERIAL_RX_PIN PD5 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index d752d52a3a..1f3efee6e5 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -133,9 +133,6 @@ //#define E1_HARDWARE_SERIAL MSerial1 //#define E2_HARDWARE_SERIAL MSerial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PF7 #define X_SERIAL_RX_PIN PF8 diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index a67af089f2..4d0369b044 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -204,9 +204,6 @@ #if HAS_TMC_UART // TMC2208/TMC2209 stepper drivers - // - // Software serial - // #define X_SERIAL_TX_PIN EXT0_PIN #define X_SERIAL_RX_PIN EXT0_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 2bfbb19427..79a414d7d4 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -137,20 +137,17 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial ## - // #define X_SERIAL_TX_PIN PE2 - #define X_SERIAL_RX_PIN PE2 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PE4 - #define Z_SERIAL_RX_PIN PE4 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD7 - #define E0_SERIAL_RX_PIN PD7 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index a806611c18..481c38f515 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -112,27 +112,24 @@ * TMC2208/TMC2209 stepper drivers */ #if HAS_TMC_UART - // - // Software serial - // #define X_SERIAL_TX_PIN PD6 - #define X_SERIAL_RX_PIN PD6 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD1 - #define Y_SERIAL_RX_PIN PD1 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD15 - #define Z_SERIAL_RX_PIN PD15 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD11 - #define E0_SERIAL_RX_PIN PD11 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #if ENABLED(BTT_E3_RRF_IDEX_BOARD) #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART - #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART + #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART - #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #endif // Reduce baud rate to improve software serial reliability diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 3151a38ae8..fa49ff1495 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -239,42 +239,39 @@ //#define E6_HARDWARE_SERIAL Serial1 // M5 MOTOR 4 //#define E7_HARDWARE_SERIAL Serial1 // M5 MOTOR 5 - // - // Software serial - // #define X_SERIAL_TX_PIN PC14 - #define X_SERIAL_RX_PIN PC14 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE1 - #define Y_SERIAL_RX_PIN PE1 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PB5 - #define Z_SERIAL_RX_PIN PB5 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PG10 - #define E0_SERIAL_RX_PIN PG10 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD4 - #define E1_SERIAL_RX_PIN PD4 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PC12 - #define E2_SERIAL_RX_PIN PC12 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #if ENABLED(M5_EXTENDER) #define E3_SERIAL_TX_PIN PG4 - #define E3_SERIAL_RX_PIN PG4 + #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN #define E4_SERIAL_TX_PIN PE15 - #define E4_SERIAL_RX_PIN PE15 + #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #define E5_SERIAL_TX_PIN PE7 - #define E5_SERIAL_RX_PIN PE7 + #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN #define E6_SERIAL_TX_PIN PF15 - #define E6_SERIAL_RX_PIN PF15 + #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN #define E7_SERIAL_TX_PIN PH14 - #define E7_SERIAL_RX_PIN PH14 + #define E7_SERIAL_RX_PIN E7_SERIAL_TX_PIN #endif // Reduce baud rate to improve software serial reliability diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 25622bc62d..92e7b5d374 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -282,32 +282,29 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PC4 - #define X_SERIAL_RX_PIN PC4 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD11 - #define Y_SERIAL_RX_PIN PD11 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PC6 - #define Z_SERIAL_RX_PIN PC6 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN PC7 - #define Z2_SERIAL_RX_PIN PC7 + #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PF2 - #define E0_SERIAL_RX_PIN PF2 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PE4 - #define E1_SERIAL_RX_PIN PE4 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PE1 - #define E2_SERIAL_RX_PIN PE1 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #define E3_SERIAL_TX_PIN PD3 - #define E3_SERIAL_RX_PIN PD3 + #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -387,7 +384,7 @@ #define E4_CS_PIN EXP1_05_PIN #if HAS_TMC_UART #define E4_SERIAL_TX_PIN EXP1_05_PIN - #define E4_SERIAL_RX_PIN EXP1_05_PIN + #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #endif // M2 on Driver Expansion Module @@ -398,7 +395,7 @@ #define E5_CS_PIN EXP1_07_PIN #if HAS_TMC_UART #define E5_SERIAL_TX_PIN EXP1_07_PIN - #define E5_SERIAL_RX_PIN EXP1_07_PIN + #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN #endif // M3 on Driver Expansion Module @@ -409,7 +406,7 @@ #define E6_CS_PIN EXP1_09_PIN #if HAS_TMC_UART #define E6_SERIAL_TX_PIN EXP1_09_PIN - #define E6_SERIAL_RX_PIN EXP1_09_PIN + #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN #endif #endif // BTT_MOTOR_EXPANSION diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index eb3ce730a6..e43cc4e5a0 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -204,26 +204,23 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PC13 - #define X_SERIAL_RX_PIN PC13 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PE1 - #define Z_SERIAL_RX_PIN PE1 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD4 - #define E0_SERIAL_RX_PIN PD4 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD1 - #define E1_SERIAL_RX_PIN PD1 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PD6 - #define E2_SERIAL_RX_PIN PD6 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index e5d6b6891b..dc2ee99aff 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -267,23 +267,20 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PE0 - #define X_SERIAL_RX_PIN PE0 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD3 - #define Y_SERIAL_RX_PIN PD3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD0 - #define Z_SERIAL_RX_PIN PD0 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PC6 - #define E0_SERIAL_RX_PIN PC6 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD12 - #define E1_SERIAL_RX_PIN PD12 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 77257f818a..728e753543 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -234,32 +234,31 @@ #if HAS_TMC_UART #define X_SERIAL_TX_PIN PG13 - #define X_SERIAL_RX_PIN PG13 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PG10 - #define Y_SERIAL_RX_PIN PG10 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD5 - #define Z_SERIAL_RX_PIN PD5 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD1 - #define E0_SERIAL_RX_PIN PD1 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PA14 - #define E1_SERIAL_RX_PIN PA14 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PG6 - #define E2_SERIAL_RX_PIN PG6 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #define E3_SERIAL_TX_PIN PG3 - #define E3_SERIAL_RX_PIN PG3 + #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN #define E4_SERIAL_TX_PIN PD10 - #define E4_SERIAL_RX_PIN PD10 + #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #define E5_SERIAL_TX_PIN PB12 - #define E5_SERIAL_RX_PIN PB12 - + #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 492383048e..986cd7feaa 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -118,9 +118,6 @@ // TMC2208/TMC2209 stepper drivers // - // - // Software serial - // #ifndef X_SERIAL_TX_PIN #define X_SERIAL_TX_PIN PE9 #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index 641805d855..6f1c9be8f5 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -40,7 +40,6 @@ #if HAS_TMC_UART #define X_SERIAL_TX_PIN PE8 #define Y_SERIAL_TX_PIN PC4 - #define Y_SERIAL_RX_PIN PC4 #define Z_SERIAL_TX_PIN PD12 #define E0_SERIAL_TX_PIN PA15 #define E1_SERIAL_TX_PIN PC5 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index e90ac552ae..e05811552e 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -76,21 +76,28 @@ #if HAS_TMC_UART #define X_SERIAL_TX_PIN PE7 - #define X_SERIAL_RX_PIN PE7 - #define Y_SERIAL_TX_PIN PE15 - #define Y_SERIAL_RX_PIN PE15 - #define Z_SERIAL_TX_PIN PD10 - #define Z_SERIAL_RX_PIN PD10 - #define E0_SERIAL_TX_PIN PD7 - #define E0_SERIAL_RX_PIN PD7 - #define E1_SERIAL_TX_PIN PC14 - #define E1_SERIAL_RX_PIN PC14 - #define E2_SERIAL_TX_PIN PC15 - #define E2_SERIAL_RX_PIN PC15 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define X2_SERIAL_TX_PIN PA15 - #define X2_SERIAL_RX_PIN PA15 + #define X2_SERIAL_RX_PIN X2_SERIAL_TX_PIN + + #define Y_SERIAL_TX_PIN PE15 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + + #define Z_SERIAL_TX_PIN PD10 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define Z2_SERIAL_TX_PIN PD11 - #define Z2_SERIAL_RX_PIN PD11 + #define Z2_SERIAL_RX_PIN Z2_SERIAL_TX_PIN + + #define E0_SERIAL_TX_PIN PD7 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + + #define E1_SERIAL_TX_PIN PC14 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN + + #define E2_SERIAL_TX_PIN PC15 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 3b75e7072a..4adc2f65a2 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -118,37 +118,37 @@ #define X_SERIAL_TX_PIN PB2 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN PB2 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #endif #ifndef Y_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE2 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN PE2 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #endif #ifndef Z_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PE3 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN PE3 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #endif #ifndef E0_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PE4 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN PE4 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PE1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN PE1 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #endif #ifndef EX_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PE0 #endif #ifndef EX_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN PE0 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #endif // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 5c66685629..adc8b2a8bd 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -160,28 +160,28 @@ // No Hardware serial for steppers // #define X_SERIAL_TX_PIN PE6 - #define X_SERIAL_RX_PIN PE6 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PB7 - #define Z_SERIAL_RX_PIN PB7 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PB3 - #define E0_SERIAL_RX_PIN PB3 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD4 - #define E1_SERIAL_RX_PIN PD4 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #define E2_SERIAL_TX_PIN PD0 - #define E2_SERIAL_RX_PIN PD0 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #define E3_SERIAL_TX_PIN PD15 - #define E3_SERIAL_RX_PIN PD15 + #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN #define E4_SERIAL_TX_PIN PD11 - #define E4_SERIAL_RX_PIN PD11 + #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 9193a85511..8008310f5a 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -134,19 +134,19 @@ // No Hardware serial for steppers // #define X_SERIAL_TX_PIN PD5 - #define X_SERIAL_RX_PIN PD5 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD7 - #define Y_SERIAL_RX_PIN PD7 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD4 - #define Z_SERIAL_RX_PIN PD4 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD9 - #define E0_SERIAL_RX_PIN PD9 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD8 - #define E1_SERIAL_RX_PIN PD8 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index c2809c8553..a56889fc7e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -147,24 +147,20 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // - #define X_SERIAL_TX_PIN PD5 - #define X_SERIAL_RX_PIN PD5 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD7 - #define Y_SERIAL_RX_PIN PD7 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD4 - #define Z_SERIAL_RX_PIN PD4 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PD9 - #define E0_SERIAL_RX_PIN PD9 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PD8 - #define E1_SERIAL_RX_PIN PD8 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h index 4dce7b79c0..0b539417d6 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h @@ -67,9 +67,6 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PA3 #define X_SERIAL_RX_PIN PC14 diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index 5e50548c9b..217664e5bc 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -130,16 +130,16 @@ #if HAS_TMC_UART #define X_SERIAL_TX_PIN PB9 - #define X_SERIAL_RX_PIN PB9 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PE3 - #define Y_SERIAL_RX_PIN PE3 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PE12 - #define Z_SERIAL_RX_PIN PE12 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - #define E_SERIAL_TX_PIN PG9 - #define E_SERIAL_RX_PIN PG9 + #define E0_SERIAL_TX_PIN PG9 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #endif // diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h index d85bbf7bed..991c611a89 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h @@ -131,23 +131,20 @@ //#define E6_HARDWARE_SERIAL Serial1 //#define E7_HARDWARE_SERIAL Serial1 - // - // Software serial - // #define X_SERIAL_TX_PIN PG10 - #define X_SERIAL_RX_PIN PG10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN #define Y_SERIAL_TX_PIN PD4 - #define Y_SERIAL_RX_PIN PD4 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD5 - #define Z_SERIAL_RX_PIN PD5 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN #define E0_SERIAL_TX_PIN PI8 - #define E0_SERIAL_RX_PIN PI8 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN PC8 - #define E1_SERIAL_RX_PIN PC8 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 From 536cf287a6f642aa3eccd290b421b0e3869f018a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 21 Aug 2021 18:00:55 -0500 Subject: [PATCH 0571/2168] =?UTF-8?q?=F0=9F=8E=A8=20Misc=20code=20and=20sp?= =?UTF-8?q?acing=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/serial.h | 2 +- Marlin/src/feature/mixing.cpp | 14 +++--- Marlin/src/feature/pause.cpp | 9 ++-- Marlin/src/feature/probe_temp_comp.cpp | 8 +--- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/feature/camera/M240.cpp | 13 +----- .../src/gcode/feature/fwretract/G10_G11.cpp | 11 +---- Marlin/src/gcode/feature/pause/M701_M702.cpp | 4 +- Marlin/src/gcode/parser.h | 3 +- Marlin/src/gcode/queue.cpp | 12 +---- Marlin/src/inc/Version.h | 12 ++--- .../dogm/u8g_dev_tft_upscale_from_128x64.cpp | 4 +- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 4 +- Marlin/src/lcd/menu/menu_ubl.cpp | 4 +- Marlin/src/module/planner.cpp | 44 +++++-------------- Marlin/src/module/settings.cpp | 8 +--- Marlin/src/module/stepper.cpp | 10 ++--- Marlin/src/module/stepper/trinamic.h | 30 ++++++------- Marlin/src/module/temperature.cpp | 10 ++--- Marlin/src/module/tool_change.cpp | 12 ++--- .../src/sd/usb_flashdrive/lib-uhs2/max3421e.h | 2 +- .../UHS_host/USB_HOST_SHIELD/UHS_max3421e.h | 12 ++--- .../USB_HOST_SHIELD/USB_HOST_SHIELD.h | 4 +- 24 files changed, 79 insertions(+), 159 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index dfcf23ddb6..a3d640ee1a 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -88,7 +88,7 @@ extern uint8_t marlin_debug_flags; #if HAS_MULTI_SERIAL #define _PORT_REDIRECT(n,p) REMEMBER(n,multiSerial.portMask,p) #define _PORT_RESTORE(n,p) RESTORE(n) - #define SERIAL_ASSERT(P) if(multiSerial.portMask!=(P)){ debugger(); } + #define SERIAL_ASSERT(P) if (multiSerial.portMask!=(P)) { debugger(); } // If we have a catchall, use that directly #ifdef SERIAL_CATCHALL #define _SERIAL_LEAF_2 SERIAL_CATCHALL diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 332a4f3740..0013797ad5 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -169,14 +169,12 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= #include "../module/planner.h" gradient_t Mixer::gradient = { - false, // enabled - {0}, // color (array) - 0, 0, // start_z, end_z - 0, 1, // start_vtool, end_vtool - {0}, {0} // start_mix[], end_mix[] - #if ENABLED(GRADIENT_VTOOL) - , -1 // vtool_index - #endif + false, // enabled + {0}, // color (array) + 0, 0, // start_z, end_z + 0, 1, // start_vtool, end_vtool + {0}, {0} // start_mix[], end_mix[] + OPTARG(GRADIENT_VTOOL, -1) // vtool_index }; float Mixer::prev_z; // = 0 diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 94c564a9aa..d24a60a0b0 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -191,13 +191,14 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; // LCD click or M108 will clear this + + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); + #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, active_extruder); host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Load Filament T"), tool, CONTINUE_STR); #endif - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); - while (wait_for_user) { impatient_beep(max_beep_count); idle_no_sleep(); @@ -237,8 +238,8 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); @@ -272,7 +273,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load #endif // Keep looping if "Purge More" was selected - } while (TERN0(M600_PURGE_MORE_RESUMABLE, show_lcd && pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); + } while (TERN0(M600_PURGE_MORE_RESUMABLE, pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE)); #endif TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end()); diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index e39896d4dc..6f2dad58b9 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -38,16 +38,12 @@ int16_t ProbeTempComp::z_offsets_probe[cali_info_init[TSI_PROBE].measurements], int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { ProbeTempComp::z_offsets_probe, ProbeTempComp::z_offsets_bed - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - , ProbeTempComp::z_offsets_ext - #endif + OPTARG(USE_TEMP_EXT_COMPENSATION, ProbeTempComp::z_offsets_ext) }; const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { cali_info_init[TSI_PROBE], cali_info_init[TSI_BED] - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - , cali_info_init[TSI_EXT] - #endif + OPTARG(USE_TEMP_EXT_COMPENSATION, cali_info_init[TSI_EXT]) }; constexpr xyz_pos_t ProbeTempComp::park_point; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 29009c6e2d..c3c8d3c92b 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -878,9 +878,7 @@ G29_TYPE GcodeSuite::G29() { // Sync the planner from the current_position if (planner.leveling_active) sync_plan_position(); - #if HAS_BED_PROBE - probe.move_z_after_probing(); - #endif + TERN_(HAS_BED_PROBE, probe.move_z_after_probing()); #ifdef Z_PROBE_END_SCRIPT if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index f5c910a9e9..19051ffd42 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -135,17 +135,8 @@ void GcodeSuite::M240() { }; #ifdef PHOTO_RETRACT_MM - const float rval = parser.seenval('R') ? parser.value_linear_units() : _PHOTO_RETRACT_MM; - feedRate_t sval = ( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - PAUSE_PARK_RETRACT_FEEDRATE - #elif ENABLED(FWRETRACT) - RETRACT_FEEDRATE - #else - 45 - #endif - ); - if (parser.seenval('S')) sval = parser.value_feedrate(); + const float rval = parser.linearval('R', _PHOTO_RETRACT_MM); + const feedRate_t sval = parser.feedrateval('S', TERN(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_RETRACT_FEEDRATE, TERN(FWRETRACT, RETRACT_FEEDRATE, 45))); e_move_m240(-rval, sval); #endif diff --git a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp index 219502f28a..35330fe0ac 100644 --- a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp +++ b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp @@ -32,16 +32,7 @@ * G10 - Retract filament according to settings of M207 * TODO: Handle 'G10 P' for tool settings and 'G10 L' for workspace settings */ -void GcodeSuite::G10() { - #if HAS_MULTI_EXTRUDER - const bool rs = parser.boolval('S'); - #endif - fwretract.retract(true - #if HAS_MULTI_EXTRUDER - , rs - #endif - ); -} +void GcodeSuite::G10() { fwretract.retract(true OPTARG(HAS_MULTI_EXTRUDER, parser.boolval('S'))); } /** * G11 - Recover filament according to settings of M208 diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 0a649dadd4..d46bb234bc 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -114,9 +114,7 @@ void GcodeSuite::M701() { true, // show_lcd thermalManager.still_heating(target_extruder), // pause_for_user PAUSE_MODE_LOAD_FILAMENT // pause_mode - #if ENABLED(DUAL_X_CARRIAGE) - , target_extruder // Dual X target - #endif + OPTARG(DUAL_X_CARRIAGE, target_extruder) // Dual X target ); #endif diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 08cf10004a..a819de6127 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -416,7 +416,8 @@ public: static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } static inline float axisunitsval(const char c, const AxisEnum a, const float dval=0) { return seenval(c) ? value_axis_units(a) : dval; } - static inline celsius_t celsiusval(const char c, const float dval=0) { return seenval(c) ? value_celsius() : dval; } + static inline celsius_t celsiusval(const char c, const celsius_t dval=0) { return seenval(c) ? value_celsius() : dval; } + static inline feedRate_t feedrateval(const char c, const feedRate_t dval=0) { return seenval(c) ? value_feedrate() : dval; } #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index fa83c82ddc..37acc8d58c 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -118,11 +118,7 @@ bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ ) { if (*cmd == ';' || length >= BUFSIZE) return false; strcpy(commands[index_w].buffer, cmd); - commit_command(skip_ok - #if HAS_MULTI_SERIAL - , serial_ind - #endif - ); + commit_command(skip_ok OPTARG(HAS_MULTI_SERIAL, serial_ind)); return true; } @@ -538,11 +534,7 @@ void GCodeQueue::get_serial_commands() { #endif // Add the command to the queue - ring_buffer.enqueue(serial.line_buffer, false - #if HAS_MULTI_SERIAL - , p - #endif - ); + ring_buffer.enqueue(serial.line_buffer, false OPTARG(HAS_MULTI_SERIAL, p)); } else process_stream_char(serial_char, serial.input_state, serial.line_buffer, serial.count); diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index abebd0742b..6bbcca1457 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -105,18 +105,18 @@ * Currently only supported by DUE platform */ #ifndef USB_DEVICE_VENDOR_ID - #define USB_DEVICE_VENDOR_ID 0x03EB /* ATMEL VID */ + #define USB_DEVICE_VENDOR_ID 0x03EB /* ATMEL VID */ #endif #ifndef USB_DEVICE_PRODUCT_ID - #define USB_DEVICE_PRODUCT_ID 0x2424 /* MSC / CDC */ + #define USB_DEVICE_PRODUCT_ID 0x2424 /* MSC / CDC */ #endif //! USB Device string definitions (Optional) #ifndef USB_DEVICE_MANUFACTURE_NAME - #define USB_DEVICE_MANUFACTURE_NAME WEBSITE_URL + #define USB_DEVICE_MANUFACTURE_NAME WEBSITE_URL #endif #ifdef CUSTOM_MACHINE_NAME - #define USB_DEVICE_PRODUCT_NAME CUSTOM_MACHINE_NAME + #define USB_DEVICE_PRODUCT_NAME CUSTOM_MACHINE_NAME #else - #define USB_DEVICE_PRODUCT_NAME MACHINE_NAME + #define USB_DEVICE_PRODUCT_NAME MACHINE_NAME #endif -#define USB_DEVICE_SERIAL_NAME "123985739853" +#define USB_DEVICE_SERIAL_NAME "123985739853" diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index b0cb59a12c..9b5f206fa9 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -390,9 +390,7 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u LOOP_L_N(y, PAGE_HEIGHT) { uint32_t k = 0; - #if HAS_LCD_IO - buffer = (y & 1) ? bufferB : bufferA; - #endif + TERN_(HAS_LCD_IO, buffer = (y & 1) ? bufferB : bufferA); for (uint16_t i = 0; i < (uint32_t)pb->width; i++) { const uint8_t b = *(((uint8_t *)pb->buf) + i); const uint16_t c = TEST(b, y) ? TFT_MARLINUI_COLOR : TFT_MARLINBG_COLOR; diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 55546caaf1..589821e23a 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -64,7 +64,7 @@ namespace ExtUI { ScreenHandler.SetupConfirmAction(setUserConfirmed); ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); } - else if (ScreenHandler.getCurrentScreen() == DGUSLCD_SCREEN_POPUP ) { + else if (ScreenHandler.getCurrentScreen() == DGUSLCD_SCREEN_POPUP) { ScreenHandler.SetupConfirmAction(nullptr); ScreenHandler.PopToOldScreen(); } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 467aa9a4eb..8834ee6eac 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -569,9 +569,7 @@ void menu_advanced_settings() { SUBMENU(MSG_JERK, menu_advanced_jerk); #elif HAS_JUNCTION_DEVIATION EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, 0.3f - #if ENABLED(LIN_ADVANCE) - , planner.recalculate_max_e_jerk - #endif + OPTARG(LIN_ADVANCE, planner.recalculate_max_e_jerk) ); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 467bd81acf..dae2c42047 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -192,9 +192,7 @@ void _lcd_ubl_edit_mesh() { char ubl_lcd_gcode[20]; sprintf_P(ubl_lcd_gcode, PSTR("G28\nG26CPH%" PRIi16 TERN_(HAS_HEATED_BED, "B%" PRIi16)) , custom_hotend_temp - #if HAS_HEATED_BED - , custom_bed_temp - #endif + OPTARG(HAS_HEATED_BED, custom_bed_temp) ); queue.inject(ubl_lcd_gcode); } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e4649b9410..00173e9ad1 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1388,9 +1388,7 @@ void Planner::check_axes_activity() { // Update Fan speeds // Only if synchronous M106/M107 is disabled // - #if HAS_TAIL_FAN_SPEED - sync_fan_speeds(tail_fan_speed); - #endif + TERN_(HAS_TAIL_FAN_SPEED, sync_fan_speeds(tail_fan_speed)); TERN_(AUTOTEMP, autotemp_task()); @@ -1585,11 +1583,7 @@ void Planner::check_axes_activity() { raw.z += ( #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(raw - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , fade_scaling_factor - #endif - ) + mbl.get_z(raw OPTARG(ENABLE_LEVELING_FADE_HEIGHT, fade_scaling_factor)) #elif ENABLED(AUTO_BED_LEVELING_UBL) fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -1622,11 +1616,7 @@ void Planner::check_axes_activity() { raw.z -= ( #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(raw - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , fade_scaling_factor - #endif - ) + mbl.get_z(raw OPTARG(ENABLE_LEVELING_FADE_HEIGHT, fade_scaling_factor)) #elif ENABLED(AUTO_BED_LEVELING_UBL) fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -1811,12 +1801,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target // Fill the block with the specified movement if (!_populate_block(block, false, target - #if HAS_POSITION_FLOAT - , target_float - #endif - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, target_float) + OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) , fr_mm_s, extruder, millimeters )) { // Movement was not queued, probably because it was too short. @@ -1975,9 +1961,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif #endif - #if HAS_EXTRUDERS - if (de < 0) SBI(dm, E_AXIS); - #endif + TERN_(HAS_EXTRUDERS, if (de < 0) SBI(dm, E_AXIS)); #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; @@ -2075,9 +2059,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ); #endif - #if HAS_EXTRUDERS - steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; - #endif + TERN_(HAS_EXTRUDERS, steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); @@ -2162,9 +2144,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->e_to_p_pressure = baricuda_e_to_p_pressure; #endif - #if HAS_MULTI_EXTRUDER - block->extruder = extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); #if ENABLED(AUTO_POWER_CONTROL) if (LINEAR_AXIS_GANG( @@ -2986,12 +2966,8 @@ bool Planner::buffer_segment(const abce_pos_t &abce // Queue the movement. Return 'false' if the move was not queued. if (!_buffer_steps(target - #if HAS_POSITION_FLOAT - , target_float - #endif - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, target_float) + OPTARG(HAS_DIST_MM_ARG, cart_dist_mm) , fr_mm_s, extruder, millimeters) ) return false; diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 47c1314e28..fca33c98c2 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2555,9 +2555,7 @@ void MarlinSettings::reset() { TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK); #endif - #if HAS_JUNCTION_DEVIATION - planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM); - #endif + TERN_(HAS_JUNCTION_DEVIATION, planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM)); #if HAS_SCARA_OFFSET scara_home_offset.reset(); @@ -3151,9 +3149,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING( "Advanced: B S T" - #if HAS_JUNCTION_DEVIATION - " J" - #endif + TERN_(HAS_JUNCTION_DEVIATION, " J") #if HAS_CLASSIC_JERK " X Y Z" TERN_(HAS_CLASSIC_E_JERK, " E") diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b8fdaa5f76..882f5efc35 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1428,14 +1428,10 @@ void Stepper::isr() { // Get the interval to the next ISR call const uint32_t interval = _MIN( + uint32_t(HAL_TIMER_TYPE_MAX), // Come back in a very long time nextMainISR // Time until the next Pulse / Block phase - #if ENABLED(LIN_ADVANCE) - , nextAdvanceISR // Come back early for Linear Advance? - #endif - #if ENABLED(INTEGRATED_BABYSTEPPING) - , nextBabystepISR // Come back early for Babystepping? - #endif - , uint32_t(HAL_TIMER_TYPE_MAX) // Come back in a very long time + OPTARG(LIN_ADVANCE, nextAdvanceISR) // Come back early for Linear Advance? + OPTARG(INTEGRATED_BABYSTEPPING, nextBabystepISR) // Come back early for Babystepping? ); // diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 766f8fced2..7957a1b353 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -121,7 +121,7 @@ void reset_trinamic_drivers(); #define X_ENABLE_READ() stepperX.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(X) - #define X_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(X_STEP_PIN); }while(0) + #define X_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(X_STEP_PIN); }while(0) #endif #endif @@ -149,7 +149,7 @@ void reset_trinamic_drivers(); #define Z_ENABLE_READ() stepperZ.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(Z) - #define Z_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z_STEP_PIN); }while(0) + #define Z_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z_STEP_PIN); }while(0) #endif #endif @@ -166,7 +166,7 @@ void reset_trinamic_drivers(); #define X2_ENABLE_READ() stepperX2.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(X2) - #define X2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(X2_STEP_PIN); }while(0) + #define X2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(X2_STEP_PIN); }while(0) #endif #endif @@ -183,7 +183,7 @@ void reset_trinamic_drivers(); #define Y2_ENABLE_READ() stepperY2.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(Y2) - #define Y2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Y2_STEP_PIN); }while(0) + #define Y2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Y2_STEP_PIN); }while(0) #endif #endif @@ -200,7 +200,7 @@ void reset_trinamic_drivers(); #define Z2_ENABLE_READ() stepperZ2.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(Z2) - #define Z2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z2_STEP_PIN); }while(0) + #define Z2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z2_STEP_PIN); }while(0) #endif #endif @@ -217,7 +217,7 @@ void reset_trinamic_drivers(); #define Z3_ENABLE_READ() stepperZ3.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(Z3) - #define Z3_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z3_STEP_PIN); }while(0) + #define Z3_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z3_STEP_PIN); }while(0) #endif #endif @@ -234,7 +234,7 @@ void reset_trinamic_drivers(); #define Z4_ENABLE_READ() stepperZ4.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(Z4) - #define Z4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z4_STEP_PIN); }while(0) + #define Z4_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z4_STEP_PIN); }while(0) #endif #endif @@ -293,7 +293,7 @@ void reset_trinamic_drivers(); #define E0_ENABLE_READ() stepperE0.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E0) - #define E0_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E0_STEP_PIN); }while(0) + #define E0_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E0_STEP_PIN); }while(0) #endif #endif @@ -310,7 +310,7 @@ void reset_trinamic_drivers(); #define E1_ENABLE_READ() stepperE1.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E1) - #define E1_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E1_STEP_PIN); }while(0) + #define E1_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E1_STEP_PIN); }while(0) #endif #endif @@ -327,7 +327,7 @@ void reset_trinamic_drivers(); #define E2_ENABLE_READ() stepperE2.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E2) - #define E2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E2_STEP_PIN); }while(0) + #define E2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E2_STEP_PIN); }while(0) #endif #endif @@ -344,7 +344,7 @@ void reset_trinamic_drivers(); #define E3_ENABLE_READ() stepperE3.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E3) - #define E3_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E3_STEP_PIN); }while(0) + #define E3_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E3_STEP_PIN); }while(0) #endif #endif @@ -361,7 +361,7 @@ void reset_trinamic_drivers(); #define E4_ENABLE_READ() stepperE4.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E4) - #define E4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E4_STEP_PIN); }while(0) + #define E4_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E4_STEP_PIN); }while(0) #endif #endif @@ -378,7 +378,7 @@ void reset_trinamic_drivers(); #define E5_ENABLE_READ() stepperE5.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E5) - #define E5_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E5_STEP_PIN); }while(0) + #define E5_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E5_STEP_PIN); }while(0) #endif #endif @@ -395,7 +395,7 @@ void reset_trinamic_drivers(); #define E6_ENABLE_READ() stepperE6.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E6) - #define E6_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E6_STEP_PIN); }while(0) + #define E6_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E6_STEP_PIN); }while(0) #endif #endif @@ -412,6 +412,6 @@ void reset_trinamic_drivers(); #define E7_ENABLE_READ() stepperE7.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(E7) - #define E7_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E7_STEP_PIN); }while(0) + #define E7_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E7_STEP_PIN); }while(0) #endif #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 52d0dfb56e..0475db486c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2288,9 +2288,7 @@ void Temperature::init() { INIT_FAN_PIN(CONTROLLER_FAN_PIN); #endif - #if HAS_MAXTC_SW_SPI - max_tc_spi.init(); - #endif + TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); HAL_adc_init(); @@ -3037,15 +3035,15 @@ void Temperature::isr() { #endif #if HAS_HEATED_BED - _PWM_MOD(BED,soft_pwm_bed,temp_bed); + _PWM_MOD(BED, soft_pwm_bed, temp_bed); #endif #if HAS_HEATED_CHAMBER - _PWM_MOD(CHAMBER,soft_pwm_chamber,temp_chamber); + _PWM_MOD(CHAMBER, soft_pwm_chamber, temp_chamber); #endif #if HAS_COOLER - _PWM_MOD(COOLER,soft_pwm_cooler,temp_cooler); + _PWM_MOD(COOLER, soft_pwm_cooler, temp_cooler); #endif #if ENABLED(FAN_SOFT_PWM) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 6d69b8722d..8fffb2e640 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -918,9 +918,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. if (ok) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; - #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position.z, soft_endstop.max.z); - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, NOMORE(current_position.z, soft_endstop.max.z)); fast_line_to_current(Z_AXIS); planner.synchronize(); } @@ -1068,9 +1066,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; - #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position.z, soft_endstop.max.z); - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, NOMORE(current_position.z, soft_endstop.max.z)); fast_line_to_current(Z_AXIS); planner.synchronize(); } @@ -1117,9 +1113,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; - #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position.z, soft_endstop.max.z); - #endif + TERN_(HAS_SOFTWARE_ENDSTOPS, NOMORE(current_position.z, soft_endstop.max.z)); fast_line_to_current(Z_AXIS); } #endif diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/max3421e.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/max3421e.h index 6cad39d0df..f7eb9adf06 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/max3421e.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/max3421e.h @@ -67,7 +67,7 @@ #define rCPUCTL 0x80 //16<<3 /* CPUCTL Bits */ -#define bmPUSLEWID1 0x80 //b7 +#define bmPULSEWID1 0x80 //b7 #define bmPULSEWID0 0x40 //b6 #define bmIE 0x01 //b0 diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/UHS_max3421e.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/UHS_max3421e.h index 8ecafd4ad8..841cc8fe75 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/UHS_max3421e.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/UHS_max3421e.h @@ -59,19 +59,19 @@ e-mail : support@circuitsathome.com // (CPUCTL) #define rCPUCTL 0x80 //16<<3 -#define bmPUSLEWID1 0x80 //b7 +#define bmPULSEWID1 0x80 //b7 #define bmPULSEWID0 0x40 //b6 #define bmIE 0x01 //b0 -// bmPUSLEWID1 bmPULSEWID0 Pulse width +// bmPULSEWID1 bmPULSEWID0 Pulse width // 0 0 10.6uS // 0 1 5.3uS // 1 0 2.6uS // 1 1 1.3uS -#define PUSLEWIDTH10_6 (0) -#define PUSLEWIDTH5_3 (bmPULSEWID0) -#define PUSLEWIDTH2_6 (bmPUSLEWID1) -#define PUSLEWIDTH1_3 (bmPULSEWID0 | bmPUSLEWID1) +#define PULSEWIDTH10_6 (0) +#define PULSEWIDTH5_3 (bmPULSEWID0) +#define PULSEWIDTH2_6 (bmPULSEWID1) +#define PULSEWIDTH1_3 (bmPULSEWID0 | bmPULSEWID1) // (PINCTL) #define rPINCTL 0x88 //17<<3 diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h index 7d17d626c1..79c06a492b 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h @@ -272,11 +272,11 @@ e-mail : support@circuitsathome.com // #define IRQ_SENSE FALLING #ifdef ARDUINO_ARCH_PIC32 -//#define bmPULSEWIDTH PUSLEWIDTH10_6 +//#define bmPULSEWIDTH PULSEWIDTH10_6 #define bmPULSEWIDTH 0 #define bmIRQ_SENSE 0 #else -#define bmPULSEWIDTH PUSLEWIDTH1_3 +#define bmPULSEWIDTH PULSEWIDTH1_3 #define bmIRQ_SENSE 0 #endif #else From 34e6940aabd6645109b497c04f8733a1d205b35c Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 22 Aug 2021 11:05:39 +1200 Subject: [PATCH 0572/2168] =?UTF-8?q?=E2=9C=A8=20BOARD=5FRUMBA32=5FBTT=20(?= =?UTF-8?q?#22607)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 55 +++++++-------- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 1 - Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h | 1 - Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h | 68 +++++++++++++++++++ Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 1 - 6 files changed, 98 insertions(+), 30 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 2ed5859199..8e84f0b967 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -365,33 +365,34 @@ #define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VET6 based controller from Aus3D #define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VET6 based controller from Aus3D #define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VET6 based controller from Makerbase -#define BOARD_BLACK_STM32F407VE 4204 // BLACK_STM32F407VE -#define BOARD_BLACK_STM32F407ZE 4205 // BLACK_STM32F407ZE -#define BOARD_STEVAL_3DP001V1 4206 // STEVAL-3DP001V1 3D PRINTER BOARD -#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZGT6) -#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6) -#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VGT6) -#define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VGT6) -#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) -#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) -#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6) -#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZET6) -#define BOARD_LERDGE_K 4216 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4217 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4218 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4219 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6) -#define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6) -#define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4223 // FLYmaker FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_MONSTER8 4227 // MKS Monster8 (STM32F407VGT6) -#define BOARD_ANET_ET4 4228 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4229 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4230 // FYSETC Cheetah V2.0 +#define BOARD_RUMBA32_BTT 4204 // RUMBA32 STM32F446VET6 based controller from BIGTREETECH +#define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE +#define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE +#define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD +#define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZGT6) +#define BOARD_BTT_SKR_PRO_V1_2 4209 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6) +#define BOARD_BTT_BTT002_V1_0 4210 // BigTreeTech BTT002 v1.0 (STM32F407VGT6) +#define BOARD_BTT_E3_RRF 4211 // BigTreeTech E3 RRF (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_A 4212 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_B 4213 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) +#define BOARD_BTT_GTR_V1_0 4214 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_BTT_OCTOPUS_V1_0 4215 // BigTreeTech Octopus v1.0 (STM32F446ZET6) +#define BOARD_BTT_OCTOPUS_V1_1 4216 // BigTreeTech Octopus v1.1 (STM32F446ZET6) +#define BOARD_LERDGE_K 4217 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4218 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4219 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4220 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4221 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4222 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4223 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4224 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4225 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4226 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4227 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_MONSTER8 4228 // MKS Monster8 (STM32F407VGT6) +#define BOARD_ANET_ET4 4229 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4230 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4231 // FYSETC Cheetah V2.0 // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 28c7ed0071..0655580f0f 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -587,6 +587,8 @@ #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32 #elif MB(RUMBA32_MKS) #include "stm32f4/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32 +#elif MB(RUMBA32_BTT) + #include "stm32f4/pins_RUMBA32_BTT.h" // STM32F4 env:rumba32 #elif MB(BLACK_STM32F407VE) #include "stm32f4/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black #elif MB(STEVAL_3DP001V1) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 986cd7feaa..c9f528b87b 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -195,7 +195,6 @@ // Misc. Functions // //#define LED_PIN PB14 -//#define BTN_PIN PC10 //#define PS_ON_PIN PE11 //#define KILL_PIN PC5 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h index a60a278149..f2073457b1 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_AUS3D.h @@ -51,7 +51,6 @@ #if MB(RUMBA32_V1_1) #define SERVO0_PIN PA15 - #undef BTN_PIN #if HAS_TMC_UART // diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h new file mode 100644 index 0000000000..b12f4737b7 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h @@ -0,0 +1,68 @@ +/** + * 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 . + * + */ + +/** + * No offical schematics have been found. + * But these differences where noted in https://github.com/bigtreetech/Rumba32/issues/1 + */ + +#pragma once + +#define BOARD_INFO_NAME "RUMBA32 (BTT)" + +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24LC64T-I/OT) +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#endif + +#include "pins_RUMBA32_common.h" + +#define SERVO0_PIN PA15 // Pin is not broken out, is a test point only. + +#if HAS_TMC_UART + // + // TMC2208/TMC2209 Software Serial + // + #define X_SERIAL_TX_PIN PC14 // BTT Rumba32 only uses 1 pin for UART + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + + #define Y_SERIAL_TX_PIN PE4 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + + #define Z_SERIAL_TX_PIN PE0 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + + #define E0_SERIAL_TX_PIN PC13 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + + #define E1_SERIAL_TX_PIN PD5 + #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN + + #define E2_SERIAL_TX_PIN PD1 + #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN +#endif diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 7bf148874c..03d8d19e94 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -134,7 +134,6 @@ // Misc. Functions // #define LED_PIN PB14 -#define BTN_PIN PC10 #define PS_ON_PIN PE11 #define KILL_PIN PC5 From 7d416bd055e3ccddf765208b2937dcc1fcd4ea8b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 22 Aug 2021 05:25:07 -0500 Subject: [PATCH 0573/2168] =?UTF-8?q?=E2=9C=A8=20MarlinUI=20for=20Ender=20?= =?UTF-8?q?3=20v2=20DWIN=20LCD=20(#22594)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: Taylor Talkington --- Marlin/Configuration.h | 6 + Marlin/Configuration_adv.h | 24 +- Marlin/src/feature/pause.cpp | 4 +- Marlin/src/inc/Conditionals_LCD.h | 7 +- Marlin/src/inc/Conditionals_post.h | 6 +- Marlin/src/inc/SanityCheck.h | 7 +- Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp | 470 + Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h | 302 + Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp | 180 + Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 1007 ++ .../src/lcd/e3v2/marlinui/lcdprint_dwin.cpp | 193 + Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h | 30 + Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h | 146 + Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 595 + .../lcd/e3v2/marlinui/ui_status_480x272.cpp | 391 + Marlin/src/lcd/lcdprint.cpp | 2 +- Marlin/src/lcd/lcdprint.h | 21 +- Marlin/src/lcd/marlinui.cpp | 8 + Marlin/src/lcd/marlinui.h | 26 +- Marlin/src/lcd/menu/menu.cpp | 2 + Marlin/src/lcd/menu/menu.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 4 +- buildroot/share/fonts/buildhzk.py | 64 + buildroot/share/fonts/marlin-10x20.bdf | 4104 +++++++ buildroot/share/fonts/marlin-12x24.bdf | 4558 ++++++++ buildroot/share/fonts/marlin-14x28.bdf | 5078 +++++++++ buildroot/share/fonts/marlin-16x32.bdf | 5492 +++++++++ buildroot/share/fonts/marlin-20x40.bdf | 6458 +++++++++++ buildroot/share/fonts/marlin-24x48.bdf | 6462 +++++++++++ buildroot/share/fonts/marlin-28x56.bdf | 7311 ++++++++++++ buildroot/share/fonts/marlin-32x64.bdf | 9870 +++++++++++++++++ buildroot/share/fonts/marlin-8x16.bdf | 3701 ++++++ buildroot/tests/STM32F103RET6_creality | 6 +- ini/features.ini | 1 + platformio.ini | 3 +- 35 files changed, 56500 insertions(+), 41 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp create mode 100644 Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h create mode 100644 Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp create mode 100644 Marlin/src/lcd/e3v2/marlinui/dwin_string.h create mode 100644 Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp create mode 100644 Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h create mode 100644 Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h create mode 100644 Marlin/src/lcd/e3v2/marlinui/ui_common.cpp create mode 100644 Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp create mode 100644 buildroot/share/fonts/buildhzk.py create mode 100644 buildroot/share/fonts/marlin-10x20.bdf create mode 100644 buildroot/share/fonts/marlin-12x24.bdf create mode 100644 buildroot/share/fonts/marlin-14x28.bdf create mode 100644 buildroot/share/fonts/marlin-16x32.bdf create mode 100644 buildroot/share/fonts/marlin-20x40.bdf create mode 100644 buildroot/share/fonts/marlin-24x48.bdf create mode 100644 buildroot/share/fonts/marlin-28x56.bdf create mode 100644 buildroot/share/fonts/marlin-32x64.bdf create mode 100644 buildroot/share/fonts/marlin-8x16.bdf diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 763c143158..ac98b1b322 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2746,6 +2746,12 @@ // //#define DWIN_CREALITY_LCD +// +// MarlinUI for Creality's DWIN display (and others) +// +//#define DWIN_MARLINUI_PORTRAIT +//#define DWIN_MARLINUI_LANDSCAPE + // // Touch Screen Settings // diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2eecc0adb3..8a07b5c97b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1306,7 +1306,7 @@ // LCD Print Progress options #if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - #if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + #if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI) //#define SHOW_REMAINING_TIME // Display estimated time to completion #if ENABLED(SHOW_REMAINING_TIME) //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation @@ -1579,16 +1579,10 @@ * printing performance versus fast display updates. */ #if HAS_MARLINUI_U8GLIB - // Show SD percentage next to the progress bar - //#define SHOW_SD_PERCENT - // Save many cycles by drawing a hollow frame or no frame on the Info Screen //#define XYZ_NO_FRAME #define XYZ_HOLLOW_FRAME - // Enable to save many cycles by drawing a hollow frame on Menu Screens - #define MENU_HOLLOW_FRAME - // A bigger font is available for edit items. Costs 3120 bytes of PROGMEM. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_BIG_EDIT_FONT @@ -1597,9 +1591,6 @@ // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - // Swap the CW/CCW indicators in the graphics overlay - //#define OVERLAY_GFX_REVERSE - /** * ST7920-based LCDs can emulate a 16 x 4 character display using * the ST7920 character-generator for very fast screen updates. @@ -1651,6 +1642,17 @@ #endif // HAS_MARLINUI_U8GLIB +#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI + // Show SD percentage next to the progress bar + //#define SHOW_SD_PERCENT + + // Enable to save many cycles by drawing a hollow frame on Menu Screens + #define MENU_HOLLOW_FRAME + + // Swap the CW/CCW indicators in the graphics overlay + //#define OVERLAY_GFX_REVERSE +#endif + // // Additional options for DGUS / DWIN displays // @@ -1716,7 +1718,7 @@ // // Specify additional languages for the UI. Default specified by LCD_LANGUAGE. // -#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE) +#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) //#define LCD_LANGUAGE_2 fr //#define LCD_LANGUAGE_3 de //#define LCD_LANGUAGE_4 es diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index d24a60a0b0..79a8af66e2 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -238,8 +238,8 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."))); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 137b9fce3e..c4309db144 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -488,7 +488,10 @@ #define HAS_MARLINUI_U8GLIB 1 #elif IS_TFTGLCD_PANEL // Neither DOGM nor HD44780. Fully customized interface. - #elif DISABLED(HAS_GRAPHICAL_TFT) + #elif IS_DWIN_MARLINUI + // Since HAS_MARLINUI_U8GLIB refers to U8G displays + // the DWIN display can define its own flags + #elif !HAS_GRAPHICAL_TFT #define HAS_MARLINUI_HD44780 1 #endif #endif @@ -1087,7 +1090,7 @@ #define HAS_ETHERNET 1 #endif -#if ENABLED(DWIN_CREALITY_LCD) +#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) #define SERIAL_CATCHALL 0 #ifndef LCD_SERIAL_PORT #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 04848bd0d6..20243ae0ea 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -461,7 +461,7 @@ #endif -#if ANY(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT) || !PIN_EXISTS(SD_DETECT) +#if ANY(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT, IS_DWIN_MARLINUI) || !PIN_EXISTS(SD_DETECT) #define NO_LCD_REINIT 1 // Suppress LCD re-initialization #endif @@ -3258,6 +3258,8 @@ #ifndef LCD_WIDTH #if HAS_MARLINUI_U8GLIB #define LCD_WIDTH 21 + #elif IS_DWIN_MARLINUI + // Defined by header #else #define LCD_WIDTH TERN(IS_ULTIPANEL, 20, 16) #endif @@ -3265,6 +3267,8 @@ #ifndef LCD_HEIGHT #if HAS_MARLINUI_U8GLIB #define LCD_HEIGHT 5 + #elif IS_DWIN_MARLINUI + // Defined by header #else #define LCD_HEIGHT TERN(IS_ULTIPANEL, 4, 2) #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 817bce28bc..b679f2cb53 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -798,8 +798,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - #if NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, or EXTENSIBLE_UI." + #if NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, IS_DWIN_MARLINUI) + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, EXTENSIBLE_UI, OR DWIN MarlinUI." #endif #endif @@ -1721,7 +1721,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !BOTH(AUTO_BED_LEVELING_UBL, HAS_MARLINUI_U8GLIB) +#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !(ENABLED(AUTO_BED_LEVELING_UBL) && EITHER(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI)) #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif @@ -2640,6 +2640,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY, DWIN_CREALITY_LCD) \ + + COUNT_ENABLED(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp new file mode 100644 index 0000000000..97dc0eec42 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp @@ -0,0 +1,470 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/******************************************************************************** + * @file lcd/e3v2/marlinui/dwin_lcd.cpp + * @brief DWIN screen control functions + ********************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if IS_DWIN_MARLINUI + +#include "../../../inc/MarlinConfig.h" + +#include "dwin_lcd.h" +#include // for memset + +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + +// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. +// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. +uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; +uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; +uint8_t databuf[26] = { 0 }; +uint8_t receivedType; + +int recnum = 0; + +inline void DWIN_Byte(size_t &i, const uint16_t bval) { + DWIN_SendBuf[++i] = bval; +} + +inline void DWIN_Word(size_t &i, const uint16_t wval) { + DWIN_SendBuf[++i] = wval >> 8; + DWIN_SendBuf[++i] = wval & 0xFF; +} + +inline void DWIN_Long(size_t &i, const uint32_t lval) { + DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; + DWIN_SendBuf[++i] = lval & 0xFF; +} + +inline void DWIN_String(size_t &i, char * const string) { + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); + memcpy(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { + if (!string) return; + const size_t len = strlen_P((PGM_P)string); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. + if (len == 0) return; + memcpy(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +// Send the data in the buffer and the packet end +inline void DWIN_Send(size_t &i) { + ++i; + LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } +} + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void) { + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + const millis_t serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + + size_t i = 0; + DWIN_Byte(i, 0x00); + DWIN_Send(i); + + while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { + databuf[recnum] = LCD_SERIAL.read(); + // ignore the invalid data + if (databuf[0] != FHONE) { // prevent the program from running. + if (recnum > 0) { + recnum = 0; + ZERO(databuf); + } + continue; + } + delay(10); + recnum++; + } + + return ( recnum >= 3 + && databuf[0] == FHONE + && databuf[1] == '\0' + && databuf[2] == 'O' + && databuf[3] == 'K' ); +} + +void DWIN_Startup(void) { + DEBUG_ECHOPGM("\r\nDWIN handshake "); + delay(750); // Delay here or init later in the boot process + const bool success = DWIN_Handshake(); + if (success) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); + DWIN_Frame_SetDir(TERN(DWIN_MARLINUI_LANDSCAPE, 0, 1)); + DWIN_Frame_Clear(Color_Bg_Black); // MarlinUI handles the bootscreen so just clear here + DWIN_UpdateLCD(); +} + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance) { + size_t i = 0; + DWIN_Byte(i, 0x30); + DWIN_Byte(i, _MAX(luminance, 0x1F)); + DWIN_Send(i); +} + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir) { + size_t i = 0; + DWIN_Byte(i, 0x34); + DWIN_Byte(i, 0x5A); + DWIN_Byte(i, 0xA5); + DWIN_Byte(i, dir); + DWIN_Send(i); +} + +// Update display +void DWIN_UpdateLCD(void) { + size_t i = 0; + DWIN_Byte(i, 0x3D); + DWIN_Send(i); +} + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color) { + size_t i = 0; + DWIN_Byte(i, 0x01); + DWIN_Word(i, color); + DWIN_Send(i); +} + +// Draw a point +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + DWIN_Word(i, color); + DWIN_Byte(i, width); + DWIN_Byte(i, height); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x03); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x05); + DWIN_Byte(i, mode); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x09); + DWIN_Byte(i, (mode << 7) | dir); + DWIN_Word(i, dis); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { + uint8_t widthAdjust = 0; + size_t i = 0; + DWIN_Byte(i, 0x11); + // Bit 7: widthAdjust + // Bit 6: bShow + // Bit 5-4: Unused (0) + // Bit 3-0: size + DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_String(i, string); + DWIN_Send(i); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + size_t i = 0; + DWIN_Byte(i, 0x14); + // Bit 7: bshow + // Bit 6: 1 = signed; 0 = unsigned number; + // Bit 5: zeroFill + // Bit 4: zeroMode + // Bit 3-0: size + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, 0); // fNum + DWIN_Word(i, x); + DWIN_Word(i, y); + #if 0 + for (char count = 0; count < 8; count++) { + DWIN_Byte(i, value); + value >>= 8; + if (!(value & 0xFF)) break; + } + #else + // Write a big-endian 64 bit integer + const size_t p = i + 1; + for (char count = 8; count--;) { // 7..0 + ++i; + DWIN_SendBuf[p + count] = value; + value >>= 8; + } + #endif + + DWIN_Send(i); +} + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + //uint8_t *fvalue = (uint8_t*)&value; + size_t i = 0; + DWIN_Byte(i, 0x14); + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, fNum); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Long(i, value); + /* + DWIN_Byte(i, fvalue[3]); + DWIN_Byte(i, fvalue[2]); + DWIN_Byte(i, fvalue[1]); + DWIN_Byte(i, fvalue[0]); + */ + DWIN_Send(i); +} + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id) { + size_t i = 0; + DWIN_Word(i, 0x2200); + DWIN_Byte(i, id); + DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C +} + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x23); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, 0x80 | libID); + //DWIN_Byte(i, libID); + DWIN_Byte(i, picID); + DWIN_Send(i); +} + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { + size_t i = 0; + DWIN_Byte(i, 0x25); + DWIN_Byte(i, n); + DWIN_Byte(i, id); + DWIN_Send(i); +} + +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x27); + DWIN_Byte(i, 0x80 | cacheID); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Animate a series of icons +// animID: Animation ID; 0x00-0x0F +// animate: true on; false off; +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Bit 7: animation on or off + // Bit 6: start from begin or end + // Bit 5-4: unused (0) + // Bit 3-0: animID + DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); + DWIN_Byte(i, libID); + DWIN_Byte(i, picIDs); + DWIN_Byte(i, picIDe); + DWIN_Byte(i, interval); + DWIN_Send(i); +} + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state) { + size_t i = 0; + DWIN_Byte(i, 0x29); + DWIN_Word(i, state); + DWIN_Send(i); +} + +/*---------------------------------------- Memory functions ----------------------------------------*/ +// The LCD has an additional 32KB SRAM and 16KB Flash + +// Data can be written to the sram and save to one of the jpeg page files + +// Write Data Memory +// command 0x31 +// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Data: data +// +// Flash writing returns 0xA5 0x4F 0x4B + +// Read Data Memory +// command 0x32 +// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Length: leangth of data to read; 0x01-0xF0 +// +// Response: +// Type, Address, Length, Data + +// Write Picture Memory +// Write the contents of the 32KB SRAM data memory into the designated image memory space +// Issued: 0x5A, 0xA5, PIC_ID +// Response: 0xA5 0x4F 0x4B +// +// command 0x33 +// 0x5A, 0xA5 +// PicId: Picture Memory location, 0x00-0x0F +// +// Flash writing returns 0xA5 0x4F 0x4B + +#endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h new file mode 100644 index 0000000000..09d7b5ddd2 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h @@ -0,0 +1,302 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/******************************************************************************** + * @file lcd/e3v2/marlinui/dwin_lcd.h + * @brief DWIN screen control functions + ********************************************************************************/ + +#include + +#define RECEIVED_NO_DATA 0x00 +#define RECEIVED_SHAKE_HAND_ACK 0x01 + +#define FHONE 0xAA + +#define DWIN_SCROLL_UP 2 +#define DWIN_SCROLL_DOWN 3 + +#if DISABLED(DWIN_MARLINUI_LANDSCAPE) + #define DWIN_WIDTH 272 + #define DWIN_HEIGHT 480 +#else + #define DWIN_WIDTH 480 + #define DWIN_HEIGHT 272 +#endif + +// Picture ID +#define DWIN_Boot_Horiz 0 +#define DWIN_Boot_Vert 1 +#define DWIN_MarlinUI_Assets 2 + +/** + * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: + * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 + * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 + */ +#define font6x12 0x00 +#define font8x16 0x01 +#define font10x20 0x02 +#define font12x24 0x03 +#define font14x28 0x04 +#define font16x32 0x05 +#define font20x40 0x06 +#define font24x48 0x07 +#define font28x56 0x08 +#define font32x64 0x09 + +#define DWIN_FONT_MENU font10x20 +#define DWIN_FONT_STAT font14x28 +#define DWIN_FONT_HEAD font10x20 +#define DWIN_FONT_ALERT font14x28 + +// Color +#define Color_White 0xFFFF +#define Color_Yellow 0xFF0F +#define Color_Error_Red 0xB000 // Error! +#define Color_Bg_Red 0xF00F // Red background color +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Heading 0x3344 // Static Heading +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color + +// Character matrix width x height +//#define LCD_WIDTH ((DWIN_WIDTH) / 8) +//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) + +// ICON ID +#define BOOT_ICON 3 // Icon set file 3.ICO +#define ICON 4 // Icon set file 4.ICO + +// MarlinUI Boot Icons +#define ICON_MarlinBoot 0 +#define ICON_OpenSource 1 +#define ICON_GitHubURL 2 +#define ICON_MarlinURL 3 +#define ICON_Copyright 4 + +// MarlinUI Icons +#define ICON_LOGO_Marlin 0 +#define ICON_HotendOff 1 +#define ICON_HotendOn 2 +#define ICON_BedOff 3 +#define ICON_BedOn 4 +#define ICON_Fan0 5 +#define ICON_Fan1 6 +#define ICON_Fan2 7 +#define ICON_Fan3 8 +#define ICON_Halted 9 +#define ICON_Question 10 +#define ICON_Alert 11 +#define ICON_RotateCW 12 +#define ICON_RotateCCW 13 +#define ICON_UpArrow 14 +#define ICON_DownArrow 15 +#define ICON_BedLine 16 + +#define ICON_AdvSet ICON_Language +#define ICON_HomeOff ICON_AdvSet +#define ICON_HomeOffX ICON_StepX +#define ICON_HomeOffY ICON_StepY +#define ICON_HomeOffZ ICON_StepZ +#define ICON_ProbeOff ICON_AdvSet +#define ICON_ProbeOffX ICON_StepX +#define ICON_ProbeOffY ICON_StepY +#define ICON_PIDNozzle ICON_SetEndTemp +#define ICON_PIDbed ICON_SetBedTemp + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void); + +// Common DWIN startup +void DWIN_Startup(void); + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance); + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir); + +// Update display +void DWIN_UpdateLCD(void); + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color); + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); + +class __FlashStringHelper; + +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(bShow, size, color, bColor, x, y, (char *)title); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); + +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID +inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } + +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, + uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp new file mode 100644 index 0000000000..c7b37319c4 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -0,0 +1,180 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfig.h" + +#if IS_DWIN_MARLINUI + +#include "dwin_string.h" +//#include "../../fontutils.h" + +uint8_t DWIN_String::data[]; +uint16_t DWIN_String::span; +uint8_t DWIN_String::len; + +void DWIN_String::set() { + //*data = 0x00; + memset(data, 0x00, sizeof(data)); + span = 0; + len = 0; +} + +uint8_t read_byte(uint8_t *byte) { return *byte; } + +/** + * Add a string, applying substitutions for the following characters: + * + * = displays '0'....'10' for indexes 0 - 10 + * ~ displays '1'....'11' for indexes 0 - 10 + * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + */ +void DWIN_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { + wchar_t wchar; + + while (*string) { + string = get_utf8_value_cb(string, read_byte, &wchar); + if (wchar > 255) wchar |= 0x0080; + uint8_t ch = uint8_t(wchar & 0x00FF); + + if (ch == '=' || ch == '~' || ch == '*') { + if (index >= 0) { + int8_t inum = index + ((ch == '=') ? 0 : LCD_FIRST_TOOL); + if (ch == '*') add_character('E'); + if (inum >= 10) { add_character('0' + (inum / 10)); inum %= 10; } + add_character('0' + inum); + } + else { + add(index == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED)); + } + continue; + } + else if (ch == '$' && itemString) { + add(itemString); + continue; + } + + add_character(ch); + } + eol(); +} + +void DWIN_String::add(uint8_t *string, uint8_t max_len) { + wchar_t wchar; + while (*string && max_len) { + string = get_utf8_value_cb(string, read_byte, &wchar); + /* + if (wchar > 255) wchar |= 0x0080; + uint8_t ch = uint8_t(wchar & 0x00FF); + add_character(ch); + */ + add(wchar); + max_len--; + } + eol(); +} + +void DWIN_String::add(wchar_t character) { + int ret; + size_t idx = 0; + dwin_charmap_t pinval; + dwin_charmap_t *copy_address = nullptr; + pinval.uchar = character; + pinval.idx = -1; + + // For 8-bit ASCII just print the single character + char str[] = { '?', 0 }; + if (character < 255) { + str[0] = (char)character; + } + else { + copy_address = nullptr; + ret = pf_bsearch_r((void *)g_dwin_charmap_device, COUNT(g_dwin_charmap_device), pf_bsearch_cb_comp_dwinmap_pgm, (void *)&pinval, &idx); + if (ret >= 0) { + copy_address = (dwin_charmap_t*)(g_dwin_charmap_device + idx); + } + else { + ret = pf_bsearch_r((void *)g_dwin_charmap_common, COUNT(g_dwin_charmap_common), pf_bsearch_cb_comp_dwinmap_pgm, (void *)&pinval, &idx); + if (ret >= 0) + copy_address = (dwin_charmap_t*)(g_dwin_charmap_common + idx); + } + if (ret >= 0) { + dwin_charmap_t localval; + memcpy_P(&localval, copy_address, sizeof(localval)); + str[0] = localval.idx; + str[1] = localval.idx2; + } + } + if (str[0]) add_character(str[0]); + if (str[1]) add_character(str[1]); +} + +void DWIN_String::add_character(uint8_t character) { + if (len < MAX_STRING_LENGTH) { + data[len] = character; + len++; + //span += glyph(character)->DWidth; + } +} + +void DWIN_String::rtrim(uint8_t character) { + while (len) { + if (data[len - 1] == 0x20 || data[len - 1] == character) { + len--; + //span -= glyph(data[length])->DWidth; + eol(); + } + else + break; + } +} + +void DWIN_String::ltrim(uint8_t character) { + uint16_t i, j; + for (i = 0; (i < len) && (data[i] == 0x20 || data[i] == character); i++) { + //span -= glyph(data[i])->DWidth; + } + if (i == 0) return; + for (j = 0; i < len; data[j++] = data[i++]); + len = j; + eol(); +} + +void DWIN_String::trim(uint8_t character) { + rtrim(character); + ltrim(character); +} + +/* return v1 - v2 */ +int dwin_charmap_compare(dwin_charmap_t *v1, dwin_charmap_t *v2) { + return (v1->uchar < v2->uchar) ? -1 : (v1->uchar > v2->uchar) ? 1 : 0; +} + +int pf_bsearch_cb_comp_dwinmap_pgm(void *userdata, size_t idx, void * data_pin) { + dwin_charmap_t localval; + dwin_charmap_t *p_dwin_charmap = (dwin_charmap_t *)userdata; + memcpy_P(&localval, p_dwin_charmap + idx, sizeof(localval)); + return dwin_charmap_compare(&localval, (dwin_charmap_t *)data_pin); +} + +DWIN_String dwin_string; + +#endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h new file mode 100644 index 0000000000..d78d774095 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -0,0 +1,1007 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + + +#include "../../fontutils.h" +#include "../../marlinui.h" + +typedef struct _dwin_charmap_t { + wchar_t uchar; // the unicode char + uint8_t idx; // the glyph of the char in the ROM + uint8_t idx2; // the char used to be combined with the idx to simulate a single char +} dwin_charmap_t; + +#define MAX_STRING_LENGTH 64 + +#define S(V) (char*)(V) + +class DWIN_String { + private: + //static glyph_t *glyphs[256]; + //static font_t *font_header; + + static uint8_t data[MAX_STRING_LENGTH + 1]; + static uint16_t span; // in pixels + static uint8_t len; // in characters + + static void add_character(uint8_t character); + static void eol() { data[len] = 0x00; } + + public: + //static void set_font(const uint8_t *font); + //static void add_glyphs(const uint8_t *font); + + //static font_t *font() { return font_header; }; + //static uint16_t font_height() { return font_header->FontAscent - font_header->FontDescent; } + //static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ + //static inline glyph_t *glyph(uint8_t *character) { return glyph(*character); } + + static void set(); + //static void add(uint8_t character) { add_character(character); eol(); } + static void add(wchar_t character); + static void add(uint8_t *string, uint8_t max_len=MAX_STRING_LENGTH); + static void add(uint8_t *string, int8_t index, uint8_t *itemString=nullptr); + static void set(uint8_t *string) { set(); add(string); } + static void set(wchar_t character) { set(); add(character); } + static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); } + static inline void set(const __FlashStringHelper *fstring) { set((uint8_t *)fstring); } + static inline void set(const char *string) { set((uint8_t *)string); } + static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } + static inline void add(const char *string) { add((uint8_t *)string); } + + static void trim(uint8_t character=0x20); + static void rtrim(uint8_t character=0x20); + static void ltrim(uint8_t character=0x20); + + static void truncate(uint8_t maxlen) { if (len > maxlen) { len = maxlen; eol(); } } + + static uint8_t length() { return len; } + static uint16_t width() { return span; } + static uint8_t *string() { return data; } + static uint16_t center(uint16_t width) { return span > width ? 0 : (width - span) / 2; } +}; + +int dwin_charmap_compare(dwin_charmap_t *v1, dwin_charmap_t *v2); +int pf_bsearch_cb_comp_dwinmap_pgm(void *userdata, size_t idx, void * data_pin); + +extern DWIN_String dwin_string; + +#ifdef __AVR__ + #define IV(a) U##a +#else + #define IV(a) L##a +#endif + +const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { + // sorted by uchar: + #if DISPLAY_CHARSET_HD44780 == JAPANESE + + {IV('¢'), 0xEC, 0}, // A2 + {IV('°'), 0xDF, 0}, // B0, Marlin special: '°' LCD_STR_DEGREE (0x09) + {IV('ä'), 0xE1, 0}, // E4 + {IV('ö'), 0xEF, 0}, // F6 + {IV('÷'), 0xFD, 0}, // 00F7 + {IV('ü'), 0xF5, 0}, // 00FC + {IV('ˣ'), 0xEB, 0}, // 02E3 + + {IV('·'), 0xA5, 0}, // 0387 + {IV('Ώ'), 0xF4, 0}, // 038F + {IV('Θ'), 0xF2, 0}, // 0398, Theta + {IV('Ξ'), 0xE3, 0}, // 039E, Xi + {IV('Σ'), 0xF6, 0}, // 03A3, Sigma + {IV('Ω'), 0xF4, 0}, // 03A9, Omega + {IV('ά'), 0xE0, 0}, // 03AC + {IV('έ'), 0xE3, 0}, // 03AD + {IV('α'), 0xE0, 0}, // 03B1, alpha + {IV('β'), 0xE2, 0}, // 03B2, beta + {IV('ε'), 0xE3, 0}, // 03B5, epsilon + {IV('θ'), 0xF2, 0}, // 03B8, theta + {IV('μ'), 0xE4, 0}, // 03BC, mu + {IV('ξ'), 0xE3, 0}, // 03BE, xi + {IV('π'), 0xF7, 0}, // 03C0, pi + {IV('ρ'), 0xE6, 0}, // 03C1, rho + {IV('σ'), 0xE5, 0}, // 03C3, sigma + + {IV('←'), 0x7F, 0}, // 2190 + {IV('→'), 0x7E, 0}, // 2192, Marlin special: '⮈⮉⮊⮋➤→' LCD_STR_ARROW_RIGHT (0x03) + {IV('√'), 0xE8, 0}, // 221A + {IV('∞'), 0xF3, 0}, // 221E + {IV('█'), 0xFF, 0}, // 2588 + + //{IV(''), 0xA0, 0}, + {IV('。'), 0xA1, 0}, + {IV('「'), 0xA2, 0}, + {IV('」'), 0xA3, 0}, + {IV('゛'), 0xDE, 0}, // ‶ + {IV('゜'), 0xDF, 0}, // '〫' + {IV('゠'), '=', 0}, + {IV('ァ'), 0xA7, 0}, + {IV('ア'), 0xB1, 0}, + {IV('ィ'), 0xA8, 0}, + {IV('イ'), 0xB2, 0}, + {IV('ゥ'), 0xA9, 0}, + {IV('ウ'), 0xB3, 0}, + {IV('ェ'), 0xAA, 0}, + {IV('エ'), 0xB4, 0}, + {IV('ォ'), 0xAB, 0}, + + {IV('オ'), 0xB5, 0}, + {IV('カ'), 0xB6, 0}, + {IV('ガ'), 0xB6, 0xDE}, + {IV('キ'), 0xB7, 0}, + {IV('ギ'), 0xB7, 0xDE}, + {IV('ク'), 0xB8, 0}, + {IV('グ'), 0xB8, 0xDE}, + {IV('ケ'), 0xB9, 0}, + {IV('ゲ'), 0xB9, 0xDE}, + {IV('コ'), 0xBA, 0}, + {IV('ゴ'), 0xBA, 0xDE}, + {IV('サ'), 0xBB, 0}, + {IV('ザ'), 0xBB, 0xDE}, + {IV('シ'), 0xBC, 0}, + {IV('ジ'), 0xBC, 0xDE}, + {IV('ス'), 0xBD, 0}, + {IV('ズ'), 0xBD, 0xDE}, + {IV('セ'), 0xBE, 0}, + {IV('ゼ'), 0xBE, 0xDE}, + {IV('ソ'), 0xBF, 0}, + {IV('ゾ'), 0xBF, 0xDE}, + + {IV('タ'), 0xC0, 0}, + {IV('ダ'), 0xC0, 0xDE}, + {IV('チ'), 0xC1, 0}, + {IV('ヂ'), 0xC1, 0xDE}, + {IV('ッ'), 0xAF, 0}, + {IV('ツ'), 0xC2, 0}, + {IV('ヅ'), 0xC2, 0xDE}, + {IV('テ'), 0xC3, 0}, + {IV('デ'), 0xC3, 0xDE}, + {IV('ト'), 0xC4, 0}, + {IV('ド'), 0xC4, 0xDE}, + {IV('ナ'), 0xC5, 0}, + {IV('ニ'), 0xC6, 0}, + {IV('ヌ'), 0xC7, 0}, + {IV('ネ'), 0xC8, 0}, + {IV('ノ'), 0xC9, 0}, + {IV('ハ'), 0xCA, 0}, + {IV('バ'), 0xCA, 0xDE}, + {IV('パ'), 0xCA, 0xDF}, + {IV('ヒ'), 0xCB, 0}, + {IV('ビ'), 0xCB, 0xDE}, + {IV('ピ'), 0xCB, 0xDF}, + {IV('フ'), 0xCC, 0}, + {IV('ブ'), 0xCC, 0xDE}, + {IV('プ'), 0xCC, 0xDF}, + {IV('ヘ'), 0xCD, 0}, + {IV('ベ'), 0xCD, 0xDE}, + {IV('ペ'), 0xCD, 0xDF}, + {IV('ホ'), 0xCE, 0}, + {IV('ボ'), 0xCE, 0xDE}, + {IV('ポ'), 0xCE, 0xDF}, + {IV('マ'), 0xCF, 0}, + + {IV('ミ'), 0xD0, 0}, + {IV('ム'), 0xD1, 0}, + {IV('メ'), 0xD2, 0}, + {IV('モ'), 0xD3, 0}, + {IV('ャ'), 0xAC, 0}, + {IV('ヤ'), 0xD4, 0}, + {IV('ュ'), 0xAD, 0}, + {IV('ユ'), 0xD5, 0}, + {IV('ョ'), 0xAE, 0}, + {IV('ヨ'), 0xD6, 0}, + {IV('ラ'), 0xD7, 0}, + {IV('リ'), 0xD8, 0}, + {IV('ル'), 0xD9, 0}, + {IV('レ'), 0xDA, 0}, + {IV('ロ'), 0xDB, 0}, + {IV('ワ'), 0xDC, 0}, + {IV('ヲ'), 0xA6, 0}, + {IV('ン'), 0xDD, 0}, + {IV('ヴ'), 0xB3, 0xDE}, + {IV('ヷ'), 0xDC, 0xDE}, + {IV('ヺ'), 0xA6, 0xDE}, + {IV('・'), 0xA5, 0}, + {IV('ー'), 0xB0, 0}, + {IV('ヽ'), 0xA4, 0}, + + //{IV('g'), 0xE7, 0}, // error + //{IV(''), 0xE9, 0}, + //{IV('j'), 0xEA, 0}, // error + //{IV(''), 0xED, 0}, + //{IV(''), 0xEE, 0}, + + //{IV('p'), 0xF0, 0}, // error + //{IV('q'), 0xF1, 0}, // error + //{IV(''), 0xF8, 0}, + //{IV('y'), 0xF9, 0}, // error + {IV('万'), 0xFB, 0}, + {IV('円'), 0xFC, 0}, + {IV('千'), 0xFA, 0}, + //{IV(''), 0xFE, 0}, + + //、・ヲァィゥェォャュョッー + {IV('、'), 0xA4, 0}, //ヽ + {IV('・'), 0xA5, 0}, //・ + {IV('ヲ'), 0xA6, 0}, //ヲ + {IV('ァ'), 0xA7, 0}, //ァ + {IV('ィ'), 0xA8, 0}, //ィ + {IV('ゥ'), 0xA9, 0}, //ゥ + {IV('ェ'), 0xAA, 0}, //ェ + {IV('ォ'), 0xAB, 0}, //ォ + {IV('ャ'), 0xAC, 0}, //ャ + {IV('ュ'), 0xAD, 0}, //ュ + {IV('ョ'), 0xAE, 0}, //ョ + {IV('ッ'), 0xAF, 0}, //ッ + {IV('ー'), 0xB0, 0}, //ー + + //アイウエオカキクケコサシスセ + {IV('ア'), 0xB1, 0}, //ア + {IV('イ'), 0xB2, 0}, //イ + {IV('ウ'), 0xB3, 0}, //ウ + {IV('エ'), 0xB4, 0}, //エ + {IV('オ'), 0xB5, 0}, //オ + {IV('カ'), 0xB6, 0}, //カ + {IV('キ'), 0xB7, 0}, //キ + {IV('ク'), 0xB8, 0}, //ク + {IV('ケ'), 0xB9, 0}, //ケ + {IV('コ'), 0xBA, 0}, //コ + {IV('サ'), 0xBB, 0}, //サ + {IV('シ'), 0xBC, 0}, //シ + {IV('ス'), 0xBD, 0}, //ス + {IV('セ'), 0xBE, 0}, //セ + + //ソタチツテトナニヌネノハヒフ + {IV('ソ'), 0xBF, 0}, //ソ + {IV('タ'), 0xC0, 0}, //タ + {IV('チ'), 0xC1, 0}, //チ + {IV('ツ'), 0xC2, 0}, //ツ + {IV('テ'), 0xC3, 0}, //テ + {IV('ト'), 0xC4, 0}, //ト + {IV('ナ'), 0xC5, 0}, //ナ + {IV('ニ'), 0xC6, 0}, //ニ + {IV('ヌ'), 0xC7, 0}, //ヌ + {IV('ネ'), 0xC8, 0}, //ネ + {IV('ノ'), 0xC9, 0}, //ノ + {IV('ハ'), 0xCA, 0}, //ハ + {IV('ヒ'), 0xCB, 0}, //ヒ + {IV('フ'), 0xCC, 0}, //フ + + //ヘホマミムメモヤユヨラリルレロワン゙゚ + {IV('ヘ'), 0xCD, 0}, //ヘ + {IV('ホ'), 0xCE, 0}, //ホ + {IV('マ'), 0xCF, 0}, //マ + {IV('ミ'), 0xD0, 0}, //ミ + {IV('ム'), 0xD1, 0}, //ム + {IV('メ'), 0xD2, 0}, //メ + {IV('モ'), 0xD3, 0}, //モ + {IV('ヤ'), 0xD4, 0}, //ヤ + {IV('ユ'), 0xD5, 0}, //ユ + {IV('ヨ'), 0xD6, 0}, //ヨ + {IV('ラ'), 0xD7, 0}, //ラ + {IV('リ'), 0xD8, 0}, //リ + {IV('ル'), 0xD9, 0}, //ル + {IV('レ'), 0xDA, 0}, //レ + {IV('ロ'), 0xDB, 0}, //ロ + {IV('ワ'), 0xDC, 0}, //ワ + {IV('ン'), 0xDD, 0}, //ン + {IV('゙'), 0xDE, 0}, // ゛ + {IV('゚'), 0xDF, 0}, // ゜ + + {IV('¥'), 0x5C, 0}, + + #elif DISPLAY_CHARSET_HD44780 == WESTERN + // 0x10 -- 0x1F (except 0x1C) + // 0x80 -- 0xFF (except 0xA7,0xB0,0xB1,0xB3,0xB4,0xBF,0xD1,0xF8,0xFA,0xFC-0xFF) + + {IV('¡'), 0xA9, 0}, + {IV('¢'), 0xA4, 0}, + {IV('£'), 0xA5, 0}, + {IV('¥'), 0xA6, 0}, + {IV('§'), 0xD2, 0}, // section sign + {IV('©'), 0xCF, 0}, + + {IV('ª'), 0x9D, 0}, + {IV('«'), 0xBB, 0}, + {IV('®'), 0xCE, 0}, + + {IV('°'), 0xB2, 0}, // Marlin special: '°' LCD_STR_DEGREE (0x09) + //{IV(''), 0xD1, 0}, + {IV('±'), 0x10, 0}, //∓± + //{'='), 0x1C, 0}, // error + {IV('²'), 0x1E, 0}, + {IV('³'), 0x1F, 0}, + {IV('¶'), 0xD3, 0}, // pilcrow sign + {IV('º'), 0x9E, 0}, + {IV('»'), 0xBC, 0}, // 00BB + //{IV(''), 0xB3, 0}, // error + //{IV(''), 0xB4, 0}, // error + {IV('¼'), 0xB6, 0}, // 00BC + {IV('½'), 0xB5, 0}, // 00BD + //{IV('¾'), '3', 0}, // 00BE + {IV('¿'), 0x9F, 0}, // 00BF + + {IV('Â'), 0x8F, 0}, + {IV('Ã'), 0xAA, 0}, + {IV('Ä'), 0x8E, 0}, + {IV('Æ'), 0x92, 0}, + {IV('Ç'), 0x80, 0}, + {IV('É'), 0x90, 0}, + {IV('Ñ'), 0x9C, 0}, + {IV('Õ'), 0xAC, 0}, + {IV('Ö'), 0x99, 0}, + {IV('×'), 0xB7, 0}, + {IV('Ø'), 0xAE, 0}, + {IV('Ü'), 0x9A, 0}, + {IV('à'), 0x85, 0}, + {IV('á'), 0xA0, 0}, + {IV('â'), 0x83, 0}, + {IV('ã'), 0xAB, 0}, + {IV('ä'), 0x84, 0}, + {IV('å'), 0x86, 0}, + {IV('æ'), 0x91, 0}, + {IV('ç'), 0x87, 0}, + {IV('è'), 0x8A, 0}, + {IV('é'), 0x82, 0}, + {IV('ê'), 0x88, 0}, + {IV('ë'), 0x89, 0}, + {IV('ì'), 0x8D, 0}, + {IV('í'), 0xA1, 0}, + {IV('î'), 0x8C, 0}, + {IV('ï'), 0x8B, 0}, + + {IV('ñ'), 0x9B, 0}, + {IV('ò'), 0x95, 0}, + {IV('ó'), 0xA2, 0}, + {IV('ô'), 0x93, 0}, + {IV('õ'), 0xAD, 0}, + {IV('ö'), 0x94, 0}, + {IV('÷'), 0xB8, 0}, + {IV('ø'), 0xAF, 0}, + {IV('ù'), 0x97, 0}, + {IV('ú'), 0xA3, 0}, + {IV('û'), 0x96, 0}, + {IV('ü'), 0x81, 0}, + {IV('ÿ'), 0x98, 0}, + + //{IV(''), 0xB0, 0}, // error + //{IV(''), 0xB1, 0}, // error + {IV('ƒ'), 0xA8, 0}, // 0192 + + {IV('Ύ'), 0xDB, 0}, // 038E + {IV('Ώ'), 0xDE, 0}, // 038F + {IV('ΐ'), 0xE7, 0}, // 0390 + + {IV('Γ'), 0xD4, 0}, // 0393, Gamma + {IV('Δ'), 0xD5, 0}, // 0394, Delta, ◿ + {IV('Θ'), 0xD6, 0}, // 0398, Theta + {IV('Λ'), 0xD7, 0}, // 039B, Lambda + {IV('Ξ'), 0xD8, 0}, // 039E, Xi + {IV('Π'), 0xD9, 0}, // Pi + {IV('Σ'), 0xDA, 0}, // Sigma + {IV('Υ'), 0xDB, 0}, // Upsilon + {IV('Φ'), 0xDC, 0}, // Phi + {IV('Ψ'), 0xDD, 0}, // Psi + {IV('Ω'), 0xDE, 0}, // Omega + + {IV('ά'), 0xDF, 0}, // 03AC + {IV('έ'), 0xE3, 0}, // 03AD + {IV('ή'), 0xE5, 0}, // 03AE + {IV('ί'), 0xE7, 0}, // 03AF + {IV('ΰ'), 0xF1, 0}, // 03B0 + + {IV('α'), 0xDF, 0}, // alpha + {IV('β'), 0xE0, 0}, // beta + {IV('γ'), 0xE1, 0}, // gamma + {IV('δ'), 0xE2, 0}, // delta + {IV('ε'), 0xE3, 0}, // epsilon + {IV('ζ'), 0xE4, 0}, // zeta + {IV('η'), 0xE5, 0}, // eta + {IV('θ'), 0xE6, 0}, // theta + {IV('ι'), 0xE7, 0}, // lota + {IV('κ'), 0xE8, 0}, // kappa + {IV('λ'), 0xE9, 0}, // lambda + {IV('μ'), 0xEA, 0}, // mu + {IV('ν'), 0xEB, 0}, // nu + {IV('ξ'), 0xEC, 0}, // xi + {IV('π'), 0xED, 0}, // pi + {IV('ρ'), 0xEE, 0}, // rho + {IV('σ'), 0xEF, 0}, // sigma + + {IV('τ'), 0xF0, 0}, // tau + {IV('υ'), 0xF1, 0}, // upsilon + {IV('χ'), 0xF2, 0}, // chi + {IV('ψ'), 0xF3, 0}, // psi + {IV('ω'), 0xF4, 0}, // 03C9, omega + {IV('ϊ'), 0xE7, 0}, // 03CA + {IV('ϋ'), 0xF1, 0}, // 03CB + {IV('ύ'), 0xF1, 0}, // 03CD + {IV('ώ'), 0xF4, 0}, // 03CE + + {IV('•'), 0xCD, 0}, // · + {IV('℞'), 0xA7, 0}, // ℞ Pt ASCII 158 + {IV('™'), 0xD0, 0}, + {IV('↤'), 0xF9, 0}, // ⟻ + {IV('↵'), 0xC4, 0}, + {IV('↻'), 0x04, 0}, // Marlin special: '↻↺⟳⟲' LCD_STR_REFRESH (0x01) + {IV('⇥'), 0xFB, 0}, + {IV('√'), 0xBE, 0}, // √ + {IV('∞'), 0xC2, 0}, // infinity + {IV('∫'), 0x1B, 0}, + {IV('∼'), 0x1D, 0}, + {IV('≈'), 0x1A, 0}, + {IV('≠'), 0xBD, 0}, + {IV('≡'), 0x11, 0}, + {IV('≤'), 0xB9, 0},// ≤≥ ⩽⩾ + {IV('≥'), 0xBA, 0}, + //{IV(''), 0xBF, 0}, // error + + {IV('⌠'), 0xC0, 0}, + {IV('⌡'), 0xC1, 0}, + + {IV('⎧'), 0x14, 0}, + {IV('⎩'), 0x15, 0}, + {IV('⎫'), 0x16, 0}, + {IV('⎭'), 0x17, 0}, + {IV('⎰'), 0x18, 0}, + {IV('⎱'), 0x19, 0}, + + {IV('⎲'), 0x12, 0}, + {IV('⎳'), 0x13, 0}, + + {IV('⏱'), 0x07, 0}, // Marlin special: '🕐🕑🕒🕓🕔🕕🕖🕗🕘🕙🕚🕛🕜🕝🕞🕟🕠🕡🕢🕣🕤🕥🕦🕧 ⌚⌛⏰⏱⏳⧖⧗' LCD_STR_CLOCK (0x05) + {IV('┌'), 0xC9, 0}, + {IV('┐'), 0xCA, 0}, + {IV('└'), 0xCB, 0}, + {IV('┘'), 0xCC, 0}, + {IV('◸'), 0xC3, 0}, // ◿ + {IV('⭠'), 0xC8, 0}, + {IV('⭡'), 0xC5, 0}, + {IV('⭢'), 0xC7, 0}, + {IV('⭣'), 0xC6, 0}, + + + {IV('⯆'), 0xF5, 0}, + {IV('⯇'), 0xF7, 0}, // ⯅ + {IV('⯈'), 0xF6, 0}, + //{IV(''), 0xF8, 0}, // error + //{IV(''), 0xFA, 0}, // error + //{IV(''), 0xFC, 0}, // error + //{IV(''), 0xFD, 0}, // error + //{IV(''), 0xFE, 0}, // error + //{IV(''), 0xFF, 0}, // error + + #elif DISPLAY_CHARSET_HD44780 == CYRILLIC + + {IV('¢'), 0x5C, 0}, // 00A2 + {IV('£'), 0xCF, 0}, // 00A3 + {IV('°'), 0x01, 0}, // 00B0, Marlin special: '°' LCD_STR_DEGREE (0x09) + + //{IV(''), 0x80, 0}, + //{IV(''), 0x81, 0}, + //{IV(''), 0x82, 0}, + //{IV(''), 0x83, 0}, + //{IV(''), 0x84, 0}, + //{IV(''), 0x85, 0}, + //{IV(''), 0x86, 0}, + //{IV(''), 0x87, 0}, + //{IV(''), 0x88, 0}, + //{IV(''), 0x89, 0}, + //{IV(''), 0x8A, 0}, + //{IV(''), 0x8B, 0}, + //{IV(''), 0x8C, 0}, + //{IV(''), 0x8D, 0}, + //{IV(''), 0x8E, 0}, + //{IV(''), 0x8F, 0}, + + //{IV(''), 0x90, 0}, + //{IV(''), 0x91, 0}, + //{IV(''), 0x92, 0}, + //{IV(''), 0x93, 0}, + //{IV(''), 0x94, 0}, + //{IV(''), 0x95, 0}, + //{IV(''), 0x96, 0}, + //{IV(''), 0x97, 0}, + //{IV(''), 0x98, 0}, + //{IV(''), 0x99, 0}, + //{IV(''), 0x9A, 0}, + //{IV(''), 0x9B, 0}, + //{IV(''), 0x9C, 0}, + //{IV(''), 0x9D, 0}, + //{IV(''), 0x9E, 0}, + //{IV(''), 0x9F, 0}, + + + {IV('¼'), 0xF0, 0}, // 00BC + {IV('⅓'), 0xF1, 0}, + {IV('½'), 0xF2, 0}, // 00BD + {IV('¾'), 0xF3, 0}, // 00BE + {IV('¿'), 0xCD, 0}, // 00BF + + #if ENABLED(DISPLAY_CHARSET_ISO10646_5) + + // Map Cyrillic to HD44780 extended CYRILLIC where possible + {IV('Ё'), 0xA2, 0}, // 0401 + {IV('А'), 'A', 0}, // 0410 + {IV('Б'), 0xA0, 0}, + {IV('В'), 'B', 0}, + {IV('Г'), 0xA1, 0}, + {IV('Д'), 0xE0, 0}, + {IV('Е'), 'E', 0}, + {IV('Ж'), 0xA3, 0}, + {IV('З'), 0xA4, 0}, + {IV('И'), 0xA5, 0}, + {IV('Й'), 0xA6, 0}, + {IV('К'), 'K', 0}, + {IV('Л'), 0xA7, 0}, + {IV('М'), 'M', 0}, + {IV('Н'), 'H', 0}, + {IV('О'), 'O', 0}, + {IV('П'), 0xA8, 0}, + {IV('Р'), 'P', 0}, + {IV('С'), 'C', 0}, + {IV('Т'), 'T', 0}, + {IV('У'), 0xA9, 0}, + {IV('Ф'), 0xAA, 0}, + {IV('Х'), 'X', 0}, + {IV('Ц'), 0xE1, 0}, + {IV('Ч'), 0xAB, 0}, + {IV('Ш'), 0xAC, 0}, + {IV('Щ'), 0xE2, 0}, + {IV('Ъ'), 0xAD, 0}, + {IV('Ы'), 0xAE, 0}, + {IV('Ь'), 'b', 0}, + {IV('Э'), 0xAF, 0}, + {IV('Ю'), 0xB0, 0}, + {IV('Я'), 0xB1, 0}, + {IV('а'), 'a', 0}, + + {IV('б'), 0xB2, 0}, + {IV('в'), 0xB3, 0}, + {IV('г'), 0xB4, 0}, + {IV('д'), 0xE3, 0}, + {IV('е'), 'e', 0}, + {IV('ж'), 0xB6, 0}, + {IV('з'), 0xB7, 0}, + {IV('и'), 0xB8, 0}, + {IV('й'), 0xB9, 0}, + {IV('к'), 0xBA, 0}, //клмноп + {IV('л'), 0xBB, 0}, + {IV('м'), 0xBC, 0}, + {IV('н'), 0xBD, 0}, + {IV('о'), 'o', 0}, + {IV('п'), 0xBE, 0}, + {IV('р'), 'p', 0}, + {IV('с'), 'c', 0}, + {IV('т'), 0xBF, 0}, + + {IV('у'), 'y', 0}, + {IV('ф'), 0xE4, 0}, + {IV('х'), 'x', 0}, + {IV('ц'), 0xE5, 0}, + {IV('ч'), 0xC0, 0}, + {IV('ш'), 0xC1, 0}, + {IV('щ'), 0xE6, 0}, + {IV('ъ'), 0xC2, 0}, + {IV('ы'), 0xC3, 0}, + {IV('ь'), 0xC4, 0}, + {IV('э'), 0xC5, 0}, + {IV('ю'), 0xC6, 0}, + {IV('я'), 0xC7, 0}, // 044F + {IV('ё'), 0xB5, 0}, // 0451 + //{IV(''), 0xC8, 0}, + //{IV(''), 0xC9, 0}, + //{IV(''), 0xCA, 0}, + //{IV(''), 0xCB, 0}, + //{IV(''), 0xCC, 0}, + //{IV(''), 0xCD, 0}, + //{IV(''), 0xCE, 0}, + + //{IV(''), 0xD0, 0}, + //{IV(''), 0xD1, 0}, + //{IV(''), 0xD2, 0}, + //{IV(''), 0xD3, 0}, + //{IV(''), 0xD4, 0}, + //{IV(''), 0xD5, 0}, + //{IV(''), 0xD6, 0}, + //{IV(''), 0xD7, 0}, + //{IV(''), 0xD8, 0}, + //{IV(''), 0xDB, 0}, + //{IV(''), 0xDC, 0}, + //{IV(''), 0xDD, 0}, + //{IV(''), 0xDE, 0}, + //{IV(''), 0xDF, 0}, + + //{IV(''), 0xE7, 0}, + //{IV(''), 0xE8, 0}, + //{IV(''), 0xE9, 0}, + //{IV(''), 0xEA, 0}, + //{IV(''), 0xEB, 0}, + //{IV(''), 0xEC, 0}, + //{IV(''), 0xED, 0}, + //{IV(''), 0xEE, 0}, + //{IV(''), 0xEF, 0}, + + //{IV(''), 0xF4, 0}, + //{IV(''), 0xF5, 0}, + //{IV(''), 0xF6, 0}, + //{IV(''), 0xF7, 0}, + //{IV(''), 0xF8, 0}, + //{IV(''), 0xF9, 0}, + //{IV(''), 0xFA, 0}, + //{IV(''), 0xFB, 0}, + //{IV(''), 0xFC, 0}, + //{IV(''), 0xFD, 0}, + //{IV(''), 0xFE, 0}, + //{IV(''), 0xFF, 0}, + + #endif + + {IV('↑'), 0xD9, 0}, // 2191 ←↑→↓ + {IV('↓'), 0xDA, 0}, // 2193 + #endif +}; + +// the plain ASCII replacement for various char +const dwin_charmap_t g_dwin_charmap_common[] PROGMEM = { + {IV('¡'), 'i', 0}, // A1 + {IV('¢'), 'c', 0}, // A2 + {IV('°'), 0x09, 0}, // B0 Marlin special: '°' LCD_STR_DEGREE (0x09) + + // Map WESTERN code to plain ASCII + {IV('Á'), 'A', 0}, // C1 + {IV('Â'), 'A', 0}, // C2 + {IV('Ã'), 'A', 0}, // C3 + {IV('Ä'), 'A', 0}, // C4 + {IV('Å'), 'A', 0}, // C5 + {IV('Æ'), 'A', 'E'}, // C6 + {IV('Ç'), 'C', 0}, // C7 + {IV('È'), 'E', 0}, // C8 + {IV('É'), 'E', 0}, // C9 + {IV('Í'), 'I', 0}, // CD + {IV('Ñ'), 'N', 0}, // D1 + {IV('Õ'), 'O', 0}, // D5 + {IV('Ö'), 'O', 0}, // D6 + {IV('×'), 'x', 0}, // D7 + {IV('Ü'), 'U', 0}, // DC + {IV('Ý'), 'Y', 0}, // DD + {IV('à'), 'a', 0}, // E0 + {IV('á'), 'a', 0}, + {IV('â'), 'a', 0}, + {IV('ã'), 'a', 0}, + {IV('ä'), 'a', 0}, + {IV('å'), 'a', 0}, + {IV('æ'), 'a', 'e'}, + {IV('ç'), 'c', 0}, + {IV('è'), 'e', 0}, // 00E8 + {IV('é'), 'e', 0}, + {IV('ê'), 'e', 0}, + {IV('ë'), 'e', 0}, + {IV('ì'), 'i', 0}, // 00EC + {IV('í'), 'i', 0}, + {IV('î'), 'i', 0}, + {IV('ï'), 'i', 0}, // 00EF + + {IV('ñ'), 'n', 0}, // 00F1 + {IV('ò'), 'o', 0}, + {IV('ó'), 'o', 0}, + {IV('ô'), 'o', 0}, + {IV('õ'), 'o', 0}, + {IV('ö'), 'o', 0}, + //{IV('÷'), 0xB8, 0}, + {IV('ø'), 'o', 0}, + {IV('ù'), 'u', 0}, + {IV('ú'), 'u', 0}, + {IV('û'), 'u', 0}, + {IV('ü'), 'u', 0}, // FC + {IV('ý'), 'y', 0}, // FD + {IV('ÿ'), 'y', 0}, // FF + + {IV('Ą'), 'A', 0}, // 0104 + {IV('ą'), 'a', 0}, // 0105 + {IV('Ć'), 'C', 0}, // 0106 + {IV('ć'), 'c', 0}, // 0107 + {IV('Č'), 'C', 0}, // 010C + {IV('č'), 'c', 0}, // 010D + {IV('Ď'), 'D', 0}, // 010E + {IV('ď'), 'd', 0}, // 010F + {IV('đ'), 'd', 0}, // 0111 + {IV('ę'), 'e', 0}, // 0119 + {IV('Ě'), 'E', 0}, // 011A + {IV('ě'), 'e', 0}, // 011B + {IV('ğ'), 'g', 0}, // 011F + {IV('İ'), 'I', 0}, // 0130 + {IV('ı'), 'i', 0}, // 0131 + + {IV('Ł'), 'L', 0}, // 0141 + {IV('ł'), 'l', 0}, // 0142 + {IV('Ń'), 'N', 0}, // 0143 + {IV('ń'), 'n', 0}, // 0144 + {IV('ň'), 'n', 0}, // 0148 + + {IV('Ř'), 'R', 0}, // 0158 + {IV('ř'), 'r', 0}, // 0159 + {IV('Ś'), 'S', 0}, // 015A + {IV('ś'), 's', 0}, // 015B + {IV('ş'), 's', 0}, // 015F + {IV('Š'), 'S', 0}, // 0160 + {IV('š'), 's', 0}, // 0161 + {IV('ť'), 't', 0}, // 0165 + {IV('ů'), 'u', 0}, // 016F + {IV('ż'), 'z', 0}, // 017C + {IV('Ž'), 'Z', 0}, // 017D + {IV('ž'), 'z', 0}, // 017E + {IV('ƒ'), 'f', 0}, // 0192 + + {IV('ˣ'), 'x', 0}, // 02E3 + + #if ENABLED(DISPLAY_CHARSET_ISO10646_VI) + + // Map Vietnamese phonetics + + //{IV('à'), 'a', 0}, {IV('À'), 'A', 0}, + {IV('ạ'), 'a', 0}, {IV('Ạ'), 'A', 0}, + {IV('ả'), 'a', 0}, {IV('Ả'), 'A', 0}, + //{IV('ã'), 'a', 0}, {IV('Ã'), 'A', 0}, + //{IV('á'), 'á', 0}, {IV('Á'), 'A', 0}, + {IV('Ạ'), 'A', 0}, + {IV('ă'), 'a', 0}, {IV('Ă'), 'A', 0}, + {IV('ằ'), 'a', 0}, {IV('Ằ'), 'A', 0}, + {IV('ẳ'), 'a', 0}, {IV('Ẳ'), 'A', 0}, + {IV('ẵ'), 'a', 0}, {IV('Ẵ'), 'A', 0}, + {IV('ắ'), 'a', 0}, {IV('Ắ'), 'A', 0}, + {IV('ặ'), 'a', 0}, {IV('Ặ'), 'A', 0}, + {IV('â'), 'a', 0}, {IV('Â'), 'A', 0}, + {IV('ầ'), 'a', 0}, {IV('Ầ'), 'A', 0}, + {IV('ẩ'), 'a', 0}, {IV('Ẩ'), 'A', 0}, + {IV('ẫ'), 'a', 0}, {IV('Ẫ'), 'A', 0}, + {IV('ấ'), 'a', 0}, {IV('Ấ'), 'A', 0}, + {IV('ậ'), 'a', 0}, {IV('Ậ'), 'A', 0}, + //{IV('đ'), 'd', 0}, + {IV('Đ'), 'D', 0}, + {IV('e'), 'e', 0}, {IV('E'), 'E', 0}, + {IV('è'), 'e', 0}, {IV('È'), 'E', 0}, + {IV('ẻ'), 'e', 0}, {IV('Ẻ'), 'E', 0}, + {IV('ẽ'), 'e', 0}, {IV('Ẽ'), 'E', 0}, + {IV('é'), 'e', 0}, {IV('É'), 'E', 0}, + {IV('ẹ'), 'e', 0}, {IV('Ẹ'), 'E', 0}, + {IV('ê'), 'e', 0}, {IV('Ê'), 'E', 0}, + {IV('ề'), 'e', 0}, {IV('Ề'), 'E', 0}, + {IV('ể'), 'e', 0}, {IV('Ể'), 'E', 0}, + {IV('ễ'), 'e', 0}, {IV('Ễ'), 'E', 0}, + {IV('ế'), 'e', 0}, {IV('Ế'), 'E', 0}, + {IV('ệ'), 'e', 0}, {IV('Ệ'), 'E', 0}, + {IV('i'), 'i', 0}, {IV('I'), 'I', 0}, + //{IV('ì'), 'ì', 0}, {IV('Ì'), 'Ì', 0}, + {IV('ỉ'), 'ỉ', 0}, {IV('Ỉ'), 'Ỉ', 0}, + {IV('ĩ'), 'ĩ', 0}, {IV('Ĩ'), 'Ĩ', 0}, + {IV('í'), 'í', 0}, {IV('Í'), 'Í', 0}, + {IV('ị'), 'ị', 0}, {IV('Ị'), 'Ị', 0}, + {IV('o'), 'o', 0}, {IV('O'), 'O', 0}, + {IV('ò'), 'o', 0}, {IV('Ò'), 'O', 0}, + {IV('ỏ'), 'o', 0}, {IV('Ỏ'), 'O', 0}, + {IV('õ'), 'o', 0}, {IV('Õ'), 'O', 0}, + {IV('ó'), 'o', 0}, {IV('Ó'), 'O', 0}, + {IV('ọ'), 'o', 0}, {IV('Ọ'), 'O', 0}, + {IV('ô'), 'o', 0}, {IV('Ô'), 'O', 0}, + {IV('ồ'), 'o', 0}, {IV('Ồ'), 'O', 0}, + {IV('ổ'), 'o', 0}, {IV('Ổ'), 'O', 0}, + {IV('ỗ'), 'o', 0}, {IV('Ỗ'), 'O', 0}, + {IV('ố'), 'o', 0}, {IV('Ố'), 'O', 0}, + {IV('ộ'), 'o', 0}, {IV('Ộ'), 'O', 0}, + {IV('ơ'), 'o', 0}, {IV('Ơ'), 'O', 0}, + {IV('ờ'), 'o', 0}, {IV('Ờ'), 'O', 0}, + {IV('ở'), 'o', 0}, {IV('Ở'), 'O', 0}, + {IV('ỡ'), 'o', 0}, {IV('Ỡ'), 'O', 0}, + {IV('ớ'), 'o', 0}, {IV('Ớ'), 'O', 0}, + {IV('ợ'), 'o', 0}, {IV('Ợ'), 'O', 0}, + {IV('ù'), 'u', 0}, {IV('Ù'), 'U', 0}, + {IV('ủ'), 'u', 0}, {IV('Ủ'), 'U', 0}, + {IV('ũ'), 'u', 0}, {IV('Ũ'), 'U', 0}, + //{IV('ú'), 'u', 0}, {IV('Ú'), 'U', 0}, + {IV('ụ'), 'u', 0}, {IV('Ụ'), 'U', 0}, + {IV('ư'), 'u', 0}, {IV('Ư'), 'U', 0}, + {IV('ừ'), 'u', 0}, {IV('Ừ'), 'U', 0}, + {IV('ử'), 'u', 0}, {IV('Ử'), 'U', 0}, + {IV('ữ'), 'u', 0}, {IV('Ữ'), 'U', 0}, + {IV('ứ'), 'u', 0}, {IV('Ứ'), 'U', 0}, + {IV('ự'), 'u', 0}, {IV('Ự'), 'U', 0}, + {IV('y'), 'y', 0}, {IV('Y'), 'Y', 0}, + + #endif + + #if ENABLED(DISPLAY_CHARSET_ISO10646_GREEK) + + {IV('΄'), '\'', 0}, // 0384 + {IV('΅'), '\'', 0}, // 0385 + {IV('Ά'), 'A', 0}, // 0386 + {IV('·'), '.', 0}, // 0387 + {IV('Έ'), 'E', 0}, // 0388 + {IV('Ή'), 'H', 0}, // 0389 + {IV('Ί'), 'I', 0}, // 038A + {IV('Ό'), 'O', 0}, // 038C + {IV('Ύ'), 'Y', 0}, // 038E + {IV('Ώ'), 'O', 0}, // 038F + {IV('ΐ'), 'i', 0}, // 0390 + {IV('Α'), 'A', 0}, // 0391 + {IV('Β'), 'B', 0}, // 0392 + {IV('Γ'), 'T', 0}, // 0393, Gamma + {IV('Δ'), '4', 0}, // 0394, Delta, ◿ + {IV('Ε'), 'E', 0}, // 0395 + {IV('Ζ'), 'Z', 0}, // 0396 + {IV('Η'), 'H', 0}, // 0397 + {IV('Θ'), '0', 0}, // 0398, Theta + {IV('Ι'), 'I', 0}, // 0399 + {IV('Κ'), 'K', 0}, // 039A + {IV('Λ'), '^', 0}, // 039B, Lambda + {IV('Μ'), 'M', 0}, // 039C + {IV('Ν'), 'N', 0}, // 039D + {IV('Ξ'), '3', 0}, // 039E, Xi + {IV('Ο'), 'O', 0}, // 039F + {IV('Π'), 'n', 0}, // 03A0, Pi + {IV('Ρ'), 'P', 0}, // 03A1 + {IV('Σ'), 'E', 0}, // 03A3, Sigma + {IV('Τ'), 'T', 0}, // 03A4 + {IV('Υ'), 'Y', 0}, // 03A5, Upsilon + {IV('Φ'), 'p', 0}, // 03A6, Phi + {IV('Χ'), 'X', 0}, // 03A7 + {IV('Ψ'), 'P', 0}, // 03A8, Psi + {IV('Ω'), 'O', 0}, // 03A9, Omega + {IV('Ϊ'), 'I', 0}, // 03AA + {IV('Ϋ'), 'Y', 0}, // 03AB + {IV('ά'), 'a', 0}, // 03AC + {IV('έ'), 'e', 0}, // 03AD + {IV('ή'), 'n', 0}, // 03AE + {IV('ί'), 'i', 0}, // 03AF + {IV('ΰ'), 'v', 0}, // 03B0 + {IV('α'), 'a', 0}, // 03B1, alpha + {IV('β'), 'B', 0}, // 03B2, beta + {IV('γ'), 'v', 0}, // 03B3, gamma + {IV('δ'), 'd', 0}, // 03B4, delta + {IV('ε'), 'e', 0}, // 03B5, epsilon + {IV('ζ'), 'Z', 0}, // 03B6, zeta + {IV('η'), 'n', 0}, // 03B7, eta + {IV('θ'), '0', 0}, // 03B8, theta + {IV('ι'), 'i', 0}, // 03B9, lota + {IV('κ'), 'k', 0}, // 03BA, kappa + {IV('λ'), 'L', 0}, // 03BB, lambda + {IV('μ'), 'u', 0}, // 03BC, mu + {IV('ν'), 'v', 0}, // 03BD, nu + {IV('ξ'), 'e', 0}, // 03BE, xi + {IV('ο'), 'o', 0}, // 03BF + {IV('π'), 'n', 0}, // 03C0, pi + {IV('ρ'), 'p', 0}, // 03C1, rho + {IV('ς'), 'c', 0}, // 03C2 + {IV('σ'), 'o', 0}, // 03C3, sigma + {IV('τ'), 't', 0}, // 03C4, tau + {IV('υ'), 'v', 0}, // 03C5, upsilon + {IV('φ'), 'p', 0}, // 03C6 + {IV('χ'), 'X', 0}, // 03C7, chi + {IV('ψ'), 'W', 0}, // 03C8, psi + {IV('ω'), 'w', 0}, // 03C9, omega + {IV('ϊ'), 'i', 0}, // 03CA + {IV('ϋ'), 'v', 0}, // 03CB + {IV('ό'), 'o', 0}, // 03CC + {IV('ύ'), 'v', 0}, // 03CD + {IV('ώ'), 'w', 0}, // 03CE + + #endif + + #if ENABLED(DISPLAY_CHARSET_ISO10646_5) + // Map CYRILLIC code to plain ASCII + {IV('Ё'), 'E', 0}, // 0401 + {IV('А'), 'A', 0}, // 0410 + {IV('Б'), 'b', 0}, // 0411 + {IV('В'), 'B', 0}, // 0412 + {IV('Г'), 'T', 0}, // 0413 + {IV('Д'), 'Q', 0}, // 0414 + {IV('Е'), 'E', 0}, // 0415 + {IV('Ж'), '*', 0}, // 0416 + {IV('З'), 'E', 0}, // 0417 + {IV('И'), 'N', 0}, // 0418 + {IV('Й'), 'N', 0}, // 0419 + {IV('К'), 'K', 0}, // 041A + {IV('Л'), 'T', 0}, // 041B + {IV('М'), 'M', 0}, // 041C + {IV('Н'), 'H', 0}, // 041D + {IV('О'), 'O', 0}, // 041E + {IV('П'), 'n', 0}, // 041F + {IV('Р'), 'P', 0}, // 0420 + {IV('С'), 'C', 0}, // 0421 + {IV('Т'), 'T', 0}, // 0422 + {IV('У'), 'Y', 0}, + {IV('Ф'), 'o', 0}, + {IV('Х'), 'X', 0}, + {IV('Ц'), 'U', 0}, + {IV('Ч'), 'y', 0}, + {IV('Ш'), 'W', 0}, + {IV('Щ'), 'W', 0}, + {IV('Ъ'), 'b', 0}, + {IV('Ы'), 'b', '|'}, + {IV('Ь'), 'b'}, + {IV('Э'), 'e'}, + {IV('Ю'), '|', 'O'}, + {IV('Я'), '9', '|'}, // 042F + + {IV('а'), 'a', 0}, // 0430 + {IV('б'), '6', 0}, // 0431 + {IV('в'), 'B', 0}, // 0432, + {IV('г'), 'r', 0}, // 0433 + {IV('д'), 'a', 0}, // 0434, + {IV('е'), 'e', 0}, // 0435 + {IV('ж'), '*', 0}, // 0436 + {IV('з'), 'e', 0}, // 0437, + {IV('и'), 'u', 0}, // 0438 + {IV('й'), 'u', 0}, // 0439, + {IV('к'), 'k', 0}, // 043A + {IV('л'), 'n', 0}, + {IV('м'), 'm', 0}, + {IV('н'), 'H', 0}, + {IV('о'), 'o', 0}, + {IV('п'), 'n', 0}, + {IV('р'), 'p', 0}, + {IV('с'), 'c', 0}, + {IV('т'), 't', 0}, + {IV('у'), 'y', 0}, + {IV('ф'), 'q', 'p'}, + {IV('х'), 'x', 0}, + {IV('ц'), 'u', 0}, + {IV('ч'), 'y', 0}, + {IV('ш'), 'w', 0}, + {IV('щ'), 'w', 0}, + {IV('ъ'), 'b', 0}, + {IV('ы'), 'b', '|'}, + {IV('ь'), 'b', 0}, + {IV('э'), 'e', 0}, + {IV('ю'), '|', 'o'}, + {IV('я'), 'g', 0}, // 044F + {IV('ё'), 'e', 0}, // 0451 + #endif + + {IV('•'), '.', 0}, // 2022 · + {IV('℞'), 'P', 'x'}, // 211E ℞ Pt ASCII 158 + {IV('™'), 'T', 'M'}, // 2122 + {IV('←'), '<', '-'}, // 2190 + {IV('→'), '-', '>'}, // 2192, Marlin special: '⮈⮉⮊⮋➤→⏵➟➠➡' LCD_STR_ARROW_RIGHT (0x03) + //{IV('↰'), '<', 0}, // 21B0, Marlin special: '⮥⮭⮉⇧↑↰⤴' LCD_STR_UPLEVEL (0x04) + {IV('↰'), 0x03, 0}, // 21B0, Marlin special: '⮥⮭⮉⇧↑↰⤴' LCD_STR_UPLEVEL (0x04) + {IV('↻'), 0x04, 0}, // 21BB Marlin special: '↻↺⟳⟲' LCD_STR_REFRESH (0x01) + {IV('∼'), '~', 0}, // 223C + {IV('≈'), '~', '='}, // 2248 + {IV('≠'), '!', '='}, // 2260 + {IV('≡'), '=', 0}, // 2261 + {IV('≤'), '<', '='},// 2264, ≤≥ ⩽⩾ + {IV('≥'), '>', '='}, // 2265 + {IV('⏱'), 0x07, 0}, // 23F1, Marlin special: '🕐🕑🕒🕓🕔🕕🕖🕗🕘🕙🕚🕛🕜🕝🕞🕟🕠🕡🕢🕣🕤🕥🕦🕧 ⌚⌛⏰⏱⏳⧖⧗' LCD_STR_CLOCK (0x05) + + {IV('゠'), '=', 0}, // 30A0 + + // ⏰⏱⏲⏳◴◵◶◷ + // ⏻⏼♁♂ + //{IV(''), 0x00, 0}, // Marlin special: '' LCD_STR_BEDTEMP (0x07) + {IV('🌡'), 0x02, 0}, // D83CDF21 Marlin special: '🌡' LCD_STR_THERMOMETER (0x08) + {IV('📂'), 0x05, 0}, // D83DDCC2 Marlin special: '📁📂' LCD_STR_FOLDER (0x02) + //{IV(''), 0x06, 0}, // Marlin special: '' LCD_STR_FEEDRATE (0x06) +}; diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp new file mode 100644 index 0000000000..20b3727dbc --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp @@ -0,0 +1,193 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * lcd/e3v2/marlinui/lcdprint_dwin.cpp + * + * Due to DWIN hardware limitations simplified characters are used + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if IS_DWIN_MARLINUI + +#include "lcdprint_dwin.h" +#include "dwin_lcd.h" +#include "dwin_string.h" + +#include "../../marlinui.h" +#include "../../../MarlinCore.h" + +#include + +cursor_t cursor; + +extern dwin_font_t dwin_font; + +void lcd_moveto_xy(const lcd_uint_t x, const lcd_uint_t y) { cursor.x = x; cursor.y = y; } + +void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { + cursor.x = col * dwin_font.width; + cursor.y = (row * (dwin_font.height + EXTRA_ROW_HEIGHT)) + (EXTRA_ROW_HEIGHT / 2); +} + +inline void lcd_advance_cursor() { cursor.x += dwin_font.width; } + +void lcd_put_int(const int i) { + // TODO: Draw an int at the cursor position, advance the cursor +} + +int lcd_put_dwin_string() { + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); + cursor.x += dwin_string.length() * dwin_font.width; + return dwin_string.length(); +} + +// return < 0 on error +// return the advanced cols +int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { + dwin_string.set(); + dwin_string.add(c); + dwin_string.truncate(max_length); + // Draw the char(s) at the cursor and advance the cursor + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); + cursor.x += dwin_string.length() * dwin_font.width; + return dwin_string.length(); +} + +/** + * @brief Draw a UTF-8 string + * + * @param utf8_str : the UTF-8 string + * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) + * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) + * + * @return the number of pixels advanced + * + * Draw a UTF-8 string + */ +static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(uint8_t * str), pixel_len_t max_length) { + uint8_t *p = (uint8_t *)utf8_str; + dwin_string.set(); + while (dwin_string.length() < max_length) { + wchar_t ch = 0; + p = get_utf8_value_cb(p, cb_read_byte, &ch); + if (!ch) break; + dwin_string.add(ch); + } + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); + cursor.x += dwin_string.length() * dwin_font.width; + return dwin_string.length(); +} + +int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); +} + +int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_str_P, read_byte_rom, max_length); +} + +lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { + dwin_string.set(); + dwin_string.add((uint8_t*)pstr, ind, (uint8_t*)inStr); + dwin_string.truncate(maxlen); + DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); + cursor.x += dwin_string.length() * dwin_font.width; + return dwin_string.length(); +} + +#if ENABLED(DEBUG_LCDPRINT) + + int test_dwin_charmap(dwin_charmap_t *data, size_t size, char *name, char flg_show_contents) { + int ret; + size_t idx = 0; + dwin_charmap_t preval = { 0, 0, 0 }; + dwin_charmap_t pinval = { 0, 0, 0 }; + char flg_error = 0; + + int i; + + TRACE("Test %s\n", name); + + for (i = 0; i < size; i ++) { + memcpy_P(&pinval, &(data[i]), sizeof(pinval)); + + if (flg_show_contents) { + #if 1 + TRACE("[% 4d] % 6" PRIu32 "(0x%04" PRIX32 ") --> 0x%02X,0x%02X%s\n", i, pinval.uchar, pinval.uchar, (unsigned int)(pinval.idx), (unsigned int)(pinval.idx2), (preval.uchar < pinval.uchar?"":" <--- ERROR")); + #else + TRACE("[% 4d]", i); + TRACE("% 6" PRIu32 "(0x%04" PRIX32 "),", pinval.uchar, pinval.uchar); + TRACE("0x%02X,", (unsigned int)(pinval.idx)); + TRACE("0x%02X,", (unsigned int)(pinval.idx2)); + TRACE("%s", (preval.uchar < pinval.uchar?"":" <--- ERROR")); + #endif + } + if (preval.uchar >= pinval.uchar) { + flg_error = 1; + //TRACE("Error: out of order in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + memcpy(&preval, &pinval, sizeof(pinval)); + + ret = pf_bsearch_r((void *)data, size, pf_bsearch_cb_comp_dwinmap_pgm, (void *)&pinval, &idx); + if (ret < 0) { + flg_error = 1; + TRACE("Error: not found item in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + if (idx != i) { + flg_error = 1; + TRACE("Error: wrong index found item in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + } + if (flg_error) { + TRACE("\nError: in array %s\n\n", name); + return -1; + } + TRACE("\nPASS array %s\n\n", name); + return 0; + } + + int test_dwin_charmap_all() { + int flg_error = 0; + if (test_dwin_charmap(g_dwin_charmap_device, COUNT(g_dwin_charmap_device), "g_dwin_charmap_device", 0) < 0) { + flg_error = 1; + test_dwin_charmap(g_dwin_charmap_device, COUNT(g_dwin_charmap_device), "g_dwin_charmap_device", 1); + } + if (test_dwin_charmap(g_dwin_charmap_common, COUNT(g_dwin_charmap_common), "g_dwin_charmap_common", 0) < 0) { + flg_error = 1; + test_dwin_charmap(g_dwin_charmap_common, COUNT(g_dwin_charmap_common), "g_dwin_charmap_common", 1); + } + if (flg_error) { + TRACE("\nFAILED in dwin tests!\n"); + return -1; + } + TRACE("\nPASS in dwin tests.\n"); + return 0; + } + +#endif // DEBUG_LCDPRINT + +#endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h new file mode 100644 index 0000000000..692f448e76 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../../lcdprint.h" + +typedef struct { int16_t x, y; } cursor_t; +extern cursor_t cursor; + +int lcd_put_dwin_string(); +void lcd_moveto_xy(const lcd_uint_t, const lcd_uint_t); diff --git a/Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h b/Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h new file mode 100644 index 0000000000..de87c30b6b --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h @@ -0,0 +1,146 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * lcd/e3v2/marlinui/lcdprint_dwin.h + */ + +#include "../../../inc/MarlinConfigPre.h" +#include "dwin_lcd.h" + +typedef uint16_t dwin_coord_t; // Screen can be pretty big +typedef uint16_t lcd_uint_t; +typedef int16_t lcd_int_t; + +typedef struct { + uint8_t index, width, height; + uint16_t fg, bg; + bool solid; +} dwin_font_t; + +extern dwin_font_t dwin_font; + +// Only Western languages support big / small fonts +//#if DISABLED(DISPLAY_CHARSET_ISO10646_1) +// #undef USE_BIG_EDIT_FONT +// #undef USE_SMALL_INFOFONT +//#endif + +#if ENABLED(USE_BIG_EDIT_FONT) + #define DWIN_FONT_EDIT font10x20 +#else + #define DWIN_FONT_EDIT font8x16 +#endif + +#define DWIN_FONT_INFO font8x16 + +#if DWIN_FONT_MENU == font6x12 + #define MENU_FONT_WIDTH 6 + #define MENU_FONT_ASCENT 10 + #define MENU_FONT_DESCENT 2 +#elif DWIN_FONT_MENU == font8x16 + #define MENU_FONT_WIDTH 8 + #define MENU_FONT_ASCENT 13 + #define MENU_FONT_DESCENT 3 +#elif DWIN_FONT_MENU == font10x20 + #define MENU_FONT_WIDTH 10 + #define MENU_FONT_ASCENT 16 + #define MENU_FONT_DESCENT 4 +#endif +#define MENU_FONT_HEIGHT (MENU_FONT_ASCENT + MENU_FONT_DESCENT) + +#define EXTRA_ROW_HEIGHT 8 +#define MENU_LINE_HEIGHT (MENU_FONT_HEIGHT + EXTRA_ROW_HEIGHT) + +#if DWIN_FONT_EDIT == font6x12 + #define EDIT_FONT_WIDTH 6 + #define EDIT_FONT_ASCENT 10 + #define EDIT_FONT_DESCENT 2 +#elif DWIN_FONT_EDIT == font8x16 + #define EDIT_FONT_WIDTH 8 + #define EDIT_FONT_ASCENT 13 + #define EDIT_FONT_DESCENT 3 +#elif DWIN_FONT_EDIT == font10x20 + #define EDIT_FONT_WIDTH 10 + #define EDIT_FONT_ASCENT 16 + #define EDIT_FONT_DESCENT 4 +#endif +#define EDIT_FONT_HEIGHT (EDIT_FONT_ASCENT + EDIT_FONT_DESCENT) + +#if DWIN_FONT_INFO == font6x12 + #define INFO_FONT_WIDTH 6 + #define INFO_FONT_ASCENT 10 + #define INFO_FONT_DESCENT 2 +#elif DWIN_FONT_INFO == font8x16 + #define INFO_FONT_WIDTH 8 + #define INFO_FONT_ASCENT 13 + #define INFO_FONT_DESCENT 3 +#elif DWIN_FONT_INFO == font10x20 + #define INFO_FONT_WIDTH 10 + #define INFO_FONT_ASCENT 16 + #define INFO_FONT_DESCENT 4 +#endif +#define INFO_FONT_HEIGHT (INFO_FONT_ASCENT + INFO_FONT_DESCENT) + +#if DWIN_FONT_STAT == font6x12 + #define STAT_FONT_WIDTH 6 + #define STAT_FONT_ASCENT 10 + #define STAT_FONT_DESCENT 2 +#elif DWIN_FONT_STAT == font8x16 + #define STAT_FONT_WIDTH 8 + #define STAT_FONT_ASCENT 13 + #define STAT_FONT_DESCENT 3 +#elif DWIN_FONT_STAT == font10x20 + #define STAT_FONT_WIDTH 10 + #define STAT_FONT_ASCENT 16 + #define STAT_FONT_DESCENT 4 +#elif DWIN_FONT_STAT == font12x24 + #define STAT_FONT_WIDTH 12 + #define STAT_FONT_ASCENT 19 + #define STAT_FONT_DESCENT 5 +#elif DWIN_FONT_STAT == font14x28 + #define STAT_FONT_WIDTH 14 + #define STAT_FONT_ASCENT 22 + #define STAT_FONT_DESCENT 6 +#elif DWIN_FONT_STAT == font16x32 + #define STAT_FONT_WIDTH 16 + #define STAT_FONT_ASCENT 26 + #define STAT_FONT_DESCENT 6 +#elif DWIN_FONT_STAT == font20x40 + #define STAT_FONT_WIDTH 20 + #define STAT_FONT_ASCENT 32 + #define STAT_FONT_DESCENT 8 +#elif DWIN_FONT_STAT == font24x48 + #define STAT_FONT_WIDTH 24 + #define STAT_FONT_ASCENT 38 + #define STAT_FONT_DESCENT 10 +#elif DWIN_FONT_STAT == font28x56 + #define STAT_FONT_WIDTH 28 + #define STAT_FONT_ASCENT 44 + #define STAT_FONT_DESCENT 12 +#elif DWIN_FONT_STAT == font32x64 + #define STAT_FONT_WIDTH 32 + #define STAT_FONT_ASCENT 50 + #define STAT_FONT_DESCENT 14 +#endif +#define STAT_FONT_HEIGHT (STAT_FONT_ASCENT + STAT_FONT_DESCENT) diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp new file mode 100644 index 0000000000..7655e059e2 --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -0,0 +1,595 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if IS_DWIN_MARLINUI + +#include "marlinui_dwin.h" +#include "dwin_lcd.h" +#include "dwin_string.h" + +//#include "../../lcdprint.h" +#include "lcdprint_dwin.h" +#include "../../fontutils.h" +#include "../../../libs/numtostr.h" +#include "../../marlinui.h" + +#include "../../../sd/cardreader.h" +#include "../../../module/motion.h" +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" + +#if ENABLED(SDSUPPORT) + #include "../../../libs/duration_t.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +// DWIN printing specifies the font on each string operation +// but we'll make the font modal for Marlin +dwin_font_t dwin_font = { font8x16, 8, 16, Color_White, Color_Bg_Black, true }; +void MarlinUI::set_font(const uint8_t font_nr) { + if (font_nr != dwin_font.index) { + dwin_font.index = font_nr; + uint8_t w, h; + switch (font_nr) { + default: + case font6x12: w = 6; h = 12; break; + case font8x16: w = 8; h = 16; break; + case font10x20: w = 10; h = 20; break; + case font12x24: w = 12; h = 24; break; + case font14x28: w = 14; h = 28; break; + case font16x32: w = 16; h = 32; break; + case font20x40: w = 20; h = 40; break; + case font24x48: w = 24; h = 48; break; + case font28x56: w = 28; h = 56; break; + case font32x64: w = 32; h = 64; break; + } + dwin_font.width = w; + dwin_font.height = h; + // TODO: Array with dimensions, auto fit menu items, + // update char width / height of the screen based on + // new (fixed-width) font size. + } +} + +// This display is always detected +bool MarlinUI::detected() { return true; } + +// Initialize or re-initialize the LCD +void MarlinUI::init_lcd() { + DWIN_Startup(); + + // Load the assets JPG (currently just the status screen 'icon') + DWIN_JPG_CacheToN(1, DWIN_MarlinUI_Assets); +} + +// This LCD should clear where it will draw anew +void MarlinUI::clear_lcd() { + DWIN_ICON_AnimationControl(0x0000); // disable all icon animations + DWIN_Frame_Clear(Color_Bg_Black); + DWIN_UpdateLCD(); + + did_first_redraw = false; +} + +#if ENABLED(SHOW_BOOTSCREEN) + + void MarlinUI::show_bootscreen() { + clear_lcd(); + dwin_string.set(F(SHORT_BUILD_VERSION)); + + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + #define LOGO_CENTER ((LCD_PIXEL_WIDTH) / 2) + #define INFO_CENTER LOGO_CENTER + #define VERSION_Y 330 + DWIN_ICON_Show(BOOT_ICON, ICON_MarlinBoot, LOGO_CENTER - 266 / 2, 15); + DWIN_ICON_Show(BOOT_ICON, ICON_OpenSource, LOGO_CENTER - 174 / 2, 280); + DWIN_ICON_Show(BOOT_ICON, ICON_GitHubURL, LOGO_CENTER - 180 / 2, 420); + DWIN_ICON_Show(BOOT_ICON, ICON_MarlinURL, LOGO_CENTER - 100 / 2, 440); + DWIN_ICON_Show(BOOT_ICON, ICON_Copyright, LOGO_CENTER - 126 / 2, 460); + #else + #define LOGO_CENTER (280 / 2) + #define INFO_CENTER ((LCD_PIXEL_WIDTH) - 200 / 2) + #define VERSION_Y 84 + DWIN_ICON_Show(BOOT_ICON, ICON_MarlinBoot, LOGO_CENTER - 266 / 2, 15); + DWIN_ICON_Show(BOOT_ICON, ICON_OpenSource, INFO_CENTER - 174 / 2, 60); + DWIN_ICON_Show(BOOT_ICON, ICON_GitHubURL, INFO_CENTER - 180 / 2, 130); + DWIN_ICON_Show(BOOT_ICON, ICON_MarlinURL, INFO_CENTER - 100 / 2, 152); + DWIN_ICON_Show(BOOT_ICON, ICON_Copyright, INFO_CENTER - 126 / 2, 200); + #endif + + DWIN_Draw_String(false, font10x20, Color_Yellow, Color_Bg_Black, INFO_CENTER - (dwin_string.length() * 10) / 2, VERSION_Y, S(dwin_string.string())); + DWIN_UpdateLCD(); + } + + void MarlinUI::bootscreen_completion(const millis_t sofar) { + if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); + clear_lcd(); + } + +#endif + +// The kill screen is displayed for unrecoverable conditions +void MarlinUI::draw_kill_screen() { + set_font(DWIN_FONT_ALERT); + DWIN_Frame_Clear(Color_Bg_Black); + dwin_font.fg = Color_Error_Red; + dwin_font.solid = false; + DWIN_Draw_Rectangle(1, Color_Bg_Window, 20, 20, LCD_PIXEL_WIDTH - 20, LCD_PIXEL_HEIGHT - 20); + // make the frame a few pixels thick + DWIN_Draw_Rectangle(0, Color_Yellow, 20, 20, LCD_PIXEL_WIDTH - 20, LCD_PIXEL_HEIGHT - 20); + DWIN_Draw_Rectangle(0, Color_Yellow, 21, 21, LCD_PIXEL_WIDTH - 21, LCD_PIXEL_HEIGHT - 21); + DWIN_Draw_Rectangle(0, Color_Yellow, 22, 22, LCD_PIXEL_WIDTH - 22, LCD_PIXEL_HEIGHT - 22); + + uint8_t cx = (LCD_PIXEL_WIDTH / dwin_font.width / 2), + cy = (LCD_PIXEL_HEIGHT / dwin_font.height / 2); + + #if ENABLED(DWIN_MARLINUI_LANDSCAPE) + cx += (96 / 2 / dwin_font.width); + DWIN_ICON_Show(ICON, ICON_Halted, 40, (LCD_PIXEL_HEIGHT - 96) / 2); + #else + DWIN_ICON_Show(ICON, ICON_Halted, (LCD_PIXEL_WIDTH - 96) / 2, 40); + #endif + + uint8_t slen = utf8_strlen(status_message); + lcd_moveto(cx - (slen / 2), cy - 1); + lcd_put_u8str(status_message); + + slen = utf8_strlen(S(GET_TEXT_F(MSG_HALTED))); + lcd_moveto(cx - (slen / 2), cy); + lcd_put_u8str_P((const char*)GET_TEXT_F(MSG_HALTED)); + + slen = utf8_strlen(S(GET_TEXT_F(MSG_HALTED))); + lcd_moveto(cx - (slen / 2), cy + 1); + lcd_put_u8str_P((const char*)GET_TEXT_F(MSG_HALTED)); +} + +// +// Status Message +// +void MarlinUI::draw_status_message(const bool blink) { + set_font(DWIN_FONT_STAT); + dwin_font.solid = true; + dwin_font.fg = Color_White; + dwin_font.bg = Color_Bg_Black; + lcd_moveto_xy(0, LCD_PIXEL_HEIGHT - (STAT_FONT_HEIGHT) - 1); + + constexpr uint8_t max_status_chars = (LCD_PIXEL_WIDTH) / (STAT_FONT_WIDTH); + + auto status_changed = []{ + static uint16_t old_hash = 0x0000; + uint16_t hash = 0x0000; + for (uint8_t i = 0; i < MAX_MESSAGE_LENGTH; i++) { + const char c = ui.status_message[i]; + if (!c) break; + hash = ((hash << 1) | (hash >> 15)) ^ c; + } + const bool hash_changed = hash != old_hash; + old_hash = hash; + return hash_changed || !ui.did_first_redraw; + }; + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + static bool last_blink = false; + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + // If the string fits into the LCD, just print it and do not scroll it + if (slen <= max_status_chars) { + + if (status_changed()) { + + // The string isn't scrolling and may not fill the screen + lcd_put_u8str(status_message); + + // Fill the rest with spaces + while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; } + } + } + else { + // String is larger than the available line space + + // Get a pointer to the next valid UTF8 character + // and the string remaining length + uint8_t rlen; + const char *stat = status_and_len(rlen); + lcd_put_u8str_max(stat, max_status_chars); + + // If the string doesn't completely fill the line... + if (rlen < max_status_chars) { + lcd_put_wchar('.'); // Always at 1+ spaces left, draw a dot + uint8_t chars = max_status_chars - rlen; // Amount of space left in characters + if (--chars) { // Draw a second dot if there's space + lcd_put_wchar('.'); + if (--chars) + lcd_put_u8str_max(status_message, chars); // Print a second copy of the message + } + } + + if (last_blink != blink) { + last_blink = blink; + advance_status_scroll(); + } + } + + #else + + UNUSED(blink); + + if (status_changed()) { + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + // Just print the string to the LCD + lcd_put_u8str_max(status_message, max_status_chars); + + // Fill the rest with spaces if there are missing spaces + while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; } + } + + #endif +} + +#if HAS_LCD_MENU + + #include "../../menu/menu.h" + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + + dwin_font.solid = false; + dwin_font.fg = Color_White; + dwin_string.set("E"); + dwin_string.add('1' + extruder); + dwin_string.add(' '); + dwin_string.add(i16tostr3rj(thermalManager.degHotend(extruder))); + dwin_string.add('/'); + if (get_blink() || !thermalManager.heater_idle[thermalManager.idle_index_for_id(extruder)].timed_out) + dwin_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder))); + else + dwin_string.add(PSTR(" ")); + + lcd_moveto(LCD_WIDTH - dwin_string.length(), row); + lcd_put_dwin_string(); + } + + #endif + + // Set the colors for a menu item based on whether it is selected + static bool mark_as_selected(const uint8_t row, const bool sel, const bool is_static=false) { + const dwin_coord_t y = row * (MENU_LINE_HEIGHT) + 1; + if (y >= LCD_PIXEL_HEIGHT) return false; + + if (is_static && sel) + DWIN_Draw_Box(1, Color_Bg_Heading, 0, y, LCD_PIXEL_WIDTH, MENU_LINE_HEIGHT - 1); + else { + #if ENABLED(MENU_HOLLOW_FRAME) + DWIN_Draw_Box(1, Color_Bg_Black, 0, y, LCD_PIXEL_WIDTH, MENU_LINE_HEIGHT - 1); + if (sel) DWIN_Draw_Box(0, Select_Color, 0, y, LCD_PIXEL_WIDTH, MENU_LINE_HEIGHT - 1); + #else + DWIN_Draw_Box(1, sel ? Select_Color : Color_Bg_Black, 0, y, LCD_PIXEL_WIDTH, MENU_LINE_HEIGHT - 1); + #endif + } + + return true; + } + + // Draw a static line of text in the same idiom as a menu item + + void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { + // Call mark_as_selected to draw a bigger selection box + // and draw the text without a background + if (mark_as_selected(row, (bool)(style & SS_INVERT), true)) { + ui.set_font(DWIN_FONT_MENU); + dwin_font.solid = false; + dwin_font.fg = Color_White; + + dwin_string.set(); + const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, + vlen = vstr ? utf8_strlen(vstr) : 0; + if (style & SS_CENTER) { + int8_t pad = (LCD_WIDTH - 1 - plen - vlen) / 2; + while (--pad) dwin_string.add(' '); + } + + if (plen) dwin_string.add((uint8_t*)pstr, itemIndex, (uint8_t*)itemString); + if (vlen) dwin_string.add((uint8_t*)vstr); + if (style & SS_CENTER) { + int8_t pad = (LCD_WIDTH - 1 - plen - vlen) / 2; + while (--pad) dwin_string.add(' '); + } + + lcd_moveto(1, row); + lcd_put_dwin_string(); + } + } + + // Draw a generic menu item + void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char, const char post_char) { + if (mark_as_selected(row, sel)) { + ui.set_font(DWIN_FONT_MENU); + dwin_font.solid = false; + dwin_font.fg = Color_White; + + dwin_string.set(pstr, itemIndex, itemString); + + pixel_len_t n = LCD_WIDTH - 1 - dwin_string.length(); + while (--n > 1) dwin_string.add(' '); + + dwin_string.add(post_char); + + lcd_moveto(1, row); + lcd_put_dwin_string(); + } + } + + // + // Draw a menu item with an editable value + // + void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) { + if (mark_as_selected(row, sel)) { + ui.set_font(DWIN_FONT_MENU); + dwin_font.solid = false; + dwin_font.fg = Color_White; + + const uint8_t vallen = (pgm ? utf8_strlen_P(data) : utf8_strlen(S(data))); + + dwin_string.set(pstr, itemIndex, itemString); + if (vallen) dwin_string.add(':'); + + lcd_moveto(1, row); + lcd_put_dwin_string(); + + if (vallen) { + dwin_font.fg = Color_Yellow; + dwin_string.set(data); + lcd_moveto(LCD_WIDTH - vallen - 1, row); + lcd_put_dwin_string(); + } + } + } + + // + // Draw an edit screen with label and current value + // + void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { + ui.encoder_direction_normal(); + + const dwin_coord_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); + + dwin_string.set(); + dwin_string.add((uint8_t*)pstr, itemIndex); + if (vallen) dwin_string.add(':'); // If a value is included, add a colon + + // Assume the label is alpha-numeric (with a descender) + const uint16_t row = (LCD_HEIGHT / 2) - 1; + + dwin_font.fg = Color_White; + dwin_font.solid = true; + lcd_moveto((LCD_WIDTH - labellen + !!vallen) / 2, row); + lcd_put_dwin_string(); + + // If a value is included, print the value in larger text below the label + if (vallen) { + dwin_string.set(); + dwin_string.add(value); + + const dwin_coord_t by = (row * MENU_LINE_HEIGHT) + MENU_FONT_HEIGHT + EXTRA_ROW_HEIGHT / 2; + DWIN_Draw_String(true, font16x32, Color_Yellow, Color_Bg_Black, (LCD_PIXEL_WIDTH - vallen * 16) / 2, by, S(dwin_string.string())); + + extern screenFunc_t _manual_move_func_ptr; + if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) { + + const dwin_coord_t slider_length = LCD_PIXEL_WIDTH - TERN(DWIN_MARLINUI_LANDSCAPE, 120, 20), + slider_height = 16, + slider_x = (LCD_PIXEL_WIDTH - slider_length) / 2, + slider_y = by + 32 + 4, + amount = ui.encoderPosition * slider_length / maxEditValue; + + DWIN_Draw_Rectangle(1, Color_Bg_Window, slider_x - 1, slider_y - 1, slider_x - 1 + slider_length + 2 - 1, slider_y - 1 + slider_height + 2 - 1); + if (amount > 0) + DWIN_Draw_Box(1, BarFill_Color, slider_x, slider_y, amount, slider_height); + if (amount < slider_length) + DWIN_Draw_Box(1, Color_Bg_Black, slider_x + amount, slider_y, slider_length - amount, slider_height); + } + } + } + + inline void draw_boxed_string(const bool yesopt, PGM_P const pstr, const bool inv) { + const uint8_t len = utf8_strlen_P(pstr), + mar = TERN(DWIN_MARLINUI_PORTRAIT, 1, 4), + col = yesopt ? LCD_WIDTH - mar - len : mar, + row = (LCD_HEIGHT >= 8 ? LCD_HEIGHT / 2 + 3 : LCD_HEIGHT - 1); + lcd_moveto(col, row); + DWIN_Draw_Box(1, inv ? Select_Color : Color_Bg_Black, cursor.x - dwin_font.width, cursor.y + 1, dwin_font.width * (len + 2), dwin_font.height + 2); + lcd_put_u8str_P(col, row, pstr); + } + + void MenuItem_confirm::draw_select_screen( + PGM_P const yes, PGM_P const no, const bool yesno, + PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ + ) { + ui.set_font(DWIN_FONT_MENU); + dwin_font.solid = false; + dwin_font.fg = Color_White; + ui.draw_select_screen_prompt(pref, string, suff); + draw_boxed_string(false, no, !yesno); + draw_boxed_string(true, yes, yesno); + } + + #if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + if (mark_as_selected(row, sel)) { + dwin_string.set(); + + uint8_t maxlen = LCD_WIDTH - 1; + if (isDir) { + dwin_string.add(LCD_STR_FOLDER " "); + maxlen -= 2; + } + + dwin_string.add((uint8_t*)ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); + uint8_t n = maxlen - dwin_string.length(); + while (n > 0) { dwin_string.add(' '); --n; } + lcd_moveto(1, row); + lcd_put_dwin_string(); + } + } + + #endif // SDSUPPORT + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * UBL LCD "radar" map data + */ + #define MAP_UPPER_LEFT_CORNER_X 5 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 5 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 262 // 272 - 10 + #define MAP_MAX_PIXELS_Y 262 + + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + // Scale the box pixels appropriately + dwin_coord_t x_map_pixels = ((MAP_MAX_PIXELS_X - 4) / (GRID_MAX_POINTS_X)) * (GRID_MAX_POINTS_X), + y_map_pixels = ((MAP_MAX_PIXELS_Y - 4) / (GRID_MAX_POINTS_Y)) * (GRID_MAX_POINTS_Y), + + pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X), + pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y), + + x_offset = MAP_UPPER_LEFT_CORNER_X + 1 + (MAP_MAX_PIXELS_X - x_map_pixels - 2) / 2, + y_offset = MAP_UPPER_LEFT_CORNER_Y + 1 + (MAP_MAX_PIXELS_Y - y_map_pixels - 2) / 2; + + // Clear the Mesh Map + + // First draw the bigger box in White so we have a border around the mesh map box + DWIN_Draw_Rectangle(1, Color_White, x_offset - 2, y_offset - 2, x_offset + 2 + x_map_pixels, y_offset + 2 + y_map_pixels); + // Now actually clear the mesh map box + DWIN_Draw_Rectangle(1, Color_Bg_Black, x_offset, y_offset, x_offset + x_map_pixels, y_offset + y_map_pixels); + + // Fill in the Specified Mesh Point + + const uint8_t y_plot_inv = (GRID_MAX_POINTS_Y - 1) - y_plot; // The origin is typically in the lower right corner. We need to + // invert the Y to get it to plot in the right location. + + const dwin_coord_t by = y_offset + y_plot_inv * pixels_per_y_mesh_pnt; + DWIN_Draw_Rectangle(1, Select_Color, + x_offset + (x_plot * pixels_per_x_mesh_pnt), by, + x_offset + (x_plot * pixels_per_x_mesh_pnt) + pixels_per_x_mesh_pnt, by + pixels_per_y_mesh_pnt + ); + + // Display Mesh Point Locations + const dwin_coord_t sx = x_offset + pixels_per_x_mesh_pnt / 2; + dwin_coord_t y = y_offset + pixels_per_y_mesh_pnt / 2; + for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_y_mesh_pnt) + for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) + DWIN_Draw_Point(Color_White, 1, 1, x, y); + + // Put Relevant Text on Display + + // Show X and Y positions at top of screen + dwin_font.fg = Color_White; + dwin_font.solid = true; + const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, + lpos = pos.asLogical(); + + lcd_moveto( + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, 1), + TERN(DWIN_MARLINUI_LANDSCAPE, 1, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 1) + ); + lcd_put_u8str_P(X_LBL); + lcd_put_u8str(ftostr52(lpos.x)); + lcd_moveto( + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, 1), + TERN(DWIN_MARLINUI_LANDSCAPE, 3, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 2) + ); + lcd_put_u8str_P(Y_LBL); + lcd_put_u8str(ftostr52(lpos.y)); + + // Print plot position + dwin_string.set("("); + dwin_string.add(i8tostr3rj(x_plot)); + dwin_string.add(","); + dwin_string.add(i8tostr3rj(y_plot)); + dwin_string.add(")"); + lcd_moveto( + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length()), + TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 2, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 1) + ); + lcd_put_dwin_string(); + + // Show the location value + dwin_string.set(Z_LBL); + if (!isnan(ubl.z_values[x_plot][y_plot])) + dwin_string.add(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + dwin_string.add(PSTR(" -----")); + lcd_moveto( + TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length()), + TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 1, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 2) + ); + lcd_put_dwin_string(); + } + + #endif // AUTO_BED_LEVELING_UBL + + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY, BABYSTEP_GFX_OVERLAY) + + void _lcd_zoffset_overlay_gfx(const float zvalue) { + // Determine whether the user is raising or lowering the nozzle. + static int8_t dir; + static float old_zvalue; + if (zvalue != old_zvalue) { + dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; + old_zvalue = zvalue; + } + + const int rot_up = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCCW, ICON_RotateCW), + rot_down = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCW, ICON_RotateCCW); + + const int nozzle = (LCD_PIXEL_WIDTH / 2) - 20; + + // Draw a representation of the nozzle + DWIN_Draw_Box(1, Color_Bg_Black, nozzle + 3, 8, 48, 52); // 'clear' the area where the nozzle is drawn in case it was moved up/down + DWIN_ICON_Show(ICON, ICON_HotendOff, nozzle + 3, 10 - dir); + DWIN_ICON_Show(ICON, ICON_BedLine, nozzle, 10 + 36); + + // Draw cw/ccw indicator and up/down arrows + const int arrow_y = LCD_PIXEL_HEIGHT / 2 - 24; + DWIN_ICON_Show(ICON, ICON_DownArrow, 0, arrow_y - dir); + DWIN_ICON_Show(ICON, rot_down, 48, arrow_y); + + DWIN_ICON_Show(ICON, ICON_UpArrow, LCD_PIXEL_WIDTH - 10 - (48*2), arrow_y - dir); + DWIN_ICON_Show(ICON, rot_up, LCD_PIXEL_WIDTH - 10 - 48, arrow_y); + } + + #endif // BABYSTEP_ZPROBE_GFX_OVERLAY || MESH_EDIT_GFX_OVERLAY + +#endif // HAS_LCD_MENU + +#endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp new file mode 100644 index 0000000000..0e2f3a3d4c --- /dev/null +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -0,0 +1,391 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if IS_DWIN_MARLINUI + +#include "marlinui_dwin.h" +#include "dwin_lcd.h" +#include "dwin_string.h" +#include "lcdprint_dwin.h" + +#include "../../fontutils.h" +#include "../../../libs/numtostr.h" +#include "../../marlinui.h" + +#include "../../../sd/cardreader.h" +#include "../../../module/motion.h" +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" + +#if ENABLED(SDSUPPORT) + #include "../../../libs/duration_t.h" +#endif + +#if ENABLED(LCD_SHOW_E_TOTAL) + #include "../../../MarlinCore.h" // for printingIsActive +#endif + +#define STATUS_HEATERS_X 15 +#define STATUS_HEATERS_Y 56 +#define STATUS_HEATERS_XSPACE 64 +#define STATUS_FAN_WIDTH 48 +#define STATUS_FAN_HEIGHT 48 +#define STATUS_FAN_Y STATUS_HEATERS_Y + 22 +#define STATUS_CHR_WIDTH 14 +#define STATUS_CHR_HEIGHT 28 + +// +// Before homing, blink '123' <-> '???'. +// Homed but unknown... '123' <-> ' '. +// Homed and known, display constantly. +// +FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink, const uint16_t x, const uint16_t y) { + uint8_t vallen = utf8_strlen(value); + + if (!ui.did_first_redraw) { + dwin_string.set(); + dwin_string.add('X' + axis); + DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x + (vallen * 14 - 14) / 2, y + 2, S(dwin_string.string())); + } + + dwin_string.set(); + if (blink) + dwin_string.add(value); + else { + if (!TEST(axis_homed, axis)) + while (const char c = *value++) dwin_string.add(c <= '.' ? c : '?'); + else { + #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) + if (!TEST(axis_trusted, axis)) + dwin_string.add(TERN1(DWIN_MARLINUI_PORTRAIT, axis == Z_AXIS) ? PSTR(" ") : PSTR(" ")); + else + #endif + dwin_string.add(value); + } + } + + // For E_TOTAL there may be some characters to cover up + if (BOTH(DWIN_MARLINUI_PORTRAIT, LCD_SHOW_E_TOTAL) && axis == X_AXIS) + dwin_string.add(" "); + + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + 32, S(dwin_string.string())); +} + +#if ENABLED(LCD_SHOW_E_TOTAL) + + FORCE_INLINE void _draw_e_value(const_float_t value, const uint16_t x, const uint16_t y) { + const uint8_t scale = value >= 100000.0f ? 10 : 1; // show cm after 99,999mm + + if (!ui.did_first_redraw) { + // Extra spaces so we don't have to clear the 'Y' label separately + dwin_string.set("E "); + DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x + (4 * 14 / 2) - 7, y + 2, S(dwin_string.string())); + } + + dwin_string.set(ui16tostr5rj(value / scale)); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + 32, S(dwin_string.string())); + + // Extra spaces so we don't have to clear out the Y value separately + DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, x + (5 * 14), y + 32, S(scale == 1 ? "mm " : "cm ")); + } + +#endif + +// +// Fan Icon and Percentage +// +FORCE_INLINE void _draw_fan_status(const uint16_t x, const uint16_t y) { + const uint16_t fanx = (4 * STATUS_CHR_WIDTH - STATUS_FAN_WIDTH) / 2; + const uint8_t fan_pct = thermalManager.scaledFanSpeedPercent(0); + const bool fan_on = !!fan_pct; + if (fan_on) { + DWIN_ICON_Animation(0, fan_on, ICON, ICON_Fan0, ICON_Fan3, x + fanx, y, 25); + dwin_string.set(i8tostr3rj(fan_pct)); + dwin_string.add('%'); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + STATUS_FAN_HEIGHT, S(dwin_string.string())); + } + else { + DWIN_ICON_Show(ICON, ICON_Fan0, x + fanx, y); + dwin_string.set(PSTR(" ")); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + STATUS_FAN_HEIGHT, S(dwin_string.string())); + } +} + +#if HOTENDS > 2 + #define HOTEND_STATS 3 +#elif HOTENDS > 1 + #define HOTEND_STATS 2 +#elif HAS_HOTEND + #define HOTEND_STATS 1 +#endif + +/** + * Draw a single heater icon with current and target temperature, at the given XY + */ +FORCE_INLINE void _draw_heater_status(const heater_id_t heater, const uint16_t x, const uint16_t y) { + + #if HAS_HOTEND + static celsius_t old_temp[HOTEND_STATS] = ARRAY_N_1(HOTEND_STATS, 500), + old_target[HOTEND_STATS] = ARRAY_N_1(HOTEND_STATS, 500); + static bool old_on[HOTEND_STATS] = ARRAY_N_1(HOTEND_STATS, false); + #endif + + #if HAS_HEATED_BED + static celsius_t old_bed_temp = 500, old_bed_target = 500; + static bool old_bed_on = false; + #endif + + #if HAS_HOTEND && HAS_HEATED_BED + const bool isBed = heater < 0; + const float tc = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)), + tt = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); + const uint8_t ta = isBed ? thermalManager.isHeatingBed() : thermalManager.isHeatingHotend(heater); + const bool c_draw = tc != (isBed ? old_bed_temp : old_temp[heater]), + t_draw = tt != (isBed ? old_bed_target : old_target[heater]), + i_draw = ta != (isBed ? old_bed_on : old_on[heater]); + if (isBed) { old_bed_temp = tc; old_bed_target = tt; old_bed_on = ta; } + else { old_temp[heater] = tc; old_target[heater] = tt; old_on[heater] = ta; } + #elif HAS_HOTEND + constexpr bool isBed = false; + const float tc = thermalManager.degHotend(heater), tt = thermalManager.degTargetHotend(heater); + const uint8_t ta = thermalManager.isHeatingHotend(heater); + const bool c_draw = tc != old_bed_temp, t_draw = tt != old_bed_target, i_draw = ta != old_bed_on; + old_temp[heater] = tc; old_target[heater] = tt; old_on[heater] = ta; + #elif HAS_HEATED_BED + constexpr bool isBed = true; + const float tc = thermalManager.degBed(), tt = thermalManager.degTargetBed(); + const uint8_t ta = thermalManager.isHeatingBed(); + const bool c_draw = tc != old_temp[heater], t_draw = tt != old_target[heater], i_draw = ta != old_on[heater]; + old_bed_temp = tc; old_bed_target = tt; old_bed_on = ta; + #endif + + if (!ui.did_first_redraw || t_draw) { + dwin_string.set(i16tostr3rj(tt + 0.5)); + dwin_string.add(LCD_STR_DEGREE); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y, S(dwin_string.string())); + } + + if (!ui.did_first_redraw || i_draw) + DWIN_ICON_Show(ICON, (isBed ? ICON_BedOff : ICON_HotendOff) + ta, x, y + STATUS_CHR_HEIGHT + 2); + + if (!ui.did_first_redraw || c_draw) { + dwin_string.set(i16tostr3rj(tc + 0.5)); + dwin_string.add(LCD_STR_DEGREE); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + 70, S(dwin_string.string())); + } +} + +/** + * Draw the current "feed rate" percentage preceded by the >> character + */ +FORCE_INLINE void _draw_feedrate_status(const char *value, uint16_t x, uint16_t y) { + if (!ui.did_first_redraw) { + dwin_string.set(LCD_STR_FEEDRATE); + DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, x, y, S(dwin_string.string())); + } + + dwin_string.set(value); + dwin_string.add(PSTR("%")); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x + 14, y, S(dwin_string.string())); +} + +/** + * Draw the MarlinUI Status Screen for Ender 3 V2 + */ +void MarlinUI::draw_status_screen() { + const bool blink = get_blink(); + + // Draw elements that never change + if (!ui.did_first_redraw) { + // Logo/Status Icon + #define STATUS_LOGO_WIDTH 128 + #define STATUS_LOGO_HEIGHT 40 + DWIN_ICON_Show(ICON, ICON_LOGO_Marlin, (LCD_PIXEL_WIDTH - (STATUS_LOGO_WIDTH)) / 2, ((STATUS_HEATERS_Y - 4) - (STATUS_LOGO_HEIGHT)) / 2); + + // Draw a frame around the x/y/z values + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + DWIN_Draw_Rectangle(0, Select_Color, 0, 193, LCD_PIXEL_WIDTH, 260); + #else + //DWIN_Draw_Rectangle(0, Select_Color, LCD_PIXEL_WIDTH - 106, 50, LCD_PIXEL_WIDTH - 1, 230); + #endif + } + + uint16_t hx = STATUS_HEATERS_X; + #if HAS_HOTEND + _draw_heater_status(H_E0, hx, STATUS_HEATERS_Y); + hx += STATUS_HEATERS_XSPACE; + #endif + #if HAS_MULTI_HOTEND + _draw_heater_status(H_E1, hx, STATUS_HEATERS_Y); + hx += STATUS_HEATERS_XSPACE; + #endif + #if HAS_HEATED_BED + _draw_heater_status(H_BED, hx, STATUS_HEATERS_Y); + #endif + + #if HAS_FAN + // Fan display, pinned to the right side + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + _draw_fan_status(LCD_PIXEL_WIDTH - STATUS_CHR_WIDTH * 4, STATUS_FAN_Y); + #else + _draw_fan_status(212, STATUS_FAN_Y); + #endif + #endif + + // Axis values + const xyz_pos_t lpos = current_position.asLogical(); + const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive()); UNUSED(show_e_total); + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + constexpr int16_t cpy = 195; + if (show_e_total) { + TERN_(LCD_SHOW_E_TOTAL, _draw_e_value(e_move_accumulator, 6, cpy)); + } + else { + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink, 6, cpy); + TERN_(HAS_Y_AXIS, _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink, 95, cpy)); + } + TERN_(HAS_Z_AXIS, _draw_axis_value(Z_AXIS, ftostr52sp(lpos.z), blink, 165, cpy)); + #else + constexpr int16_t cpx = LCD_PIXEL_WIDTH - 104; + _draw_axis_value(X_AXIS, ftostr52sp(lpos.x), blink, cpx, STATUS_HEATERS_Y); + TERN_(HAS_Y_AXIS, _draw_axis_value(Y_AXIS, ftostr52sp(lpos.y), blink, cpx, STATUS_HEATERS_Y + 59)); + TERN_(HAS_Z_AXIS, _draw_axis_value(Z_AXIS, ftostr52sp(lpos.z), blink, cpx, STATUS_HEATERS_Y + 118)); + #endif + + // Feedrate + static uint16_t old_fp = 0; + if (!ui.did_first_redraw || old_fp != feedrate_percentage) { + old_fp = feedrate_percentage; + _draw_feedrate_status(i16tostr3rj(feedrate_percentage), + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + 5, 290 + #else + 294, STATUS_HEATERS_Y + #endif + ); + } + + // + // Elapsed time + // + char buffer[14]; + duration_t time; + + #if ENABLED(DWIN_MARLINUI_PORTRAIT) + + // Portrait mode only shows one value at a time, and will rotate if ROTATE_PROGRESS_DISPLAY + dwin_string.set(); + char prefix = ' '; + #if ENABLED(SHOW_REMAINING_TIME) + if (TERN1(ROTATE_PROGRESS_DISPLAY, blink) && print_job_timer.isRunning()) { + time = get_remaining_time(); + prefix = 'R'; + } + else + #endif + time = print_job_timer.duration(); + + time.toDigital(buffer); + dwin_string.add(prefix); + dwin_string.add(buffer); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, (LCD_PIXEL_WIDTH - ((dwin_string.length() + 1) * 14)), 290, S(dwin_string.string())); + + #else + + // landscape mode shows both elapsed and remaining (if SHOW_REMAINING_TIME) + time = print_job_timer.duration(); + time.toDigital(buffer); + dwin_string.set(" "); + dwin_string.add(buffer); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 280, 100, S(dwin_string.string())); + + #if ENABLED(LCD_SHOW_E_TOTAL) + if (show_e_total && TERN1(SHOW_REMAINING_TIME, !blink)) { // if SHOW_REMAINING_TIME is also + const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // show cm after 99,000mm + + DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 249, 135, S("E")); + dwin_string.set(ui16tostr5rj(e_move_accumulator * escale)); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 263, 135, S(dwin_string.string())); + DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 333, 135, S(escale==1 ? "mm" : "cm")); + } + #endif + #if ENABLED(SHOW_REMAINING_TIME) + if (!show_e_total || blink) { + DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 249, 135, S(" R ")); + time = get_remaining_time(); + time.toDigital(buffer); + dwin_string.set(buffer); + DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 291, 135, S(dwin_string.string())); + } + #endif + #endif + + // + // Progress Bar + // + constexpr int16_t pb_margin = 5, pb_left = pb_margin, pb_height = 60, + pb_right = LCD_PIXEL_WIDTH - TERN(DWIN_MARLINUI_PORTRAIT, 0, 107) - pb_margin, + pb_bottom = TERN(DWIN_MARLINUI_PORTRAIT, 410, 230), + pb_top = pb_bottom - pb_height, + pb_width = pb_right - pb_left; + + const progress_t progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, get_progress_permyriad, get_progress_percent)(); + + if (!ui.did_first_redraw) + DWIN_Draw_Rectangle(0, Select_Color, pb_left, pb_top, pb_right, pb_bottom); // Outline + + static uint16_t old_solid = 50; + const uint16_t pb_solid = (pb_width - 2) * (progress / (PROGRESS_SCALE)) * 0.01f; + const bool p_draw = !ui.did_first_redraw || old_solid != pb_solid; + + if (p_draw) { + //if (pb_solid) + DWIN_Draw_Rectangle(1, Select_Color, pb_left + 1, pb_top + 1, pb_left + pb_solid, pb_bottom - 1); // Fill the solid part + + //if (pb_solid < old_solid) + DWIN_Draw_Rectangle(1, Color_Bg_Black, pb_left + 1 + pb_solid, pb_top + 1, pb_right - 1, pb_bottom - 1); // Erase the rest + + #if ENABLED(SHOW_SD_PERCENT) + dwin_string.set(TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE)))); + dwin_string.add(PSTR("%")); + DWIN_Draw_String( + false, font16x32, Percent_Color, Color_Bg_Black, + pb_left + (pb_width - dwin_string.length() * 16) / 2, + pb_top + (pb_height - 32) / 2, + S(dwin_string.string()) + ); + #endif + + old_solid = pb_solid; + } + + // + // Status Message + // + draw_status_message(blink); + + ui.did_first_redraw = true; +} + +#endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index eef27dbdb4..b2c939557d 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT +#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI #include "marlinui.h" #include "lcdprint.h" diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index 32d958bf7f..f6ac818ae5 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -34,7 +34,21 @@ #include "../inc/MarlinConfig.h" -#if HAS_MARLINUI_U8GLIB +#if IS_DWIN_MARLINUI + + #include "e3v2/marlinui/marlinui_dwin.h" + + #define LCD_PIXEL_WIDTH DWIN_WIDTH + #define LCD_PIXEL_HEIGHT DWIN_HEIGHT + #define LCD_WIDTH ((LCD_PIXEL_WIDTH) / (MENU_FONT_WIDTH)) + #define LCD_HEIGHT ((LCD_PIXEL_HEIGHT) / (MENU_LINE_HEIGHT)) + + // The DWIN lcd_moveto function uses row / column, not pixels + #define LCD_COL_X(col) (col) + #define LCD_ROW_Y(row) (row) + #define LCD_COL_X_RJ(len) (LCD_WIDTH - LCD_COL_X(len)) + +#elif HAS_MARLINUI_U8GLIB #include "dogm/u8g_fontutf8.h" typedef u8g_uint_t lcd_uint_t; @@ -105,7 +119,10 @@ #define MENU_LINE_HEIGHT MENU_FONT_HEIGHT #endif -#define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) +#ifndef LCD_COL_X_RJ + #define LCD_COL_X_RJ(len) (LCD_PIXEL_WIDTH - LCD_COL_X(len)) +#endif + #define SETCURSOR(col, row) lcd_moveto(LCD_COL_X(col), LCD_ROW_Y(row)) #define SETCURSOR_RJ(len, row) lcd_moveto(LCD_COL_X_RJ(len), LCD_ROW_Y(row)) #define SETCURSOR_X(col) SETCURSOR(col, _lcdLineNr) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index f4938722e3..1472f5c32a 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -202,6 +202,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false #endif + #if IS_DWIN_MARLINUI + bool MarlinUI::did_first_redraw; + #endif + // Encoder Handling #if HAS_ENCODER_ACTION uint32_t MarlinUI::encoderPosition; @@ -335,6 +339,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; col = (LCD_WIDTH - plen - slen) / 2; row = LCD_HEIGHT > 3 ? 1 : 0; } + if (LCD_HEIGHT >= 8) row = LCD_HEIGHT / 2 - 2; wrap_string_P(col, row, pref, true); if (string) { if (col) { col = 0; row++; } // Move to the start of the next line @@ -1073,6 +1078,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; run_current_screen(); + // Apply all DWIN drawing after processing + TERN_(IS_DWIN_MARLINUI, DWIN_UpdateLCD()); + #endif TERN_(HAS_LCD_MENU, lcd_clicked = false); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 9930796a01..edee8f0cc2 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -387,22 +387,22 @@ public: #endif #if HAS_MARLINUI_U8GLIB - static void set_font(const MarlinFont font_nr); + #elif IS_DWIN_MARLINUI + static void set_font(const uint8_t font_nr); + #endif - #else - + #if HAS_MARLINUI_HD44780 static void set_custom_characters(const HD44780CharSet screen_charset=CHARSET_INFO); + #endif - #if ENABLED(LCD_PROGRESS_BAR) - static millis_t progress_bar_ms; // Start time for the current progress bar cycle - static void draw_progress_bar(const uint8_t percent); - #if PROGRESS_MSG_EXPIRE > 0 - static millis_t expire_status_ms; // = 0 - FORCE_INLINE static void reset_progress_bar_timeout() { expire_status_ms = 0; } - #endif + #if ENABLED(LCD_PROGRESS_BAR) && !HAS_MARLINUI_U8GLIB + static millis_t progress_bar_ms; // Start time for the current progress bar cycle + static void draw_progress_bar(const uint8_t percent); + #if PROGRESS_MSG_EXPIRE > 0 + static millis_t expire_status_ms; // = 0 + FORCE_INLINE static void reset_progress_bar_timeout() { expire_status_ms = 0; } #endif - #endif static uint8_t lcd_status_update_delay; @@ -447,6 +447,10 @@ public: static constexpr bool drawing_screen = false, first_page = true; #endif + #if IS_DWIN_MARLINUI + static bool did_first_redraw; + #endif + static bool get_blink(); static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); static void draw_kill_screen(); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 01c8bb80c0..dd52eb2b5b 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -179,6 +179,8 @@ bool printer_busy() { void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, const uint8_t top/*=0*/, const uint8_t items/*=0*/) { if (currentScreen != screen) { + TERN_(IS_DWIN_MARLINUI, did_first_redraw = false); + TERN_(HAS_TOUCH_BUTTONS, repeat_delay = BUTTON_DELAY_MENU); TERN_(LCD_SET_PROGRESS_MANUALLY, progress_reset()); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 28d377da0c..7b253ad0ee 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -39,7 +39,7 @@ typedef void (*selectFunc_t)(); #define SS_INVERT 0x02 #define SS_DEFAULT SS_CENTER -#if HAS_MARLINUI_U8GLIB && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) +#if EITHER(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI) && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void _lcd_zoffset_overlay_gfx(const_float_t zvalue); #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 6b3c4ed8fa..0437156c0c 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -184,7 +184,7 @@ #define BTN_EN1 PB10 #define BTN_EN2 PA6 -#elif ENABLED(DWIN_CREALITY_LCD) +#elif EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD #define BTN_ENC PB14 @@ -194,7 +194,7 @@ //#define LCD_LED_PIN PB2 #ifndef BEEPER_PIN #define BEEPER_PIN PB13 - #undef SPEAKER + //#undef SPEAKER #endif #elif ENABLED(DWIN_VET6_CREALITY_LCD) diff --git a/buildroot/share/fonts/buildhzk.py b/buildroot/share/fonts/buildhzk.py new file mode 100644 index 0000000000..185cc14e97 --- /dev/null +++ b/buildroot/share/fonts/buildhzk.py @@ -0,0 +1,64 @@ +# Generate a 'HZK' font file for the T5UIC1 DWIN LCD +# from multiple bdf font files. +# Note: the 16x16 glyphs are not produced +# Author: Taylor Talkington +# License: GPL + +import bdflib.reader +import math + +def glyph_bits(size_x, size_y, font, glyph_ord): + asc = font[b'FONT_ASCENT'] + desc = font[b'FONT_DESCENT'] + bits = [0 for y in range(size_y)] + + glyph_bytes = math.ceil(size_x / 8) + try: + glyph = font[glyph_ord] + for y, row in enumerate(glyph.data): + v = row + rpad = size_x - glyph.bbW + if rpad < 0: rpad = 0 + if glyph.bbW > size_x: v = v >> (glyph.bbW - size_x) # some glyphs are actually too wide to fit! + v = v << (glyph_bytes * 8) - size_x + rpad + v = v >> glyph.bbX + bits[y + desc + glyph.bbY] |= v + except KeyError: + pass + + bits.reverse() + return bits + +def marlin_font_hzk(): + fonts = [ + [6,12,'marlin-6x12-3.bdf'], + [8,16,'marlin-8x16.bdf'], + [10,20,'marlin-10x20.bdf'], + [12,24,'marlin-12x24.bdf'], + [14,28,'marlin-14x28.bdf'], + [16,32,'marlin-16x32.bdf'], + [20,40,'marlin-20x40.bdf'], + [24,48,'marlin-24x48.bdf'], + [28,56,'marlin-28x56.bdf'], + [32,64,'marlin-32x64.bdf'] + ] + + with open('marlin_fixed.hzk','wb') as output: + for f in fonts: + with open(f[2], 'rb') as file: + print(f'{f[0]}x{f[1]}') + font = bdflib.reader.read_bdf(file) + for glyph in range(128): + bits = glyph_bits(f[0], f[1], font, glyph) + glyph_bytes = math.ceil(f[0]/8) + + for b in bits: + try: + z = b.to_bytes(glyph_bytes, 'big') + output.write(z) + except OverflowError: + print('Overflow') + print(f'{glyph}') + print(font[glyph]) + for b in bits: print(f'{b:0{f[0]}b}') + return diff --git a/buildroot/share/fonts/marlin-10x20.bdf b/buildroot/share/fonts/marlin-10x20.bdf new file mode 100644 index 0000000000..e6716d9b12 --- /dev/null +++ b/buildroot/share/fonts/marlin-10x20.bdf @@ -0,0 +1,4104 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 20 100 100 +FONTBOUNDINGBOX 12 19 0 -3 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 17 +FONT_DESCENT 3 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3000 +FE00 +FE00 +F180 +F180 +C180 +C180 +C180 +C780 +C780 +3F80 +0600 +0600 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +F000 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +FF80 +FF80 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 8 0 2 +BITMAP +08 +0C +0E +FF +FF +0E +0C +08 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 14 0 0 +BITMAP +0800 +1C00 +3E00 +7F00 +FF80 +FF80 +0800 +0800 +0800 +0800 +0800 +0800 +F800 +F800 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 -2 +BITMAP +0800 +3E00 +3E00 +C980 +C980 +C980 +CF80 +CF80 +C180 +C180 +C180 +3E00 +3E00 +0800 +0800 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 11 8 0 2 +BITMAP +E700 +7380 +39C0 +1CE0 +1CE0 +39C0 +7380 +E700 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 15 1 -2 +BITMAP +FE +92 +92 +82 +82 +82 +82 +82 +82 +82 +82 +92 +92 +92 +FE +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 16 1 -3 +BITMAP +10 +28 +28 +28 +28 +28 +28 +28 +C6 +82 +92 +92 +92 +82 +82 +7C +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 4 1 5 +BITMAP +60 +90 +90 +60 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 1 12 4 0 +BITMAP +80 +80 +80 +80 +80 +80 +80 +80 +80 +00 +80 +80 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 5 2 8 +BITMAP +90 +90 +90 +90 +90 +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 10 0 0 +BITMAP +2200 +2200 +FF80 +2200 +2200 +2200 +2200 +FF80 +2200 +2200 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 16 0 -2 +BITMAP +0800 +0800 +3E00 +4900 +8880 +8880 +4800 +3E00 +0900 +0880 +0880 +8880 +4900 +3E00 +0800 +0800 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +E080 +E080 +E100 +0200 +0400 +0800 +0800 +1000 +2000 +4380 +8380 +8380 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 0 +BITMAP +3000 +4800 +8800 +4800 +3000 +3000 +4880 +8900 +4600 +2900 +1080 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 1 5 4 8 +BITMAP +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 15 2 -2 +BITMAP +18 +20 +20 +40 +40 +40 +80 +80 +80 +40 +40 +40 +20 +20 +18 +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 15 2 -2 +BITMAP +C0 +20 +20 +10 +10 +10 +08 +08 +08 +10 +10 +10 +20 +20 +C0 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0800 +0800 +8880 +4900 +3E00 +0800 +0800 +3E00 +4900 +8880 +0800 +0800 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 9 0 1 +BITMAP +0800 +0800 +0800 +0800 +FF80 +0800 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 3 5 2 -2 +BITMAP +E0 +20 +20 +40 +80 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 1 0 5 +BITMAP +FF80 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 2 2 3 0 +BITMAP +C0 +C0 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0080 +0100 +0200 +0200 +0400 +0800 +0800 +1000 +1000 +2000 +4000 +8000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8380 +8480 +9880 +E080 +8080 +4100 +2200 +1C00 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 12 2 0 +BITMAP +20 +20 +E0 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +0100 +0200 +0400 +0800 +1000 +2000 +4000 +FF80 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF00 +0180 +0080 +0100 +0200 +0400 +0E00 +0100 +0080 +C100 +2200 +1C00 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0200 +0600 +0A00 +1200 +2200 +4200 +8200 +8200 +FF80 +0200 +0200 +0200 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +8000 +8000 +8000 +FE00 +0100 +0080 +0080 +8080 +4100 +2200 +1C00 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 0 0 +BITMAP +06 +08 +10 +20 +40 +FC +82 +81 +81 +41 +22 +1C +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +0080 +0080 +0100 +0200 +0400 +0800 +0800 +0800 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3E00 +4100 +8080 +8080 +4100 +3E00 +4100 +8080 +8080 +8080 +4100 +3E00 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 1 0 +BITMAP +3C +42 +81 +81 +81 +41 +3F +01 +02 +04 +08 +70 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 2 7 2 0 +BITMAP +C0 +C0 +00 +00 +00 +C0 +C0 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 3 9 2 -2 +BITMAP +C0 +C0 +00 +00 +E0 +20 +20 +40 +80 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 8 2 2 +BITMAP +10 +20 +40 +80 +80 +40 +20 +10 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 5 0 3 +BITMAP +FF80 +0000 +0000 +0000 +FF80 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 8 2 2 +BITMAP +80 +40 +20 +10 +10 +20 +40 +80 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 0 0 +BITMAP +1C +22 +41 +81 +02 +04 +08 +08 +08 +00 +00 +08 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8780 +8880 +8880 +8880 +8700 +4000 +2000 +1E00 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8080 +8080 +FF80 +8080 +8080 +8080 +8080 +8080 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 1 0 +BITMAP +FC +42 +41 +41 +42 +7C +42 +41 +41 +41 +42 +FC +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8000 +8000 +8000 +8000 +8080 +4100 +2200 +1C00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 1 0 +BITMAP +F8 +44 +42 +41 +41 +41 +41 +41 +41 +42 +44 +F8 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +8000 +8000 +8000 +8000 +FE00 +8000 +8000 +8000 +8000 +8000 +FF80 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +8000 +8000 +8000 +8000 +FE00 +8000 +8000 +8000 +8000 +8000 +8000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8000 +8000 +8000 +8780 +8080 +4100 +2200 +1C00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +8080 +8080 +FF80 +8080 +8080 +8080 +8080 +8080 +8080 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 12 2 0 +BITMAP +F8 +20 +20 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0F80 +0200 +0200 +0200 +0200 +0200 +0200 +0200 +0200 +8200 +4400 +3800 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 1 0 +BITMAP +81 +82 +84 +88 +90 +E0 +A0 +90 +88 +84 +82 +81 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8000 +8000 +8000 +8000 +8000 +8000 +8000 +8000 +8000 +8000 +8000 +FF80 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +C180 +A280 +9480 +8880 +8080 +8080 +8080 +8080 +8080 +8080 +8080 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +C080 +A080 +9080 +8880 +8480 +8280 +8180 +8080 +8080 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8080 +8080 +8080 +8080 +8080 +4100 +2200 +1C00 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 0 0 +BITMAP +FC +82 +81 +81 +81 +82 +FC +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +1C00 +2200 +4100 +8080 +8080 +8080 +8080 +8080 +8480 +4200 +2100 +1C80 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 0 0 +BITMAP +FC +82 +81 +81 +81 +FE +90 +90 +88 +84 +82 +81 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 12 1 0 +BITMAP +3C +42 +81 +80 +80 +7C +02 +01 +01 +81 +42 +3C +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +8080 +8080 +8080 +8080 +8080 +8080 +8080 +4100 +3E00 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +8080 +8080 +8080 +8080 +8080 +4100 +2200 +1400 +0800 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +8080 +8080 +8080 +8080 +8880 +8880 +8880 +5500 +2200 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +4100 +2200 +1400 +0800 +0800 +1400 +2200 +4100 +8080 +8080 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8080 +8080 +8080 +4100 +2200 +1400 +0800 +0800 +0800 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +FF80 +0080 +0080 +0100 +0200 +0400 +0800 +1000 +2000 +4000 +8000 +FF80 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 15 2 -2 +BITMAP +F8 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +F8 +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8000 +4000 +2000 +1000 +1000 +0800 +0800 +0400 +0400 +0200 +0100 +0080 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 15 2 -2 +BITMAP +F8 +08 +08 +08 +08 +08 +08 +08 +08 +08 +08 +08 +08 +08 +F8 +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 5 0 8 +BITMAP +0800 +1400 +2200 +4100 +8080 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 1 0 -3 +BITMAP +FF80 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 5 2 8 +BITMAP +80 +40 +20 +10 +08 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 8 1 0 +BITMAP +7C +02 +01 +7F +81 +81 +81 +7F +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8000 +8000 +8000 +8000 +FE00 +8100 +8080 +8080 +8080 +8080 +8100 +FE00 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 8 0 0 +BITMAP +3E +40 +80 +80 +80 +41 +22 +1C +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0080 +0080 +0080 +0080 +3F80 +4080 +8080 +8080 +8080 +8080 +4080 +3F80 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 8 0 0 +BITMAP +7E +81 +81 +81 +FE +80 +40 +3E +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 0 +BITMAP +0E00 +1100 +2080 +2000 +2000 +F800 +2000 +2000 +2000 +2000 +2000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +3E00 +4100 +8080 +8080 +8080 +8080 +4080 +3F80 +0080 +0100 +3E00 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8000 +8000 +8000 +8000 +FE00 +8100 +8080 +8080 +8080 +8080 +8080 +8080 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 12 2 0 +BITMAP +20 +00 +00 +00 +E0 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 15 2 -3 +BITMAP +02 +00 +00 +00 +1E +02 +02 +02 +02 +02 +02 +02 +82 +44 +38 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +8000 +8000 +8000 +8080 +8100 +8200 +8400 +F800 +8400 +8200 +8100 +8080 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 12 2 0 +BITMAP +E0 +20 +20 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +F600 +8900 +8880 +8880 +8880 +8880 +8880 +8880 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +9E00 +A100 +C080 +8080 +8080 +8080 +8080 +8080 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +3E00 +4100 +8080 +8080 +8080 +8080 +4100 +3E00 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +FE00 +8100 +8080 +8080 +8080 +8080 +8100 +FE00 +8000 +8000 +8000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +3F00 +4080 +8080 +8080 +8080 +8080 +4080 +3F80 +0080 +0080 +0080 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +9E00 +A100 +C080 +8000 +8000 +8000 +8000 +8000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +3F80 +4000 +4000 +3E00 +0100 +0080 +0100 +FE00 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0800 +0800 +0800 +0800 +FF80 +0800 +0800 +0800 +0800 +0800 +0400 +0380 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +8080 +8080 +8080 +8080 +8180 +8280 +4480 +3880 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +8080 +8080 +8080 +8080 +4100 +2200 +1400 +0800 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +8080 +8080 +8080 +8880 +8880 +8880 +5500 +2200 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 9 0 0 +BITMAP +8080 +4100 +2200 +1400 +0800 +1400 +2200 +4100 +8080 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +8080 +8080 +8080 +8080 +4100 +2200 +1400 +0800 +1000 +2000 +4000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 8 8 0 0 +BITMAP +FF +02 +04 +08 +10 +20 +40 +FF +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 16 3 -2 +BITMAP +10 +20 +40 +40 +40 +40 +40 +80 +80 +40 +40 +40 +40 +40 +20 +10 +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 1 15 4 -2 +BITMAP +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 4 16 2 -2 +BITMAP +80 +40 +20 +20 +20 +20 +20 +10 +10 +20 +20 +20 +20 +20 +40 +80 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 10 5 0 3 +BITMAP +3040 +4840 +8880 +8500 +8200 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 360 0 +DWIDTH 5 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 1 12 4 0 +BITMAP +80 +80 +00 +00 +80 +80 +80 +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 -2 +BITMAP +0800 +0800 +3E00 +C980 +C980 +C800 +C800 +C980 +3E00 +3E00 +0800 +0800 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0E00 +0E00 +3180 +3180 +3000 +F800 +F800 +3000 +3000 +3180 +CE00 +CE00 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +C980 +3600 +3600 +C180 +C180 +3600 +C980 +C980 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +C180 +C180 +3600 +3600 +FF80 +0800 +0800 +FF80 +FF80 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 1 12 4 0 +BITMAP +80 +80 +80 +80 +80 +00 +00 +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 13 2 0 +BITMAP +3E +C0 +C0 +38 +38 +C6 +C6 +C6 +38 +38 +06 +F8 +F8 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 1 2 12 +BITMAP +D8 +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 10 12 0 0 +BITMAP +3F80 +3F80 +C040 +C040 +CE40 +C840 +C840 +CE40 +CE40 +C040 +3F80 +3F80 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 8 2 7 +BITMAP +38 +38 +D8 +38 +38 +00 +00 +F8 +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +0980 +3600 +3600 +C800 +C800 +3600 +0980 +0980 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 5 0 2 +BITMAP +FF80 +FF80 +0180 +0180 +0180 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 2 2 5 +BITMAP +F8 +F8 +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 10 12 0 0 +BITMAP +3F80 +3F80 +C040 +C040 +CE40 +C840 +C840 +C840 +C840 +C040 +3F80 +3F80 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 1 0 12 +BITMAP +FF80 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 7 2 8 +BITMAP +38 +38 +C6 +C6 +C6 +38 +38 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0800 +0800 +0800 +0800 +FF80 +0800 +0800 +0800 +0800 +0000 +FF80 +FF80 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 8 2 7 +BITMAP +20 +20 +D8 +18 +18 +20 +20 +F8 +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 8 2 7 +BITMAP +E0 +E0 +18 +20 +20 +18 +18 +E0 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 5 2 8 +BITMAP +18 +20 +20 +C0 +C0 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +C180 +C180 +C180 +C180 +C180 +C780 +F980 +F980 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3F80 +F980 +F980 +F980 +F980 +F980 +3980 +3980 +0980 +0980 +0980 +0980 +0980 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 3 3 4 5 +BITMAP +E0 +E0 +E0 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 3 2 -3 +BITMAP +18 +18 +E0 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 8 2 7 +BITMAP +20 +20 +E0 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 9 2 8 +BITMAP +20 +20 +D8 +D8 +20 +00 +00 +F8 +F8 +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +C800 +3600 +3600 +0980 +0980 +3600 +C800 +C800 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +F000 +F000 +3180 +3600 +3600 +3800 +3800 +3600 +CE00 +CE00 +3600 +3600 +3F80 +0600 +0600 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +F000 +F000 +3180 +3600 +3600 +3800 +3800 +3600 +C980 +C980 +0180 +0180 +0600 +0F80 +0F80 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +F000 +F000 +0800 +0800 +3180 +0E00 +0E00 +F800 +F800 +3600 +CE00 +CE00 +3600 +3600 +3F80 +0600 +0600 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +0800 +0800 +0000 +0000 +0800 +0800 +0800 +3000 +3000 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +0800 +0800 +0000 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0600 +0600 +0800 +0800 +0000 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0800 +0800 +3600 +3600 +0000 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3980 +3980 +CE00 +CE00 +0000 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 0 +BITMAP +3600 +3600 +0000 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0800 +0800 +3600 +3600 +0800 +3E00 +3E00 +C180 +C180 +C180 +FF80 +FF80 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3F80 +3F80 +C800 +C800 +C800 +FE00 +FE00 +C800 +C800 +C800 +CF80 +CF80 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 -3 +BITMAP +3E00 +3E00 +C180 +C180 +C000 +C000 +C000 +C000 +C000 +C180 +3E00 +3E00 +0600 +0600 +3800 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +0800 +0800 +0000 +FF80 +FF80 +C000 +C000 +C000 +FE00 +FE00 +C000 +C000 +C000 +FF80 +FF80 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0600 +0600 +0800 +0800 +0000 +FF80 +FF80 +C000 +C000 +C000 +FE00 +FE00 +C000 +C000 +C000 +FF80 +FF80 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0800 +0800 +3600 +3600 +0000 +FF80 +FF80 +C000 +C000 +C000 +FE00 +FE00 +C000 +C000 +C000 +FF80 +FF80 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 0 +BITMAP +3600 +3600 +0000 +FF80 +FF80 +C000 +C000 +C000 +FE00 +FE00 +C000 +C000 +C000 +FF80 +FF80 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 17 2 0 +BITMAP +C0 +C0 +20 +20 +00 +F8 +F8 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 17 2 0 +BITMAP +18 +18 +20 +20 +00 +F8 +F8 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 17 2 0 +BITMAP +20 +20 +D8 +D8 +00 +F8 +F8 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 15 2 0 +BITMAP +D8 +D8 +00 +F8 +F8 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3E00 +3E00 +3180 +3180 +3180 +F980 +F980 +3180 +3180 +3180 +3E00 +3E00 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3980 +3980 +CE00 +CE00 +0000 +C180 +C180 +C180 +C180 +F180 +C980 +C980 +C780 +C780 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +0800 +0800 +0000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0600 +0600 +0800 +0800 +0000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0800 +0800 +3600 +3600 +0000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3980 +3980 +CE00 +CE00 +0000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 0 +BITMAP +3600 +3600 +0000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 2 +BITMAP +C180 +C180 +3600 +0800 +0800 +3600 +3600 +C180 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 -2 +BITMAP +0180 +3E00 +3E00 +C780 +C780 +C980 +C980 +C980 +C980 +C980 +F180 +3E00 +3E00 +C000 +C000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +3000 +3000 +0800 +0800 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0600 +0600 +0800 +0800 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0800 +0800 +3600 +3600 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 0 +BITMAP +3600 +3600 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 17 0 0 +BITMAP +0600 +0600 +0800 +0800 +0000 +C180 +C180 +C180 +C180 +3600 +0800 +0800 +0800 +0800 +0800 +0800 +0800 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 7 12 2 0 +BITMAP +C0 +C0 +F8 +F8 +C6 +C6 +C6 +C6 +C6 +F8 +C0 +C0 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3E00 +3E00 +C180 +C180 +C600 +C800 +C800 +C600 +C600 +C180 +CE00 +CE00 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3000 +0800 +0800 +0000 +0000 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0600 +0800 +0800 +0000 +0000 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0800 +3600 +3600 +0000 +0000 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3980 +CE00 +CE00 +0000 +0000 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3600 +3600 +0000 +0000 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0800 +3600 +3600 +0800 +0800 +3E00 +0180 +0180 +3F80 +3F80 +C180 +3F80 +3F80 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +3E00 +0980 +0980 +3E00 +3E00 +C800 +3F80 +3F80 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 11 0 -3 +BITMAP +3E00 +C180 +C180 +C000 +C000 +C180 +3E00 +3E00 +0600 +0600 +3800 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3000 +0800 +0800 +0000 +0000 +3E00 +C180 +C180 +FE00 +FE00 +C000 +3E00 +3E00 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0600 +0800 +0800 +0000 +0000 +3E00 +C180 +C180 +FE00 +FE00 +C000 +3E00 +3E00 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0800 +3600 +3600 +0000 +0000 +3E00 +C180 +C180 +FE00 +FE00 +C000 +3E00 +3E00 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3600 +3600 +0000 +0000 +3E00 +C180 +C180 +FE00 +FE00 +C000 +3E00 +3E00 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 13 2 0 +BITMAP +C0 +20 +20 +00 +00 +E0 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 13 2 0 +BITMAP +18 +20 +20 +00 +00 +E0 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 13 2 0 +BITMAP +20 +D8 +D8 +00 +00 +E0 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 5 12 2 0 +BITMAP +D8 +D8 +00 +00 +E0 +20 +20 +20 +20 +20 +F8 +F8 +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 0 +BITMAP +3600 +3600 +0800 +3600 +3600 +0180 +0180 +3F80 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3980 +CE00 +CE00 +0000 +0000 +CE00 +F180 +F180 +C180 +C180 +C180 +C180 +C180 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3000 +0800 +0800 +0000 +0000 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0600 +0800 +0800 +0000 +0000 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0800 +3600 +3600 +0000 +0000 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3980 +CE00 +CE00 +0000 +0000 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3600 +3600 +0000 +0000 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 2 +BITMAP +0800 +0800 +0000 +FF80 +FF80 +0000 +0000 +0800 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 8 0 0 +BITMAP +3F80 +C780 +C780 +C980 +C980 +F180 +FE00 +FE00 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +3000 +0800 +0800 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0600 +0800 +0800 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 13 0 0 +BITMAP +0800 +3600 +3600 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 12 0 0 +BITMAP +3600 +3600 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 16 0 -3 +BITMAP +0600 +0800 +0800 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +3600 +0800 +0800 +3000 +3000 +C000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 -3 +BITMAP +C000 +C000 +C000 +C000 +FE00 +C180 +C180 +C180 +C180 +C180 +FE00 +FE00 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 15 0 -3 +BITMAP +3600 +3600 +0000 +0000 +C180 +C180 +C180 +C180 +C180 +3600 +0800 +0800 +3000 +3000 +C000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-12x24.bdf b/buildroot/share/fonts/marlin-12x24.bdf new file mode 100644 index 0000000000..b8b85e3286 --- /dev/null +++ b/buildroot/share/fonts/marlin-12x24.bdf @@ -0,0 +1,4558 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 24 100 100 +FONTBOUNDINGBOX 14 23 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 22 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3000 +3000 +FF00 +FF00 +F0C0 +F0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C3C0 +C3C0 +3FC0 +3FC0 +0300 +0300 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +F000 +F000 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 4 +BITMAP +0C00 +0E00 +0F00 +0F80 +FFC0 +FFC0 +0F80 +0F00 +0E00 +0C00 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +1E00 +3F00 +7F80 +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +FC00 +FC00 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 0 +BITMAP +0C00 +0C00 +3F00 +3F00 +CCC0 +CCC0 +CCC0 +CCC0 +CFC0 +CFC0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +0C00 +0C00 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 13 10 0 4 +BITMAP +F380 +F380 +3DE0 +3DE0 +0E78 +0E78 +3DE0 +3DE0 +F380 +F380 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 0 +BITMAP +FFC0 +FFC0 +CCC0 +CCC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +CCC0 +CCC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 -2 +BITMAP +0C00 +1E00 +3300 +3300 +3300 +3300 +3300 +3300 +3300 +7380 +E1C0 +C0C0 +CCC0 +CCC0 +CCC0 +CCC0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 6 0 8 +BITMAP +30 +78 +CC +CC +78 +30 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 2 14 4 2 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +C0 +C0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 6 2 12 +BITMAP +CC +CC +CC +CC +CC +CC +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 12 0 2 +BITMAP +3300 +3300 +FFC0 +FFC0 +3300 +3300 +3300 +3300 +FFC0 +FFC0 +3300 +3300 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 19 0 0 +BITMAP +0C00 +0C00 +1E00 +3F00 +6F80 +CDC0 +CCC0 +CC00 +EC00 +7F00 +3F80 +0DC0 +0CC0 +CCC0 +EDC0 +7F80 +3F00 +0C00 +0C00 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +E0C0 +E0C0 +E0C0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +E000 +C1C0 +C1C0 +C1C0 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3000 +7800 +CC00 +CC00 +CC00 +CC00 +7800 +7800 +DCC0 +CFC0 +C780 +C780 +7FC0 +3CC0 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 2 6 4 12 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +0C +1C +38 +30 +60 +60 +C0 +C0 +C0 +C0 +C0 +C0 +E0 +60 +70 +38 +1C +0C +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +C0 +E0 +70 +30 +18 +18 +0C +0C +0C +0C +0C +0C +18 +18 +30 +70 +E0 +C0 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0C00 +0C00 +CCC0 +EDC0 +7F80 +3F00 +0C00 +0C00 +3F00 +7F80 +EDC0 +CCC0 +0C00 +0C00 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 4 +BITMAP +0C00 +0C00 +0C00 +0C00 +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 4 6 2 0 +BITMAP +F0 +F0 +30 +30 +E0 +C0 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 2 0 8 +BITMAP +FFC0 +FFC0 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 4 4 2 2 +BITMAP +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +00C0 +01C0 +0380 +0300 +0300 +0700 +0E00 +1C00 +3800 +3000 +3000 +7000 +E000 +C000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C1C0 +C3C0 +C7C0 +CEC0 +DCC0 +F8C0 +F0C0 +E0C0 +C0C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 14 2 2 +BITMAP +30 +30 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C0C0 +00C0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +00C0 +01C0 +0380 +0700 +0F00 +0F80 +01C0 +00C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0300 +0700 +0F00 +1F00 +3B00 +7300 +E300 +C300 +FFC0 +FFC0 +0300 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +C000 +C000 +FF00 +FF80 +01C0 +00C0 +00C0 +00C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0F00 +1F00 +3800 +7000 +E000 +C000 +FF00 +FF80 +C1C0 +C0C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +00C0 +00C0 +0180 +0300 +0600 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C0C0 +C0C0 +C0C0 +7F80 +7F80 +C0C0 +C0C0 +C0C0 +C0C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C0C0 +C0C0 +C0C0 +7FC0 +3FC0 +00C0 +01C0 +0380 +0700 +3E00 +3C00 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 4 10 2 2 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 4 12 2 0 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +F0 +F0 +30 +30 +E0 +C0 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 4 +BITMAP +0C +1C +38 +70 +E0 +E0 +70 +38 +1C +0C +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 6 0 6 +BITMAP +FFC0 +FFC0 +0000 +0000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 4 +BITMAP +C0 +E0 +70 +38 +1C +1C +38 +70 +E0 +C0 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C1C0 +0380 +0700 +0E00 +0C00 +0C00 +0C00 +0000 +0000 +0C00 +0C00 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C0C0 +C7C0 +CFC0 +CCC0 +CCC0 +CFC0 +C780 +C000 +C000 +7F00 +3F00 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FF00 +FF80 +30C0 +30C0 +30C0 +30C0 +3F80 +3F80 +30C0 +30C0 +30C0 +30C0 +FF80 +FF00 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C000 +C000 +C000 +C000 +C000 +C000 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FF00 +FF80 +31C0 +30C0 +30C0 +30C0 +30C0 +30C0 +30C0 +30C0 +30C0 +31C0 +FF80 +FF00 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C000 +C000 +C000 +C000 +C3C0 +C3C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 14 2 2 +BITMAP +FC +FC +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0FC0 +0FC0 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +C300 +E700 +7E00 +3C00 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C1C0 +C380 +C700 +CE00 +DC00 +F800 +F800 +DC00 +CE00 +C700 +C380 +C1C0 +C0C0 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +E1C0 +F3C0 +FFC0 +DEC0 +CCC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +E0C0 +F0C0 +F8C0 +DCC0 +CEC0 +C7C0 +C3C0 +C1C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FF00 +FF80 +C1C0 +C0C0 +C0C0 +C1C0 +FF80 +FF00 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +CCC0 +CEC0 +C700 +E380 +7DC0 +3CC0 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FF00 +FF80 +C1C0 +C0C0 +C0C0 +C1C0 +FF80 +FF00 +DC00 +CE00 +C700 +C380 +C1C0 +C0C0 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C000 +E000 +7F00 +3F80 +01C0 +00C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +CCC0 +CCC0 +CCC0 +FFC0 +7F80 +3300 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +1E00 +3F00 +7380 +E1C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +FFC0 +FFC0 +00C0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +E000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +FC +FC +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +FC +FC +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C000 +E000 +7000 +3000 +3000 +3800 +1C00 +0E00 +0700 +0300 +0300 +0380 +01C0 +00C0 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +FC +FC +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +FC +FC +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 6 0 12 +BITMAP +0C00 +1E00 +3F00 +7380 +E1C0 +C0C0 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 2 0 -2 +BITMAP +FFC0 +FFC0 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 6 2 12 +BITMAP +C0 +E0 +70 +38 +1C +0C +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3F00 +3F80 +01C0 +00C0 +3FC0 +7FC0 +C0C0 +C0C0 +7FC0 +3FC0 +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C000 +C000 +C000 +C000 +FF00 +FF80 +C1C0 +C0C0 +C0C0 +C0C0 +C0C0 +C1C0 +FF80 +FF00 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3F00 +7F00 +E000 +C000 +C000 +C000 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +00C0 +00C0 +00C0 +00C0 +3FC0 +7FC0 +E0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E0C0 +7FC0 +3FC0 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +FF80 +FF00 +C000 +E000 +7F00 +3F00 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0F00 +1F80 +39C0 +30C0 +3000 +3000 +FC00 +FC00 +3000 +3000 +3000 +3000 +3000 +3000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C0C0 +C0C0 +C0C0 +E0C0 +7FC0 +3FC0 +00C0 +01C0 +3F80 +3F00 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C000 +C000 +C000 +C000 +FF00 +FF80 +C1C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 14 2 2 +BITMAP +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 8 18 2 -2 +BITMAP +03 +03 +00 +00 +0F +0F +03 +03 +03 +03 +03 +03 +03 +03 +C3 +E7 +7E +3C +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C000 +C000 +C000 +C000 +C0C0 +C1C0 +C380 +C700 +FE00 +FE00 +C700 +C380 +C1C0 +C0C0 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 14 2 2 +BITMAP +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +F300 +FF80 +DFC0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +CF00 +DF80 +F9C0 +F0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3F00 +7F80 +E1C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +FF00 +FF80 +C1C0 +C0C0 +C0C0 +C0C0 +C0C0 +C1C0 +FF80 +FF00 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +3FC0 +7FC0 +E0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E0C0 +7FC0 +3FC0 +00C0 +00C0 +00C0 +00C0 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +CF00 +DF80 +F9C0 +F0C0 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3FC0 +7FC0 +C000 +C000 +7F00 +3F80 +00C0 +00C0 +FF80 +FF00 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0C00 +0C00 +0C00 +0C00 +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +0C00 +0E00 +07C0 +03C0 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C3C0 +E7C0 +7EC0 +3CC0 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +CCC0 +CCC0 +CCC0 +FFC0 +7F80 +3300 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +C0C0 +E1C0 +7380 +3F00 +1E00 +1E00 +3F00 +7380 +E1C0 +C0C0 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +1C00 +3800 +7000 +E000 +C000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +FFC0 +FFC0 +0380 +0700 +0E00 +1C00 +3800 +7000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +0C +1C +38 +30 +30 +30 +30 +70 +C0 +C0 +70 +30 +30 +30 +30 +38 +1C +0C +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 2 18 4 0 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 0 +BITMAP +C0 +E0 +70 +30 +30 +30 +30 +38 +0C +0C +38 +30 +30 +30 +30 +70 +E0 +C0 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 6 0 6 +BITMAP +30C0 +78C0 +DCC0 +CEC0 +C780 +C300 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 2 14 4 2 +BITMAP +C0 +C0 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 0 +BITMAP +0C00 +0C00 +3F00 +3F00 +CCC0 +CCC0 +CC00 +CC00 +CCC0 +CCC0 +3F00 +3F00 +0C00 +0C00 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0F00 +0F00 +30C0 +30C0 +3000 +3000 +FC00 +FC00 +3000 +3000 +30C0 +30C0 +CF00 +CF00 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +CCC0 +CCC0 +3300 +3300 +C0C0 +C0C0 +3300 +3300 +CCC0 +CCC0 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +C0C0 +C0C0 +3300 +3300 +FFC0 +FFC0 +0C00 +0C00 +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 2 14 4 2 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 8 16 2 2 +BITMAP +3F +3F +C0 +C0 +3C +3C +C3 +C3 +C3 +C3 +3C +3C +03 +03 +FC +FC +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 2 2 16 +BITMAP +CC +CC +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 12 14 0 2 +BITMAP +3FC0 +3FC0 +C030 +C030 +CF30 +CF30 +CC30 +CC30 +CF30 +CF30 +C030 +C030 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 10 +BITMAP +3C +3C +CC +CC +3C +3C +00 +00 +FC +FC +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +0CC0 +0CC0 +3300 +3300 +CC00 +CC00 +3300 +3300 +0CC0 +0CC0 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 6 0 4 +BITMAP +FFC0 +FFC0 +00C0 +00C0 +00C0 +00C0 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 2 2 8 +BITMAP +FC +FC +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 12 14 0 2 +BITMAP +3FC0 +3FC0 +C030 +C030 +CF30 +CF30 +CC30 +CC30 +CC30 +CC30 +C030 +C030 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 2 0 16 +BITMAP +FFC0 +FFC0 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 8 8 2 12 +BITMAP +3C +3C +C3 +C3 +C3 +C3 +3C +3C +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0C00 +0C00 +0C00 +0C00 +FFC0 +FFC0 +0C00 +0C00 +0C00 +0C00 +0000 +0000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 10 +BITMAP +30 +30 +CC +CC +0C +0C +30 +30 +FC +FC +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 10 +BITMAP +F0 +F0 +0C +0C +30 +30 +0C +0C +F0 +F0 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 6 2 12 +BITMAP +0C +0C +30 +30 +C0 +C0 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C3C0 +C3C0 +FCC0 +FCC0 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3FC0 +3FC0 +FCC0 +FCC0 +FCC0 +FCC0 +FCC0 +FCC0 +3CC0 +3CC0 +0CC0 +0CC0 +0CC0 +0CC0 +0CC0 +0CC0 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 4 4 4 8 +BITMAP +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 4 2 -2 +BITMAP +0C +0C +F0 +F0 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 10 +BITMAP +30 +30 +F0 +F0 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 10 2 12 +BITMAP +30 +30 +CC +CC +30 +30 +00 +00 +FC +FC +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +CC00 +CC00 +3300 +3300 +0CC0 +0CC0 +3300 +3300 +CC00 +CC00 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +F000 +F000 +30C0 +30C0 +3300 +3300 +3C00 +3C00 +3300 +3300 +CF00 +CF00 +3300 +3300 +3FC0 +3FC0 +0300 +0300 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +F000 +F000 +30C0 +30C0 +3300 +3300 +3C00 +3C00 +3300 +3300 +CCC0 +CCC0 +00C0 +00C0 +0300 +0300 +0FC0 +0FC0 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +F000 +F000 +0C00 +0C00 +30C0 +30C0 +0F00 +0F00 +FC00 +FC00 +3300 +3300 +CF00 +CF00 +3300 +3300 +3FC0 +3FC0 +0300 +0300 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +0C00 +0C00 +0000 +0000 +0C00 +0C00 +0C00 +0C00 +3000 +3000 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 2 +BITMAP +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0C00 +0C00 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +FFC0 +FFC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3FC0 +3FC0 +CC00 +CC00 +CC00 +CC00 +FF00 +FF00 +CC00 +CC00 +CC00 +CC00 +CFC0 +CFC0 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 -2 +BITMAP +3F00 +3F00 +C0C0 +C0C0 +C000 +C000 +C000 +C000 +C000 +C000 +C0C0 +C0C0 +3F00 +3F00 +0300 +0300 +3C00 +3C00 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 2 +BITMAP +3300 +3300 +0000 +0000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +FF00 +FF00 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 20 2 2 +BITMAP +C0 +C0 +30 +30 +00 +00 +FC +FC +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 20 2 2 +BITMAP +0C +0C +30 +30 +00 +00 +FC +FC +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 20 2 2 +BITMAP +30 +30 +CC +CC +00 +00 +FC +FC +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 18 2 2 +BITMAP +CC +CC +00 +00 +FC +FC +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +3F00 +30C0 +30C0 +30C0 +30C0 +FCC0 +FCC0 +30C0 +30C0 +30C0 +30C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +F0C0 +F0C0 +CCC0 +CCC0 +C3C0 +C3C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 2 +BITMAP +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 4 +BITMAP +C0C0 +C0C0 +3300 +3300 +0C00 +0C00 +3300 +3300 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 0 +BITMAP +00C0 +00C0 +3F00 +3F00 +C3C0 +C3C0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +F0C0 +F0C0 +3F00 +3F00 +C000 +C000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 2 +BITMAP +3300 +3300 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +3300 +3300 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 8 14 2 2 +BITMAP +C0 +C0 +FC +FC +C3 +C3 +C3 +C3 +C3 +C3 +FC +FC +C0 +C0 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3F00 +3F00 +C0C0 +C0C0 +C300 +C300 +CC00 +CC00 +C300 +C300 +C0C0 +C0C0 +CF00 +CF00 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3300 +3300 +0000 +0000 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0C00 +0C00 +3F00 +3F00 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3F00 +3F00 +0CC0 +0CC0 +3F00 +3F00 +CC00 +CC00 +3FC0 +3FC0 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 -2 +BITMAP +3F00 +3F00 +C0C0 +C0C0 +C000 +C000 +C0C0 +C0C0 +3F00 +3F00 +0300 +0300 +3C00 +3C00 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +FF00 +FF00 +C000 +C000 +3F00 +3F00 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +FF00 +FF00 +C000 +C000 +3F00 +3F00 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +FF00 +FF00 +C000 +C000 +3F00 +3F00 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +FF00 +FF00 +C000 +C000 +3F00 +3F00 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 16 2 2 +BITMAP +C0 +C0 +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 16 2 2 +BITMAP +0C +0C +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 16 2 2 +BITMAP +30 +30 +CC +CC +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 6 14 2 2 +BITMAP +CC +CC +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +FC +FC +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 2 +BITMAP +3300 +3300 +0C00 +0C00 +3300 +3300 +00C0 +00C0 +3FC0 +3FC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +CF00 +CF00 +F0C0 +F0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3CC0 +3CC0 +CF00 +CF00 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3300 +3300 +0000 +0000 +3F00 +3F00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 4 +BITMAP +0C00 +0C00 +0000 +0000 +FFC0 +FFC0 +0000 +0000 +0C00 +0C00 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 10 0 2 +BITMAP +3FC0 +3FC0 +C3C0 +C3C0 +CCC0 +CCC0 +F0C0 +F0C0 +FF00 +FF00 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +3000 +3000 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 16 0 2 +BITMAP +0C00 +0C00 +3300 +3300 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 14 0 2 +BITMAP +3300 +3300 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 20 0 -2 +BITMAP +0300 +0300 +0C00 +0C00 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3300 +3300 +0C00 +0C00 +3000 +3000 +C000 +C000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 -2 +BITMAP +C000 +C000 +C000 +C000 +FF00 +FF00 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +FF00 +FF00 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 864 0 +DWIDTH 12 0 +BBX 10 18 0 -2 +BITMAP +3300 +3300 +0000 +0000 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +3300 +3300 +0C00 +0C00 +3000 +3000 +C000 +C000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-14x28.bdf b/buildroot/share/fonts/marlin-14x28.bdf new file mode 100644 index 0000000000..8a91ff0605 --- /dev/null +++ b/buildroot/share/fonts/marlin-14x28.bdf @@ -0,0 +1,5078 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 28 100 100 +FONTBOUNDINGBOX 16 27 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. orig" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 26 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1800 +1800 +FFC0 +FFC0 +FFC0 +F830 +F830 +E030 +E030 +E030 +E030 +E030 +E1F0 +E1F0 +1FF0 +1FF0 +01C0 +01C0 +01C0 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +F800 +F800 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 11 0 5 +BITMAP +0600 +0700 +0780 +07C0 +FFE0 +FFF0 +FFE0 +07C0 +0780 +0700 +0600 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0F00 +1F80 +3FC0 +7FE0 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +FE00 +FE00 +FE00 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 0 +BITMAP +0600 +0600 +1FC0 +1FC0 +1FC0 +E630 +E630 +E630 +E630 +E7F0 +E7F0 +E7F0 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +0600 +0600 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 13 11 1 5 +BITMAP +E380 +F3C0 +79E0 +3CF0 +1E78 +1E78 +1E78 +3CF0 +79E0 +F3C0 +E380 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 0 +BITMAP +FFF0 +FFF0 +E630 +E630 +E630 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E630 +E630 +E630 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 23 1 -2 +BITMAP +0C00 +0C00 +3300 +3300 +3300 +3300 +3300 +3300 +3300 +3300 +3300 +3300 +C0C0 +C0C0 +CCC0 +CCC0 +CCC0 +CCC0 +CCC0 +C0C0 +C0C0 +3F00 +3F00 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 6 6 1 10 +BITMAP +30 +78 +CC +CC +78 +30 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 2 17 5 2 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 6 7 3 14 +BITMAP +CC +CC +CC +CC +CC +CC +CC +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 14 0 2 +BITMAP +1980 +1980 +FFF0 +FFF0 +1980 +1980 +1980 +1980 +1980 +FFF0 +FFF0 +1980 +1980 +1980 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 0 +BITMAP +0600 +0600 +1F80 +3FC0 +76E0 +E670 +C630 +C600 +E600 +7600 +3F80 +1FC0 +06E0 +0670 +C630 +E670 +76E0 +3FC0 +1F80 +0600 +0600 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +F060 +F060 +F060 +F060 +00E0 +03C0 +0780 +0E00 +0C00 +1C00 +3800 +7000 +E000 +C1E0 +C1E0 +C1E0 +C1E0 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1800 +3C00 +7E00 +E600 +C600 +C600 +EE00 +7C00 +3800 +7C00 +EE30 +C770 +C3E0 +E3E0 +7F70 +3E30 +1C30 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 2 7 5 14 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 21 3 0 +BITMAP +0E +1E +38 +70 +60 +E0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +E0 +60 +70 +38 +1E +0E +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 21 3 0 +BITMAP +E0 +F0 +38 +1C +0C +0E +06 +06 +06 +06 +06 +06 +06 +06 +06 +0E +0C +1C +38 +F0 +E0 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0600 +0600 +0600 +E670 +F6F0 +3FC0 +1F80 +0600 +0600 +0600 +1F80 +3FC0 +F6F0 +E670 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 4 +BITMAP +0600 +0600 +0600 +0600 +0600 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 4 7 3 0 +BITMAP +F0 +F0 +30 +30 +70 +E0 +C0 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 3 0 9 +BITMAP +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 4 5 3 2 +BITMAP +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0030 +0030 +0070 +00E0 +01C0 +0180 +0380 +0300 +0700 +0E00 +1C00 +1800 +3800 +7000 +E000 +C000 +C000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1F80 +3FC0 +6060 +C030 +C070 +C0F0 +C1B0 +C330 +C630 +CC30 +D830 +F030 +E030 +C030 +6060 +3FC0 +1F80 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 17 3 2 +BITMAP +30 +30 +30 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1FC0 +3FE0 +7060 +E030 +C030 +0030 +0070 +00E0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +0030 +0030 +0070 +00E0 +01C0 +0380 +07C0 +03E0 +0070 +0030 +E030 +7070 +38E0 +1FC0 +0F80 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 0 2 +BITMAP +0180 +0180 +0380 +0780 +0F80 +1D80 +3980 +7180 +E180 +C180 +FFE0 +FFE0 +0180 +0180 +0180 +0180 +0180 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +C000 +C000 +C000 +FFC0 +FFE0 +0070 +0030 +0030 +0030 +0030 +E030 +7070 +38E0 +1FC0 +0F80 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +03C0 +07C0 +0E00 +1C00 +3800 +7000 +E000 +C000 +FFC0 +FFE0 +C070 +C030 +C030 +E030 +7070 +3FE0 +1FC0 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +0030 +0030 +0030 +0070 +00E0 +01C0 +0380 +0700 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C060 +C060 +E0E0 +7FC0 +7FC0 +E0E0 +C060 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +3F80 +7FC0 +E0C0 +C060 +C060 +C060 +C060 +E060 +7FE0 +3FE0 +0060 +00E0 +01C0 +0380 +0700 +1E00 +1C00 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 4 11 3 2 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +00 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 4 13 3 0 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +F0 +F0 +30 +30 +70 +E0 +C0 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 13 3 4 +BITMAP +06 +0E +1C +38 +70 +E0 +C0 +E0 +70 +38 +1C +0E +06 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 7 0 7 +BITMAP +FFF0 +FFF0 +0000 +0000 +0000 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 13 2 4 +BITMAP +C0 +E0 +70 +38 +1C +0E +06 +0E +1C +38 +70 +E0 +C0 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 0 2 +BITMAP +1F80 +3FC0 +70E0 +E060 +C060 +00E0 +01C0 +0380 +0700 +0600 +0600 +0600 +0000 +0000 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +1F00 +3F80 +71C0 +E0E0 +C060 +C7E0 +CFE0 +CE60 +CC60 +CEE0 +CFE0 +C7C0 +C000 +E000 +7000 +3F80 +1F80 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +1F00 +3F80 +71C0 +E0E0 +C060 +C060 +C060 +C060 +FFE0 +FFE0 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +FF80 +FFC0 +30E0 +3060 +3060 +3060 +30E0 +3FE0 +3FC0 +30C0 +3060 +3060 +3060 +3060 +30E0 +FFE0 +FFC0 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +3F00 +7F80 +E1C0 +C0E0 +C060 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C060 +C0E0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +FF80 +FFC0 +30E0 +3060 +3060 +3060 +3060 +3060 +3060 +3060 +3060 +3060 +3060 +3060 +30E0 +FFC0 +FF80 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +C000 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +C000 +C000 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +C000 +C000 +C000 +C000 +C000 +FFC0 +FFC0 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +1F00 +3F80 +71C0 +E0E0 +C060 +C000 +C000 +C000 +C000 +C000 +C3E0 +C3E0 +C060 +C0E0 +E1C0 +7F80 +3F00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C060 +C060 +C060 +C060 +C060 +C060 +FFE0 +FFE0 +FFE0 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 8 16 2 2 +BITMAP +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 16 0 2 +BITMAP +07E0 +07E0 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +C180 +E380 +7700 +3E00 +1C00 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C0E0 +C1C0 +C380 +C700 +CE00 +DC00 +F800 +F000 +F800 +DC00 +CE00 +C700 +C380 +C1C0 +C0E0 +C060 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +FFE0 +FFE0 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 17 1 2 +BITMAP +C0C0 +C0C0 +E1C0 +F3C0 +FFC0 +DEC0 +CCC0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C060 +C060 +C060 +E060 +F060 +F860 +DC60 +CE60 +C760 +C3E0 +C1E0 +C0E0 +C060 +C060 +C060 +C060 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +FF80 +FFC0 +C0E0 +C060 +C060 +C060 +C060 +C0E0 +FFC0 +FF80 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +CC60 +CE60 +C760 +C3A0 +E1C0 +7EE0 +3E70 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +FF80 +FFC0 +C0E0 +C060 +C060 +C060 +C060 +C0E0 +FFC0 +FF80 +DC00 +CE00 +C700 +C380 +C1C0 +C0E0 +C060 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C000 +C000 +E000 +7F80 +3FC0 +00E0 +0060 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +FFF0 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +60C0 +60C0 +3180 +3180 +1B00 +0E00 +0E00 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +CE60 +CE60 +CE60 +FFE0 +FBE0 +7BC0 +3180 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 17 1 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +1E00 +3F00 +7380 +E1C0 +C0C0 +C0C0 +C0C0 +C0C0 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 17 1 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +0C00 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 16 1 2 +BITMAP +FFE0 +FFE0 +0060 +0060 +00E0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +E000 +C000 +FFE0 +FFE0 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 21 3 0 +BITMAP +FE +FE +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +FE +FE +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C000 +E000 +6000 +7000 +3000 +3800 +1C00 +0C00 +0E00 +0600 +0700 +0380 +0180 +01C0 +00C0 +00E0 +0060 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 6 21 3 0 +BITMAP +FC +FC +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +0C +FC +FC +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 7 0 14 +BITMAP +0600 +0F00 +1F80 +39C0 +70E0 +E070 +C030 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 2 0 -2 +BITMAP +FFF0 +FFF0 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 7 3 14 +BITMAP +C0 +E0 +70 +38 +1C +0E +06 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +3F80 +3FC0 +00E0 +0060 +0060 +3FE0 +7FE0 +E060 +C060 +E0E0 +7FE0 +3FC0 +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C000 +C000 +C000 +C000 +C000 +FF80 +FFC0 +C0E0 +C060 +C060 +C060 +C060 +C060 +C060 +C0E0 +FFC0 +FF80 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +3F80 +7F80 +E000 +C000 +C000 +C000 +C000 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0030 +0030 +0030 +0030 +0030 +3FF0 +7FF0 +E030 +C030 +C030 +C030 +C030 +C030 +C030 +E030 +7FF0 +3FF0 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C0E0 +FFC0 +FF80 +C000 +C000 +E000 +7F80 +3F80 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +0F00 +1F80 +39C0 +30E0 +3060 +3000 +3000 +3000 +FC00 +FC00 +3000 +3000 +3000 +3000 +3000 +3000 +3000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 16 1 -2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C060 +C060 +C060 +C060 +E060 +7FE0 +3FE0 +0060 +00E0 +3FC0 +3F80 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C000 +C000 +C000 +C000 +C000 +FF80 +FFC0 +C0E0 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 16 3 2 +BITMAP +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 9 20 3 -2 +BITMAP +0180 +0180 +0000 +0000 +0F80 +0F80 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +0180 +C180 +E380 +7F00 +3E00 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 17 1 2 +BITMAP +C000 +C000 +C000 +C000 +C000 +C060 +C0E0 +C1C0 +C380 +C700 +FE00 +FE00 +C700 +C380 +C1C0 +C0E0 +C060 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 17 3 2 +BITMAP +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +F380 +FFC0 +DEE0 +CC60 +CC60 +CC60 +CC60 +CC60 +CC60 +CC60 +CC60 +CC60 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +CF80 +DFC0 +F8E0 +F060 +E060 +C060 +C060 +C060 +C060 +C060 +C060 +C060 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +3F80 +7FC0 +E0E0 +C060 +C060 +C060 +C060 +C060 +C060 +E0E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 16 1 -2 +BITMAP +FF80 +FFC0 +C0E0 +C060 +C060 +C060 +C060 +C060 +C060 +C0E0 +FFC0 +FF80 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 16 1 -2 +BITMAP +3FE0 +7FE0 +E060 +C060 +C060 +C060 +C060 +C060 +C060 +E060 +7FE0 +3FE0 +0060 +0060 +0060 +0060 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +CF80 +DFC0 +F8E0 +F060 +E060 +C000 +C000 +C000 +C000 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +3FE0 +7FE0 +E000 +C000 +E000 +7F80 +3FC0 +00E0 +0060 +00E0 +FFC0 +FF80 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0600 +0600 +0600 +0600 +0600 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0700 +03F0 +01F0 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 12 1 2 +BITMAP +C060 +C060 +C060 +C060 +C060 +C060 +C0E0 +C1E0 +C3E0 +E760 +7E60 +3C60 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 12 1 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E1C0 +7380 +3F00 +1E00 +0C00 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 12 1 2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +CCC0 +CCC0 +CCC0 +DEC0 +FFC0 +7380 +3300 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +C030 +E070 +70E0 +39C0 +1F80 +0F00 +0F00 +1F80 +39C0 +70E0 +E070 +C030 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 10 16 1 -2 +BITMAP +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +C0C0 +E0C0 +71C0 +3B80 +1F00 +0E00 +1C00 +3800 +7000 +E000 +C000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +FFF0 +FFF0 +00E0 +01C0 +0380 +0700 +0E00 +1C00 +3800 +7000 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 21 3 0 +BITMAP +0E +1E +38 +30 +30 +30 +30 +30 +70 +E0 +C0 +E0 +70 +30 +30 +30 +30 +30 +38 +1E +0E +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 2 21 5 0 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 6 21 3 0 +BITMAP +C0 +E0 +70 +30 +30 +30 +30 +30 +38 +1C +0C +1C +38 +30 +30 +30 +30 +30 +70 +E0 +C0 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 11 7 1 7 +BITMAP +3060 +7860 +FC60 +CC60 +CEE0 +C7C0 +C380 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 648 0 +DWIDTH 9 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 2 17 5 2 +BITMAP +C0 +C0 +C0 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 16 0 0 +BITMAP +0600 +0600 +1FC0 +1FC0 +E630 +E630 +E630 +E600 +E600 +E630 +E630 +1FC0 +1FC0 +1FC0 +0600 +0600 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +07C0 +07C0 +07C0 +1830 +1830 +1800 +1800 +FE00 +FE00 +FE00 +1800 +1800 +1830 +1830 +E7C0 +E7C0 +E7C0 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +E630 +E630 +19C0 +19C0 +19C0 +E030 +E030 +19C0 +19C0 +E630 +E630 +E630 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +E030 +E030 +E030 +19C0 +19C0 +FFF0 +FFF0 +0600 +0600 +0600 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 2 17 5 2 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 9 19 3 2 +BITMAP +3F80 +3F80 +C000 +C000 +C000 +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +0180 +0180 +FE00 +FE00 +FE00 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 2 3 19 +BITMAP +CE +CE +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 14 17 0 2 +BITMAP +1FF0 +1FF0 +1FF0 +E00C +E00C +E7CC +E7CC +E60C +E60C +E60C +E7CC +E7CC +E00C +E00C +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 11 3 12 +BITMAP +3E +3E +CE +CE +3E +3E +3E +00 +00 +FE +FE +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +0630 +0630 +19C0 +19C0 +19C0 +E600 +E600 +19C0 +19C0 +0630 +0630 +0630 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 7 0 5 +BITMAP +FFF0 +FFF0 +FFF0 +0030 +0030 +0030 +0030 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 3 3 9 +BITMAP +FE +FE +FE +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 14 17 0 2 +BITMAP +1FF0 +1FF0 +1FF0 +E00C +E00C +E7CC +E7CC +E60C +E60C +E60C +E60C +E60C +E00C +E00C +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 2 0 19 +BITMAP +FFF0 +FFF0 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 9 9 3 14 +BITMAP +3E00 +3E00 +C180 +C180 +C180 +C180 +C180 +3E00 +3E00 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0600 +0600 +0600 +0600 +0600 +FFF0 +FFF0 +0600 +0600 +0600 +0600 +0600 +0000 +0000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 11 3 12 +BITMAP +30 +30 +CE +CE +0E +0E +0E +30 +30 +FE +FE +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 11 3 12 +BITMAP +F0 +F0 +0E +0E +30 +30 +30 +0E +0E +F0 +F0 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 7 3 14 +BITMAP +0E +0E +30 +30 +30 +C0 +C0 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 16 0 -2 +BITMAP +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E1F0 +E1F0 +FE30 +FE30 +FE30 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1FF0 +1FF0 +FE30 +FE30 +FE30 +FE30 +FE30 +FE30 +FE30 +1E30 +1E30 +1E30 +0630 +0630 +0630 +0630 +0630 +0630 +0630 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 5 5 5 9 +BITMAP +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 4 3 -2 +BITMAP +0E +0E +F0 +F0 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 11 3 12 +BITMAP +30 +30 +F0 +F0 +30 +30 +30 +30 +30 +FE +FE +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 12 3 14 +BITMAP +30 +30 +30 +CE +CE +30 +30 +00 +00 +00 +FE +FE +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +E600 +E600 +19C0 +19C0 +19C0 +0630 +0630 +19C0 +19C0 +E600 +E600 +E600 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +F800 +F800 +1830 +1830 +19C0 +19C0 +19C0 +1E00 +1E00 +19C0 +19C0 +E7C0 +E7C0 +E7C0 +19C0 +19C0 +1FF0 +1FF0 +01C0 +01C0 +01C0 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +F800 +F800 +1830 +1830 +19C0 +19C0 +19C0 +1E00 +1E00 +19C0 +19C0 +E630 +E630 +E630 +0030 +0030 +01C0 +01C0 +07F0 +07F0 +07F0 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +F800 +F800 +F800 +0600 +0600 +1830 +1830 +07C0 +07C0 +07C0 +FE00 +FE00 +19C0 +19C0 +E7C0 +E7C0 +E7C0 +19C0 +19C0 +1FF0 +1FF0 +01C0 +01C0 +01C0 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +0600 +0600 +0600 +0000 +0000 +0600 +0600 +0600 +0600 +0600 +1800 +1800 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +01C0 +01C0 +01C0 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +0600 +0600 +0600 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1E30 +1E30 +1E30 +E7C0 +E7C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 2 +BITMAP +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +0600 +0600 +0600 +19C0 +19C0 +0600 +0600 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +FFF0 +FFF0 +FFF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1FF0 +1FF0 +1FF0 +E600 +E600 +E600 +E600 +FFC0 +FFC0 +FFC0 +E600 +E600 +E600 +E600 +E7F0 +E7F0 +E7F0 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 -2 +BITMAP +1FC0 +1FC0 +1FC0 +E030 +E030 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E030 +E030 +1FC0 +1FC0 +1FC0 +01C0 +01C0 +1E00 +1E00 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +0600 +0600 +0000 +0000 +FFF0 +FFF0 +FFF0 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +01C0 +01C0 +01C0 +0600 +0600 +0000 +0000 +FFF0 +FFF0 +FFF0 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +0600 +0600 +0600 +19C0 +19C0 +0000 +0000 +FFF0 +FFF0 +FFF0 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 2 +BITMAP +19C0 +19C0 +0000 +0000 +FFF0 +FFF0 +FFF0 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 24 3 2 +BITMAP +C0 +C0 +C0 +30 +30 +00 +00 +FE +FE +FE +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 24 3 2 +BITMAP +0E +0E +0E +30 +30 +00 +00 +FE +FE +FE +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 24 3 2 +BITMAP +30 +30 +30 +CE +CE +00 +00 +FE +FE +FE +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 21 3 2 +BITMAP +CE +CE +00 +00 +FE +FE +FE +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1FC0 +1FC0 +1FC0 +1830 +1830 +1830 +1830 +FE30 +FE30 +FE30 +1830 +1830 +1830 +1830 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1E30 +1E30 +1E30 +E7C0 +E7C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +F830 +F830 +E630 +E630 +E630 +E1F0 +E1F0 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +01C0 +01C0 +01C0 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +0600 +0600 +0600 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1E30 +1E30 +1E30 +E7C0 +E7C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 2 +BITMAP +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 11 0 5 +BITMAP +E030 +E030 +19C0 +19C0 +0600 +0600 +0600 +19C0 +19C0 +E030 +E030 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 0 +BITMAP +0030 +0030 +1FC0 +1FC0 +1FC0 +E1F0 +E1F0 +E630 +E630 +E630 +E630 +E630 +E630 +E630 +F830 +F830 +1FC0 +1FC0 +1FC0 +E000 +E000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +1800 +1800 +1800 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +01C0 +01C0 +01C0 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +0600 +0600 +0600 +19C0 +19C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 2 +BITMAP +19C0 +19C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 24 0 2 +BITMAP +01C0 +01C0 +01C0 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +19C0 +19C0 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +0600 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 9 17 3 2 +BITMAP +C000 +C000 +C000 +FE00 +FE00 +C180 +C180 +C180 +C180 +C180 +C180 +C180 +FE00 +FE00 +C000 +C000 +C000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +1FC0 +1FC0 +1FC0 +E030 +E030 +E1C0 +E1C0 +E600 +E600 +E600 +E1C0 +E1C0 +E030 +E030 +E7C0 +E7C0 +E7C0 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1800 +1800 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +01C0 +01C0 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0600 +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1E30 +1E30 +E7C0 +E7C0 +E7C0 +0000 +0000 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0600 +19C0 +19C0 +19C0 +0600 +0600 +1FC0 +1FC0 +0030 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +1FC0 +1FC0 +0630 +0630 +0630 +1FC0 +1FC0 +E600 +E600 +1FF0 +1FF0 +1FF0 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 16 0 -2 +BITMAP +1FC0 +1FC0 +E030 +E030 +E030 +E000 +E000 +E030 +E030 +1FC0 +1FC0 +1FC0 +01C0 +01C0 +1E00 +1E00 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1800 +1800 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +FFC0 +FFC0 +E000 +E000 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +01C0 +01C0 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +FFC0 +FFC0 +E000 +E000 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0600 +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +FFC0 +FFC0 +E000 +E000 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +FFC0 +FFC0 +E000 +E000 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 19 3 2 +BITMAP +C0 +C0 +30 +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 19 3 2 +BITMAP +0E +0E +30 +30 +30 +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 19 3 2 +BITMAP +30 +30 +CE +CE +CE +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 7 17 3 2 +BITMAP +CE +CE +CE +00 +00 +F0 +F0 +30 +30 +30 +30 +30 +30 +30 +FE +FE +FE +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 2 +BITMAP +19C0 +19C0 +0600 +0600 +19C0 +19C0 +19C0 +0030 +0030 +1FF0 +1FF0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1E30 +1E30 +E7C0 +E7C0 +E7C0 +0000 +0000 +E7C0 +E7C0 +F830 +F830 +F830 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1800 +1800 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +01C0 +01C0 +0600 +0600 +0600 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0600 +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1E30 +1E30 +E7C0 +E7C0 +E7C0 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +19C0 +19C0 +19C0 +0000 +0000 +1FC0 +1FC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 11 0 5 +BITMAP +0600 +0600 +0000 +0000 +FFF0 +FFF0 +FFF0 +0000 +0000 +0600 +0600 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 12 0 2 +BITMAP +1FF0 +1FF0 +E1F0 +E1F0 +E1F0 +E630 +E630 +F830 +F830 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +1800 +1800 +0600 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +01C0 +01C0 +0600 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 19 0 2 +BITMAP +0600 +0600 +19C0 +19C0 +19C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 17 0 2 +BITMAP +19C0 +19C0 +19C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 23 0 -2 +BITMAP +01C0 +01C0 +0600 +0600 +0600 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +19C0 +19C0 +0600 +0600 +0600 +1800 +1800 +E000 +E000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 -2 +BITMAP +E000 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 1008 0 +DWIDTH 14 0 +BBX 12 21 0 -2 +BITMAP +19C0 +19C0 +19C0 +0000 +0000 +E030 +E030 +E030 +E030 +E030 +E030 +E030 +19C0 +19C0 +0600 +0600 +0600 +1800 +1800 +E000 +E000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-16x32.bdf b/buildroot/share/fonts/marlin-16x32.bdf new file mode 100644 index 0000000000..0cbcbb6879 --- /dev/null +++ b/buildroot/share/fonts/marlin-16x32.bdf @@ -0,0 +1,5492 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 32 100 100 +FONTBOUNDINGBOX 18 31 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 30 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1C00 +1C00 +FFE0 +FFE0 +FFE0 +FC1C +FC1C +FC1C +E01C +E01C +E01C +E01C +E01C +E0FC +E0FC +E0FC +1FFC +1FFC +00E0 +00E0 +00E0 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +FC00 +FC00 +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 15 0 5 +BITMAP +0200 +0300 +0380 +03C0 +03E0 +03F0 +FFF8 +FFFC +FFF8 +03F0 +03E0 +03C0 +0380 +0300 +0200 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 22 0 3 +BITMAP +0300 +0780 +0FC0 +1FE0 +3FF0 +7FF8 +FFFC +FFFC +FFFC +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +FF00 +FF00 +FF00 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 0 +BITMAP +0300 +0300 +1FE0 +1FE0 +1FE0 +E31C +E31C +E31C +E31C +E31C +E3FC +E3FC +E3FC +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 1296 0 +DWIDTH 18 0 +BBX 16 13 0 6 +BITMAP +F9E0 +F9F0 +7CF8 +3E7C +1F3E +0F9F +078F +0F9F +1F3E +3E7C +7EF8 +FDF0 +F9E0 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 0 +BITMAP +FFFC +FFFC +E31C +E31C +E31C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E31C +E31C +E31C +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 26 0 -2 +BITMAP +0780 +0FC0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +3CF0 +7CF8 +F03C +E01C +E01C +E31C +E31C +E31C +E31C +E31C +E01C +E01C +F03C +7FF8 +3FF0 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 7 7 1 12 +BITMAP +38 +7C +EE +C6 +EE +7C +38 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 2 19 6 3 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 8 3 16 +BITMAP +E7 +E7 +E7 +E7 +E7 +E7 +E7 +E7 +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 16 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +FFFC +FFFC +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +1CE0 +FFFC +FFFC +1CE0 +1CE0 +1CE0 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 25 0 0 +BITMAP +0300 +0300 +0300 +1FE0 +3FF0 +7FF8 +F33C +E31C +E31C +E300 +F300 +7FE0 +3FF0 +1FF8 +033C +031C +031C +E31C +F33C +7FF8 +3FF0 +1FE0 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +F81C +F81C +F81C +F81C +F83C +0078 +00F0 +01E0 +03C0 +0780 +0F00 +1E00 +3C00 +7800 +F07C +E07C +E07C +E07C +E07C +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1C00 +3E00 +7E00 +F700 +E300 +E300 +E300 +F700 +7E00 +3E00 +3E00 +771C +E3BC +E1FC +E0F0 +F1F0 +7FFC +3FBC +1F1C +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 2 8 6 16 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 7 24 4 0 +BITMAP +0E +1E +38 +30 +60 +60 +60 +60 +E0 +C0 +C0 +C0 +C0 +C0 +C0 +E0 +60 +60 +60 +30 +38 +18 +0E +0E +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 7 24 5 0 +BITMAP +E0 +F0 +38 +18 +0C +0C +0C +0C +0E +06 +06 +06 +06 +06 +06 +0E +0C +0C +0C +18 +38 +30 +E0 +E0 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +0300 +0300 +0300 +E31C +E31C +F33C +3FF0 +1FE0 +0300 +0300 +0300 +1FE0 +1FE0 +3FF0 +F33C +E31C +0300 +0300 +0300 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 6 +BITMAP +0300 +0300 +0300 +0300 +0300 +FFFC +FFFC +FFFC +0300 +0300 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 5 8 3 0 +BITMAP +F8 +F8 +18 +18 +38 +F0 +E0 +C0 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 3 0 11 +BITMAP +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 5 5 3 3 +BITMAP +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +001C +001C +0038 +0070 +00F0 +00E0 +01C0 +03C0 +0380 +0700 +0F00 +0E00 +1C00 +1C00 +3800 +7000 +F000 +E000 +C000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E0FC +E1FC +E3DC +E79C +EF1C +FE1C +FC1C +F81C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 19 3 3 +BITMAP +18 +38 +78 +F8 +F8 +F8 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +001C +003C +0078 +00F0 +01E0 +03C0 +0780 +0F00 +1E00 +3C00 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +001C +001C +003C +0078 +00F0 +01E0 +03F0 +03F8 +003C +001C +001C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +00E0 +01E0 +03E0 +07E0 +0FE0 +1EE0 +3CE0 +78E0 +F0E0 +E0E0 +E0E0 +FFFC +FFFC +FFFC +00E0 +00E0 +00E0 +00E0 +00E0 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +E000 +E000 +E000 +FFF0 +FFF8 +003C +001C +001C +001C +001C +001C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +03E0 +07E0 +0FE0 +1E00 +3C00 +7800 +F000 +E000 +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +001C +001C +003C +0078 +00F0 +01E0 +03C0 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +F01C +7FFC +3FFC +1FFC +001C +001C +003C +0078 +00F0 +1FE0 +1FC0 +1F80 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 5 13 3 3 +BITMAP +F8 +F8 +F8 +F8 +F8 +00 +00 +00 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 5 16 3 0 +BITMAP +F8 +F8 +F8 +F8 +F8 +00 +00 +00 +F8 +F8 +F8 +18 +18 +F8 +F0 +E0 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 14 3 5 +BITMAP +07 +0F +1F +3C +78 +F0 +E0 +E0 +F0 +78 +3C +1F +0F +07 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 9 0 8 +BITMAP +FFFC +FFFC +FFFC +0000 +0000 +0000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 14 3 5 +BITMAP +E0 +F0 +F8 +7C +3E +1F +0F +0F +1F +3E +7C +F8 +F0 +E0 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E03C +0078 +00F0 +01E0 +03C0 +0380 +0380 +0380 +0380 +0000 +0000 +0380 +0380 +0380 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E1FC +E3FC +E31C +E31C +E31C +E3FC +E3FC +E1F8 +E000 +F000 +7FE0 +3FE0 +1FE0 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFE0 +FFF0 +FFF8 +1C3C +1C1C +1C1C +1C1C +1C3C +1FF8 +1FF0 +1FF8 +1C3C +1C1C +1C1C +1C1C +1C3C +FFF8 +FFF0 +FFE0 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFE0 +FFF0 +FFF8 +1C3C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C1C +1C3C +FFF8 +FFF0 +FFE0 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E000 +E000 +E000 +E000 +E000 +E0FC +E0FC +E0FC +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 19 3 3 +BITMAP +FF +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +07FC +07FC +07FC +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +E0E0 +F1E0 +7FC0 +3F80 +1F00 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E03C +E078 +E0F0 +E1E0 +E3C0 +E780 +EF00 +FE00 +FC00 +FE00 +EF00 +E780 +E3C0 +E1E0 +E0F0 +E078 +E03C +E01C +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +F03C +F87C +FCFC +FFFC +EFDC +E79C +E31C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +F01C +F81C +FC1C +FE1C +EF1C +E79C +E3DC +E1FC +E0FC +E07C +E03C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +E03C +FFF8 +FFF0 +FFE0 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E19C +E1DC +E1EC +F0F0 +7F78 +3FBC +1F9C +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +E03C +FFF8 +FFF0 +FFE0 +E700 +E780 +E3C0 +E1E0 +E0F0 +E078 +E03C +E01C +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E000 +F000 +7FE0 +3FF0 +1FF8 +003C +001C +001C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +F03C +7038 +3878 +3870 +1CE0 +1FE0 +0FC0 +0780 +0300 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E79C +E79C +E79C +E79C +F7BC +7FF8 +3FF0 +1CE0 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +E01C +F03C +7878 +3CF0 +1FE0 +0FC0 +07C0 +0FC0 +1FE0 +3FF0 +7CF8 +F87C +F03C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 15 19 0 3 +BITMAP +E00E +E00E +E00E +E00E +E00E +E00E +701C +3838 +1FF0 +0FE0 +07C0 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +FFFC +FFFC +FFFC +001C +003C +0078 +00F0 +01E0 +03C0 +0780 +0F00 +1E00 +3C00 +7800 +F000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 24 3 0 +BITMAP +FF +FF +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +FF +FF +FF +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E000 +F000 +F000 +7800 +3C00 +1C00 +1E00 +0F00 +0780 +0380 +03C0 +01C0 +01E0 +00E0 +00F0 +0078 +003C +001C +001C +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 25 3 0 +BITMAP +FF +FF +FF +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +07 +FF +FF +FF +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 8 0 16 +BITMAP +0780 +0FC0 +1FE0 +3FF0 +7CF8 +F87C +F03C +E01C +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 3 0 -2 +BITMAP +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 8 3 16 +BITMAP +E0 +F0 +78 +3C +1E +0F +07 +03 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 14 0 3 +BITMAP +1FE0 +1FF0 +1FF8 +003C +001C +001C +1FFC +3FFC +7FFC +E01C +E01C +7FFC +3FFC +1FFC +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E000 +E000 +E000 +E000 +E000 +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +E01C +E01C +E01C +E03C +FFF8 +FFF0 +FFE0 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 14 0 3 +BITMAP +1FE0 +3FE0 +7FE0 +F000 +E000 +E000 +E000 +E000 +E000 +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +001C +001C +001C +001C +001C +1FFC +3FFC +7FFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +F01C +7FFC +3FFC +1FFC +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 14 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E03C +FFF8 +FFF0 +FFE0 +E000 +F000 +7FE0 +3FE0 +1FE0 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +03E0 +07F0 +0FF8 +1E3C +1C1C +1C1C +1C00 +1C00 +FF80 +FF80 +FF80 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 -2 +BITMAP +1FE0 +3FF0 +7FF8 +F01C +E01C +E01C +E01C +E01C +E01C +E01C +F01C +7FFC +3FFC +1FFC +001C +001C +003C +1FF8 +1FF0 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E000 +E000 +E000 +E000 +E000 +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 9 19 3 3 +BITMAP +1C00 +1C00 +1C00 +0000 +0000 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 11 24 3 -2 +BITMAP +00E0 +00E0 +00E0 +0000 +0000 +07E0 +07E0 +07E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +00E0 +E0E0 +E0E0 +F1E0 +7FC0 +3F80 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E000 +E000 +E000 +E000 +E000 +E01C +E03C +E078 +E0F0 +E1E0 +E3C0 +FF80 +FF80 +FFC0 +E1E0 +E0F0 +E078 +E03C +E01C +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 9 19 3 3 +BITMAP +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +FEF0 +FFF8 +E7BC +E31C +E31C +E31C +E31C +E31C +E31C +E31C +E31C +E31C +E31C +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E7F0 +EFF8 +FFFC +FC3C +F81C +F01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +1FE0 +3FF0 +7FF8 +F03C +E01C +E01C +E01C +E01C +E01C +F03C +7FF8 +3FF0 +1FE0 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 18 0 -2 +BITMAP +FFE0 +FFF0 +FFF8 +E03C +E01C +E01C +E01C +E01C +E01C +E03C +FFF8 +FFF0 +FFE0 +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 18 0 -2 +BITMAP +1FFC +3FFC +7FFC +F01C +E01C +E01C +E01C +E01C +E01C +F01C +7FFC +3FFC +1FFC +001C +001C +001C +001C +001C +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E7F0 +EFF8 +FFFC +FC1C +F81C +F000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +1FFC +3FFC +7FFC +E000 +F000 +7FE0 +3FF0 +1FF8 +003C +001C +FFF8 +FFF0 +FFE0 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +0700 +0700 +0700 +0700 +0700 +FFFC +FFFC +FFFC +0700 +0700 +0700 +0700 +0700 +0700 +0700 +0780 +03FC +01FC +00FC +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E03C +E07C +E0FC +F1FC +7FDC +3F9C +1F1C +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +F03C +7878 +3CF0 +1FE0 +0FC0 +0780 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E01C +E01C +E01C +E01C +E01C +E31C +E31C +E31C +E31C +F7BC +7FF8 +3FF0 +1CE0 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E01C +F03C +7878 +3CF0 +1FE0 +0FC0 +0780 +0FC0 +1FE0 +3CF0 +7878 +F03C +E01C +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 13 18 0 -2 +BITMAP +E038 +E038 +E038 +E038 +E038 +E038 +E038 +F078 +78F0 +3DE0 +1FC0 +0F80 +0F00 +1E00 +3C00 +7800 +F000 +E000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +FFFC +FFFC +FFFC +00F0 +01E0 +03C0 +0780 +0F00 +1E00 +3C00 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 24 3 0 +BITMAP +07 +0F +1C +18 +18 +18 +18 +18 +38 +38 +E0 +E0 +E0 +38 +38 +18 +18 +18 +18 +18 +1C +0F +0F +07 +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 3 24 6 0 +BITMAP +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 24 3 0 +BITMAP +E0 +F0 +38 +18 +18 +18 +18 +18 +18 +1C +07 +07 +07 +1C +18 +18 +18 +18 +18 +18 +38 +F0 +E0 +E0 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 8 0 8 +BITMAP +3C1C +7E1C +F71C +E31C +E3BC +E1F0 +E0E0 +E0E0 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 792 0 +DWIDTH 11 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 2 19 6 3 +BITMAP +C0 +C0 +C0 +00 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 0 +BITMAP +0300 +0300 +0300 +1FE0 +1FE0 +E31C +E31C +E31C +E300 +E300 +E300 +E31C +E31C +1FE0 +1FE0 +1FE0 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +03E0 +03E0 +03E0 +1C1C +1C1C +1C1C +1C00 +1C00 +FF00 +FF00 +FF00 +1C00 +1C00 +1C00 +1C1C +1C1C +E3E0 +E3E0 +E3E0 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E31C +E31C +1CE0 +1CE0 +1CE0 +E01C +E01C +E01C +1CE0 +1CE0 +E31C +E31C +E31C +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +E01C +E01C +E01C +1CE0 +1CE0 +1CE0 +FFFC +FFFC +0300 +0300 +0300 +FFFC +FFFC +FFFC +0300 +0300 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 2 19 6 3 +BITMAP +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +00 +00 +00 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +C0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 11 21 3 3 +BITMAP +1FE0 +1FE0 +E000 +E000 +E000 +1F00 +1F00 +1F00 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +1F00 +1F00 +1F00 +00E0 +00E0 +FF00 +FF00 +FF00 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 2 3 22 +BITMAP +E7 +E7 +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 16 19 0 3 +BITMAP +1FFC +1FFC +1FFC +E003 +E003 +E003 +E3E3 +E3E3 +E303 +E303 +E303 +E3E3 +E3E3 +E3E3 +E003 +E003 +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 13 3 14 +BITMAP +1F +1F +1F +E7 +E7 +1F +1F +1F +00 +00 +00 +FF +FF +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +031C +031C +1CE0 +1CE0 +1CE0 +E300 +E300 +E300 +1CE0 +1CE0 +031C +031C +031C +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 8 0 6 +BITMAP +FFFC +FFFC +FFFC +001C +001C +001C +001C +001C +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 3 3 11 +BITMAP +FF +FF +FF +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 16 19 0 3 +BITMAP +1FFC +1FFC +1FFC +E003 +E003 +E003 +E3E3 +E3E3 +E303 +E303 +E303 +E303 +E303 +E303 +E003 +E003 +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 2 0 22 +BITMAP +FFFC +FFFC +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 11 11 3 16 +BITMAP +1F00 +1F00 +1F00 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +1F00 +1F00 +1F00 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +0300 +0300 +0300 +0300 +0300 +0300 +FFFC +FFFC +0300 +0300 +0300 +0300 +0300 +0300 +0000 +0000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 13 3 14 +BITMAP +18 +18 +18 +E7 +E7 +07 +07 +07 +18 +18 +18 +FF +FF +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 13 3 14 +BITMAP +F8 +F8 +F8 +07 +07 +18 +18 +18 +07 +07 +07 +F8 +F8 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 8 3 16 +BITMAP +07 +07 +18 +18 +18 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 18 0 -2 +BITMAP +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E0FC +E0FC +FF1C +FF1C +FF1C +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1FFC +1FFC +FF1C +FF1C +FF1C +FF1C +FF1C +FF1C +FF1C +FF1C +1F1C +1F1C +1F1C +031C +031C +031C +031C +031C +031C +031C +031C +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 5 5 6 11 +BITMAP +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 5 3 -2 +BITMAP +07 +07 +07 +F8 +F8 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 13 3 14 +BITMAP +18 +18 +18 +F8 +F8 +18 +18 +18 +18 +18 +18 +FF +FF +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 14 3 16 +BITMAP +18 +18 +18 +E7 +E7 +E7 +18 +18 +00 +00 +00 +FF +FF +FF +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +E300 +E300 +1CE0 +1CE0 +1CE0 +031C +031C +031C +1CE0 +1CE0 +E300 +E300 +E300 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +FC00 +FC00 +FC00 +1C1C +1C1C +1CE0 +1CE0 +1CE0 +1F00 +1F00 +1F00 +1CE0 +1CE0 +E3E0 +E3E0 +E3E0 +1CE0 +1CE0 +1CE0 +1FFC +1FFC +00E0 +00E0 +00E0 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +FC00 +FC00 +FC00 +1C1C +1C1C +1CE0 +1CE0 +1CE0 +1F00 +1F00 +1F00 +1CE0 +1CE0 +E31C +E31C +E31C +001C +001C +001C +00E0 +00E0 +03FC +03FC +03FC +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +FC00 +FC00 +FC00 +0300 +0300 +0300 +1C1C +1C1C +03E0 +03E0 +03E0 +FF00 +FF00 +FF00 +1CE0 +1CE0 +E3E0 +E3E0 +E3E0 +1CE0 +1CE0 +1CE0 +1FFC +1FFC +00E0 +00E0 +00E0 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +0300 +0300 +0300 +0000 +0000 +0000 +0300 +0300 +0300 +0300 +0300 +1C00 +1C00 +1C00 +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +00E0 +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1F1C +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +0300 +0300 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +FFFC +FFFC +FFFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FFC +1FFC +1FFC +E300 +E300 +E300 +E300 +E300 +FFE0 +FFE0 +FFE0 +E300 +E300 +E300 +E300 +E300 +E3FC +E3FC +E3FC +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 -2 +BITMAP +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E01C +E01C +1FE0 +1FE0 +1FE0 +00E0 +00E0 +00E0 +1F00 +1F00 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +00E0 +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +FFFC +FFFC +FFFC +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 27 3 3 +BITMAP +E0 +E0 +E0 +18 +18 +18 +00 +00 +FF +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 27 3 3 +BITMAP +07 +07 +07 +18 +18 +18 +00 +00 +FF +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 27 3 3 +BITMAP +18 +18 +18 +E7 +E7 +E7 +00 +00 +FF +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 24 3 3 +BITMAP +E7 +E7 +E7 +00 +00 +FF +FF +FF +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +1FE0 +1FE0 +1C1C +1C1C +1C1C +1C1C +1C1C +FF1C +FF1C +FF1C +1C1C +1C1C +1C1C +1C1C +1C1C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1F1C +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +FC1C +FC1C +E31C +E31C +E31C +E0FC +E0FC +E0FC +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +00E0 +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1F1C +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 6 +BITMAP +E01C +E01C +E01C +1CE0 +1CE0 +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +E01C +E01C +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 0 +BITMAP +001C +001C +1FE0 +1FE0 +1FE0 +E0FC +E0FC +E0FC +E31C +E31C +E31C +E31C +E31C +E31C +E31C +E31C +FC1C +FC1C +1FE0 +1FE0 +1FE0 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +1C00 +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +00E0 +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +0300 +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 27 0 3 +BITMAP +00E0 +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +1CE0 +1CE0 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +0300 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 11 19 3 3 +BITMAP +E000 +E000 +E000 +FF00 +FF00 +FF00 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +E0E0 +FF00 +FF00 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1FE0 +1FE0 +1FE0 +E01C +E01C +E01C +E0E0 +E0E0 +E300 +E300 +E300 +E0E0 +E0E0 +E0E0 +E01C +E01C +E3E0 +E3E0 +E3E0 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +0000 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +0300 +0300 +1CE0 +1CE0 +1CE0 +0300 +0300 +0300 +1FE0 +1FE0 +001C +001C +001C +1FFC +1FFC +1FFC +E01C +E01C +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +1FE0 +1FE0 +031C +031C +031C +1FE0 +1FE0 +1FE0 +E300 +E300 +1FFC +1FFC +1FFC +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 18 0 -2 +BITMAP +1FE0 +1FE0 +E01C +E01C +E01C +E000 +E000 +E000 +E01C +E01C +1FE0 +1FE0 +1FE0 +00E0 +00E0 +00E0 +1F00 +1F00 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +FFE0 +FFE0 +FFE0 +E000 +E000 +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +FFE0 +FFE0 +FFE0 +E000 +E000 +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +FFE0 +FFE0 +FFE0 +E000 +E000 +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +FFE0 +FFE0 +FFE0 +E000 +E000 +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 21 3 3 +BITMAP +E0 +E0 +18 +18 +18 +00 +00 +00 +F8 +F8 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 21 3 3 +BITMAP +07 +07 +18 +18 +18 +00 +00 +00 +F8 +F8 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 21 3 3 +BITMAP +18 +18 +E7 +E7 +E7 +00 +00 +00 +F8 +F8 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 8 19 3 3 +BITMAP +E7 +E7 +E7 +00 +00 +00 +F8 +F8 +18 +18 +18 +18 +18 +18 +18 +18 +FF +FF +FF +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0300 +0300 +1CE0 +1CE0 +1CE0 +001C +001C +001C +1FFC +1FFC +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +0000 +E3E0 +E3E0 +FC1C +FC1C +FC1C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1F1C +1F1C +E3E0 +E3E0 +E3E0 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +1FE0 +1FE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 6 +BITMAP +0300 +0300 +0300 +0000 +0000 +FFFC +FFFC +FFFC +0000 +0000 +0000 +0300 +0300 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 13 0 3 +BITMAP +1FFC +1FFC +E0FC +E0FC +E0FC +E31C +E31C +E31C +FC1C +FC1C +FFE0 +FFE0 +FFE0 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +1C00 +1C00 +0300 +0300 +0300 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 21 0 3 +BITMAP +0300 +0300 +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 19 0 3 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1FE0 +1FE0 +1FE0 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 26 0 -2 +BITMAP +00E0 +00E0 +0300 +0300 +0300 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1CE0 +1CE0 +0300 +0300 +0300 +1C00 +1C00 +1C00 +E000 +E000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 -2 +BITMAP +E000 +E000 +E000 +E000 +E000 +E000 +FFE0 +FFE0 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +FFE0 +FFE0 +FFE0 +E000 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 1152 0 +DWIDTH 16 0 +BBX 14 24 0 -2 +BITMAP +1CE0 +1CE0 +1CE0 +0000 +0000 +0000 +E01C +E01C +E01C +E01C +E01C +E01C +E01C +E01C +1CE0 +1CE0 +0300 +0300 +0300 +1C00 +1C00 +1C00 +E000 +E000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-20x40.bdf b/buildroot/share/fonts/marlin-20x40.bdf new file mode 100644 index 0000000000..e44e0b7f70 --- /dev/null +++ b/buildroot/share/fonts/marlin-20x40.bdf @@ -0,0 +1,6458 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 40 100 100 +FONTBOUNDINGBOX 22 39 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. orig" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 38 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +FE0380 +FE0380 +FE0380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F03F80 +F03F80 +F03F80 +0FFF80 +0FFF80 +0FFF80 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +FE0000 +FE0000 +FE0000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 16 0 8 +BITMAP +01C000 +01E000 +01F000 +01F800 +01FC00 +01FE00 +FFFF00 +FFFF80 +FFFF80 +FFFF00 +01FE00 +01FC00 +01F800 +01F000 +01E000 +01C000 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 28 0 4 +BITMAP +008000 +01C000 +03E000 +07F000 +0FF800 +1FFC00 +3FFE00 +7FFF00 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +FFC000 +FFC000 +FFC000 +FFC000 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 1 +BITMAP +01C000 +01C000 +01C000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1FF80 +F1FF80 +F1FF80 +F1FF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 1584 0 +DWIDTH 22 0 +BBX 19 16 1 8 +BITMAP +F8F800 +FCFC00 +FEFE00 +7F7F00 +3FBF80 +1FDFC0 +0FEFE0 +07EFE0 +07EFE0 +07EFE0 +0FDFC0 +1FBF80 +3F7F00 +FEFE00 +FCFC00 +F8F800 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 1 +BITMAP +FFFF80 +FFFF80 +FFFF80 +F1C380 +F1C380 +F1C380 +F1C380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F1C380 +F1C380 +F1C380 +F1C380 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 33 0 -2 +BITMAP +01C000 +03E000 +07F000 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +1E3C00 +3E3E00 +7C1F00 +F80F80 +F00780 +F00780 +F08780 +F1C780 +F1C780 +F1C780 +F1C780 +F1C780 +F08780 +F00780 +F00780 +F80F80 +7FFF80 +3FFF00 +1FFE00 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 9 1 15 +BITMAP +1C00 +3E00 +7F00 +E380 +E380 +E380 +7F00 +3E00 +1C00 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 3 24 7 4 +BITMAP +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +00 +00 +00 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 10 4 21 +BITMAP +E380 +E380 +E380 +E380 +E380 +E380 +E380 +E380 +E380 +E380 +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 20 0 4 +BITMAP +0E3800 +0E3800 +0E3800 +FFFF80 +FFFF80 +FFFF80 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +0E3800 +FFFF80 +FFFF80 +FFFF80 +0E3800 +0E3800 +0E3800 +0E3800 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 16 30 1 1 +BITMAP +0380 +0380 +0380 +0380 +1FFC +3FFE +7FFF +E38F +E387 +E387 +E380 +E380 +E380 +F380 +7FFC +3FFE +1FFF +038F +0387 +0387 +E387 +E387 +E387 +F38F +7FFE +3FFC +1FF8 +0380 +0380 +0380 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FE0380 +FE0380 +FE0380 +FE0380 +FE0780 +FE0F80 +FE1F80 +003F00 +007E00 +00FC00 +01F800 +01F000 +03E000 +07C000 +0F8000 +1F0000 +3E0000 +FC3F80 +F83F80 +F03F80 +F03F80 +F03F80 +F03F80 +F03F80 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 16 24 1 4 +BITMAP +1C00 +1C00 +3E00 +7F00 +F780 +E380 +E380 +E380 +E380 +F780 +7F00 +3E00 +3C00 +7E00 +F787 +E38F +E3DF +E1FC +E0FC +F1FE +7FFF +3FCF +1F87 +1F87 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 3 10 7 21 +BITMAP +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 30 4 1 +BITMAP +0380 +0780 +0F00 +1E00 +1C00 +3800 +3800 +3800 +7000 +7000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +7000 +7000 +3800 +3800 +3C00 +1C00 +1E00 +0F00 +0780 +0380 +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 30 7 1 +BITMAP +E000 +F000 +7800 +3C00 +1C00 +0E00 +0E00 +0E00 +0700 +0700 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0380 +0700 +0700 +0E00 +0E00 +1E00 +1C00 +3C00 +7800 +F000 +E000 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +01E000 +01E000 +01E000 +E1E1C0 +F1E3C0 +F9E7C0 +7DEF80 +3FFF00 +1FFE00 +0FFC00 +01E000 +01E000 +01E000 +01E000 +0FFC00 +1FFE00 +3FFF00 +7DEF80 +F9E7C0 +F1E3C0 +C1E1C0 +01E000 +01E000 +01E000 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 7 +BITMAP +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 6 10 4 1 +BITMAP +F8 +FC +FC +1C +1C +1C +3C +F8 +F0 +E0 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 4 0 14 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 6 7 4 4 +BITMAP +FC +FC +FC +FC +FC +FC +FC +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +000180 +000380 +000780 +000F80 +000F00 +001E00 +003C00 +003C00 +007800 +00F800 +00F000 +01E000 +03C000 +07C000 +078000 +0F0000 +0F0000 +1E0000 +3C0000 +780000 +F00000 +F00000 +E00000 +C00000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F00FC0 +F01FC0 +F03FC0 +F07FC0 +F0FFC0 +F1FBC0 +F3F3C0 +F7E3C0 +FFC3C0 +FF83C0 +FF03C0 +FE03C0 +FC03C0 +F803C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 24 4 4 +BITMAP +1E00 +1E00 +3E00 +7E00 +FE00 +FE00 +FE00 +FE00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +0003C0 +0007C0 +000FC0 +001F80 +003F00 +007E00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +3F0000 +FFFFC0 +FFFFC0 +FFFFC0 +FFFFC0 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +000380 +000780 +000F00 +001E00 +003C00 +007800 +00F000 +01FC00 +01FE00 +00FF00 +000F80 +000780 +000380 +E00380 +F00380 +F80780 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +003C00 +007C00 +00FC00 +01FC00 +03FC00 +07FC00 +0FBC00 +1F3C00 +3E3C00 +7C3C00 +F83C00 +F03C00 +F03C00 +F03C00 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +FFFC00 +FFFE00 +FFFF00 +FFFF80 +0007C0 +0003C0 +0003C0 +0003C0 +0003C0 +0003C0 +E003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +00FC00 +01FC00 +03FC00 +07FC00 +0FC000 +1F8000 +3F0000 +7E0000 +FC0000 +F80000 +FFFC00 +FFFE00 +FFFF00 +FFFF80 +F007C0 +F003C0 +F003C0 +F003C0 +F003C0 +F80780 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +000780 +000780 +000780 +000F80 +001F00 +003E00 +007C00 +00F800 +01F000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +01E000 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F007C0 +7FFF80 +3FFF00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F803C0 +7FFFC0 +3FFFC0 +1FFFC0 +0FFFC0 +0003C0 +0007C0 +000F80 +001F00 +003E00 +007C00 +0FF800 +0FF000 +0FE000 +0FC000 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 6 17 4 4 +BITMAP +FC +FC +FC +FC +FC +FC +FC +00 +00 +00 +FC +FC +FC +FC +FC +FC +FC +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 6 20 4 1 +BITMAP +FC +FC +FC +FC +FC +FC +FC +00 +00 +00 +F8 +FC +FC +1C +1C +1C +3C +F8 +F0 +E0 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 16 4 8 +BITMAP +0380 +0780 +0F80 +1F00 +3E00 +7C00 +F800 +F000 +F000 +F800 +7C00 +3E00 +1F00 +0F80 +0780 +0380 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 10 0 11 +BITMAP +FFFF80 +FFFF80 +FFFF80 +000000 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 16 4 8 +BITMAP +E000 +F000 +F800 +7C00 +3E00 +1F00 +0F80 +0780 +0780 +0F80 +1F00 +7E00 +7C00 +F800 +F000 +E000 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F80F80 +F00780 +E00780 +000F80 +001F00 +003E00 +007C00 +00F800 +01F000 +01E000 +01E000 +01E000 +01E000 +000000 +000000 +000000 +01E000 +01E000 +01E000 +01E000 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F0FFC0 +F1FFC0 +F1FFC0 +F1E3C0 +F1C3C0 +F1C3C0 +F1E7C0 +F1FFC0 +F1FFC0 +F0FF80 +F00000 +F00000 +F80000 +7FFC00 +3FFC00 +1FFC00 +0FFC00 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +FFFFC0 +FFFFC0 +FFFFC0 +FFFFC0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +FFFC00 +FFFE00 +FFFF00 +FFFF80 +1E07C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E07C0 +1FFF80 +1FFF00 +1FFF00 +1FFF80 +1E07C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E07C0 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F003C0 +F003C0 +F807C0 +FFFF80 +7FFF00 +3FFE00 +1FFC00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +FFFC00 +FFFE00 +FFFF00 +FFFF80 +1E07C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E03C0 +1E07C0 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F03FC0 +F03FC0 +F03FC0 +F003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 11 24 3 4 +BITMAP +FFE0 +FFE0 +FFE0 +FFE0 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +0E00 +FFE0 +FFE0 +FFE0 +FFE0 +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +01FF80 +01FF80 +01FF80 +01FF80 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +F03C00 +F03C00 +F87C00 +7FF800 +3FF000 +1FE000 +0FC000 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00380 +F00780 +F00F80 +F01F00 +F03E00 +F07C00 +F0F800 +F1F000 +F3E000 +F7C000 +FF8000 +FF0000 +FF0000 +FF8000 +F7C000 +F3E000 +F1F000 +F0F800 +F07C00 +F03E00 +F01F00 +F00F80 +F00780 +F00380 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +F007C0 +F007C0 +F80FC0 +FC1FC0 +FE3FC0 +FF7FC0 +FFFFC0 +F7F3C0 +F3E3C0 +F1C3C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F803C0 +FC03C0 +FE03C0 +FF03C0 +FF83C0 +F7C3C0 +F3E3C0 +F1F3C0 +F0FBC0 +F07FC0 +F03FC0 +F01FC0 +F00FC0 +F007C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +FFFC00 +FFFE00 +FFFF00 +FFFF80 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F007C0 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F1C3C0 +F1E3C0 +F1F3C0 +F0F9C0 +F07DC0 +F83EC0 +7FDF40 +3FEF80 +1FF7C0 +0FF3C0 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +FFFC00 +FFFE00 +FFFF00 +FFFF80 +F007C0 +F003C0 +F003C0 +F003C0 +F003C0 +F007C0 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +F7C000 +F3E000 +F1F000 +F0F800 +F07C00 +F03E00 +F01F00 +F00F80 +F00780 +F00380 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F003C0 +F003C0 +F001C0 +F00000 +F00000 +F80000 +7FFC00 +3FFE00 +1FFF00 +0FFF80 +0007C0 +0003C0 +0003C0 +E003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +780F00 +3C1E00 +3C1E00 +1E3C00 +0E3800 +0F7800 +07F000 +03E000 +03E000 +01C000 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F1C780 +F1C780 +F1C780 +F1C780 +F1C780 +FBEF80 +7FFF00 +3FFE00 +1F7C00 +0E3800 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F80F80 +7C1F00 +3E3E00 +1F7C00 +0FF800 +07F000 +03E000 +03E000 +07F000 +0FF800 +1F7C00 +3E3E00 +7C1F00 +F80F80 +F00780 +F00780 +F00780 +F00780 +F00780 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F80F80 +7C1F00 +3E3E00 +1F7C00 +0FF800 +07F000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +03E000 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +000780 +000F80 +001F80 +003F00 +007E00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +3F0000 +7E0000 +FC0000 +F80000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 30 4 1 +BITMAP +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +E00000 +F00000 +F80000 +F80000 +7C0000 +3E0000 +3E0000 +1F0000 +0F0000 +0F8000 +07C000 +03C000 +01E000 +01F000 +00F800 +007800 +003C00 +003E00 +001F00 +001F00 +000F80 +000F80 +000780 +000380 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 30 4 1 +BITMAP +FFC0 +FFC0 +FFC0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +03C0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 10 0 21 +BITMAP +01C000 +03E000 +07F000 +0FF800 +1FFC00 +3F7E00 +7E3F00 +FC1F80 +F80F80 +F00780 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 3 0 -2 +BITMAP +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 10 4 21 +BITMAP +E000 +F000 +F800 +7C00 +3E00 +1F00 +0F80 +07C0 +03C0 +01C0 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 16 17 1 4 +BITMAP +1FF8 +1FFC +1FFE +000F +0007 +0007 +0FFF +1FFF +3FFF +7FFF +F007 +E007 +F007 +FFFF +7FFF +3FFF +1FFF +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFE00 +FFFF00 +F00780 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00780 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +1FFC00 +3FFC00 +7FFC00 +F80000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00380 +F00380 +F80780 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +000380 +000380 +000380 +000380 +000380 +000380 +000380 +1FFF80 +3FFF80 +7FFF80 +F80380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F80380 +7FFF80 +3FFF80 +1FFF80 +0FFF80 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +1FFC00 +3FFE00 +7FFF00 +F80780 +F00380 +F00380 +F00780 +FFFF00 +FFFE00 +FFFC00 +F00000 +F00000 +F80000 +7FFC00 +3FFC00 +1FFC00 +0FFC00 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 24 0 4 +BITMAP +01FC00 +03FE00 +07FF00 +0FFF80 +0F07C0 +0F03C0 +0F03C0 +0F0000 +0F0000 +0F0000 +FFF000 +FFF000 +FFF000 +FFF000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +1FFE00 +3FFF00 +7FFF80 +F80780 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F80380 +7FFF80 +3FFF80 +1FFF80 +0FFF80 +000380 +000380 +000780 +0FFF80 +0FFF00 +0FFE00 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFE00 +FFFF00 +FFFF80 +F00780 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 24 4 4 +BITMAP +1E00 +1E00 +1E00 +1E00 +0000 +0000 +0000 +FE00 +FE00 +FE00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +1E00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 13 30 4 -2 +BITMAP +0038 +0038 +0038 +0038 +0000 +0000 +0000 +03F8 +03F8 +03F8 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +0038 +E038 +E038 +F078 +FFF8 +7FF0 +3FE0 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00780 +F00F80 +F01F80 +F03F00 +F07E00 +F0FC00 +F1F800 +FFF000 +FFE000 +FFE000 +F1F000 +F0F800 +F07C00 +F03E00 +F01F00 +F00F80 +F00780 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 24 4 4 +BITMAP +FC00 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +FE3C00 +FF7E00 +FFFF00 +F3E780 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F1FC00 +F3FE00 +F7FF00 +FF8780 +FF0380 +FE0380 +FC0380 +F80380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 18 0 4 +BITMAP +0FFC00 +1FFE00 +3FFF00 +7FFF80 +F807C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F003C0 +F807C0 +7FFF80 +3FFF00 +1FFE00 +0FFC00 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +FFFE00 +FFFF00 +FFFF80 +F00780 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00780 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +1FFF80 +3FFF80 +7FFF80 +F80380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F80380 +7FFF80 +3FFF80 +1FFF80 +0FFF80 +000380 +000380 +000380 +000380 +000380 +000380 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F1FC00 +F3FE00 +F7FF00 +FFC780 +FF8380 +FF0380 +FE0380 +FC0000 +F80000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +1FFF80 +3FFF80 +7FFF80 +F80000 +F00000 +F00000 +F80000 +7FFE00 +3FFF00 +1FFF80 +000780 +000380 +000780 +FFFF80 +FFFF00 +FFFE00 +FFFC00 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01E000 +01FF80 +00FF80 +007F80 +003F80 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00780 +F00F80 +F01F80 +F03F80 +F87F80 +7FFB80 +3FF380 +1FE380 +0FC380 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F80F80 +7C1F00 +3E3E00 +1F7C00 +0FF800 +07F000 +03E000 +01C000 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F1C780 +F1C780 +F1C780 +F1C780 +F1C780 +FBEF80 +7FFF00 +3F7E00 +1F7C00 +0E3800 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +E00380 +F00780 +F80F80 +7C1F00 +3E3E00 +1F7C00 +0FF800 +07F000 +03E000 +07F000 +0FF800 +1F7C00 +3E3E00 +7C1F00 +F80F80 +F00780 +E00380 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F00780 +F80F80 +7C1F00 +3E3E00 +1F7C00 +0FF800 +07F000 +03E000 +07C000 +0F8000 +1F0000 +3E0000 +FC0000 +F80000 +F00000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +FFFF80 +FFFF80 +FFFF80 +001F00 +003E00 +007C00 +00F800 +01F000 +03E000 +07C000 +0F8000 +1F0000 +3E0000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 30 4 1 +BITMAP +03C0 +07C0 +0FC0 +1E00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +3C00 +7800 +E000 +E000 +E000 +E000 +7800 +3C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1E00 +0FC0 +07C0 +03C0 +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 3 30 7 1 +BITMAP +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 9 30 4 1 +BITMAP +E000 +F000 +F800 +3C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1E00 +0F00 +0380 +0380 +0380 +0380 +0F00 +1E00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +3C00 +F800 +F000 +E000 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 18 10 0 11 +BITMAP +0E03C0 +1F03C0 +3F83C0 +7BC3C0 +F1C3C0 +F1C3C0 +F1E7C0 +F0FF80 +F07F00 +F03E00 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 1080 0 +DWIDTH 15 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 3 24 7 4 +BITMAP +E0 +E0 +E0 +E0 +00 +00 +00 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 1 +BITMAP +01C000 +01C000 +01C000 +0FFC00 +0FFC00 +0FFC00 +F1C380 +F1C380 +F1C380 +F1C380 +F1C000 +F1C000 +F1C000 +F1C380 +F1C380 +F1C380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +01FC00 +01FC00 +01FC00 +01FC00 +0E0380 +0E0380 +0E0380 +0E0000 +0E0000 +0E0000 +FFC000 +FFC000 +FFC000 +FFC000 +0E0000 +0E0000 +0E0000 +0E0380 +0E0380 +0E0380 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F1C380 +F1C380 +F1C380 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +F1C380 +F1C380 +F1C380 +F1C380 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +F00380 +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 3 24 7 4 +BITMAP +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +00 +00 +00 +00 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +E0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 13 27 4 4 +BITMAP +1FF8 +1FF8 +1FF8 +E000 +E000 +E000 +E000 +1FC0 +1FC0 +1FC0 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +1FC0 +1FC0 +1FC0 +0038 +0038 +0038 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 3 4 28 +BITMAP +E3C0 +E3C0 +E3C0 +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 20 24 0 4 +BITMAP +0FFF80 +0FFF80 +0FFF80 +0FFF80 +F00070 +F00070 +F00070 +F1FC70 +F1FC70 +F1FC70 +F1C070 +F1C070 +F1C070 +F1C070 +F1FC70 +F1FC70 +F1FC70 +F00070 +F00070 +F00070 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 16 4 18 +BITMAP +1FC0 +1FC0 +1FC0 +E3C0 +E3C0 +E3C0 +1FC0 +1FC0 +1FC0 +1FC0 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +01C380 +01C380 +01C380 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +F1C000 +F1C000 +F1C000 +0E3C00 +0E3C00 +0E3C00 +01C380 +01C380 +01C380 +01C380 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 10 0 8 +BITMAP +FFFF80 +FFFF80 +FFFF80 +FFFF80 +000380 +000380 +000380 +000380 +000380 +000380 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 4 4 14 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 20 24 0 4 +BITMAP +0FFF80 +0FFF80 +0FFF80 +0FFF80 +F00070 +F00070 +F00070 +F1FC70 +F1FC70 +F1FC70 +F1C070 +F1C070 +F1C070 +F1C070 +F1C070 +F1C070 +F1C070 +F00070 +F00070 +F00070 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 3 0 28 +BITMAP +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 13 13 4 21 +BITMAP +1FC0 +1FC0 +1FC0 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +1FC0 +1FC0 +1FC0 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +FFFF80 +FFFF80 +FFFF80 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 16 4 18 +BITMAP +1C00 +1C00 +1C00 +E3C0 +E3C0 +E3C0 +03C0 +03C0 +03C0 +03C0 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 16 4 18 +BITMAP +FC00 +FC00 +FC00 +03C0 +03C0 +03C0 +1C00 +1C00 +1C00 +1C00 +03C0 +03C0 +03C0 +FC00 +FC00 +FC00 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 10 4 21 +BITMAP +03C0 +03C0 +03C0 +1C00 +1C00 +1C00 +1C00 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F03F80 +F03F80 +F03F80 +FFC380 +FFC380 +FFC380 +FFC380 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0FFF80 +0FFF80 +0FFF80 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +FFC380 +0FC380 +0FC380 +0FC380 +0FC380 +01C380 +01C380 +01C380 +01C380 +01C380 +01C380 +01C380 +01C380 +01C380 +01C380 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 7 7 7 14 +BITMAP +FE +FE +FE +FE +FE +FE +FE +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 6 4 -2 +BITMAP +03C0 +03C0 +03C0 +FC00 +FC00 +FC00 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 16 4 18 +BITMAP +1C00 +1C00 +1C00 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 17 4 21 +BITMAP +1C00 +1C00 +1C00 +1C00 +E3C0 +E3C0 +E3C0 +1C00 +1C00 +1C00 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +F1C000 +F1C000 +F1C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +01C380 +01C380 +01C380 +0E3C00 +0E3C00 +0E3C00 +F1C000 +F1C000 +F1C000 +F1C000 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +FE0000 +FE0000 +FE0000 +0E0380 +0E0380 +0E0380 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +0FC000 +0FC000 +0FC000 +0E3C00 +0E3C00 +0E3C00 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +0E3C00 +0E3C00 +0E3C00 +0FFF80 +0FFF80 +0FFF80 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +FE0000 +FE0000 +FE0000 +0E0380 +0E0380 +0E0380 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +0FC000 +0FC000 +0FC000 +0E3C00 +0E3C00 +0E3C00 +F1C380 +F1C380 +F1C380 +F1C380 +000380 +000380 +000380 +003C00 +003C00 +003C00 +01FF80 +01FF80 +01FF80 +01FF80 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +FE0000 +FE0000 +FE0000 +FE0000 +01C000 +01C000 +01C000 +0E0380 +0E0380 +0E0380 +01FC00 +01FC00 +01FC00 +01FC00 +FFC000 +FFC000 +FFC000 +0E3C00 +0E3C00 +0E3C00 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +0E3C00 +0E3C00 +0E3C00 +0FFF80 +0FFF80 +0FFF80 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +0E0000 +0E0000 +0E0000 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +003C00 +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0FFF80 +0FFF80 +0FFF80 +0FFF80 +F1C000 +F1C000 +F1C000 +F1C000 +F1C000 +F1C000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F1C000 +F1C000 +F1C000 +F1C000 +F1C000 +F1C000 +F1FF80 +F1FF80 +F1FF80 +F1FF80 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 -2 +BITMAP +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +003C00 +003C00 +003C00 +0FC000 +0FC000 +0FC000 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +003C00 +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 34 4 4 +BITMAP +E000 +E000 +E000 +E000 +1C00 +1C00 +1C00 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 34 4 4 +BITMAP +03C0 +03C0 +03C0 +03C0 +1C00 +1C00 +1C00 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 34 4 4 +BITMAP +1C00 +1C00 +1C00 +1C00 +E3C0 +E3C0 +E3C0 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 30 4 4 +BITMAP +E3C0 +E3C0 +E3C0 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0FFC00 +0FFC00 +0FFC00 +0FFC00 +0E0380 +0E0380 +0E0380 +0E0380 +0E0380 +0E0380 +FFC380 +FFC380 +FFC380 +FFC380 +0E0380 +0E0380 +0E0380 +0E0380 +0E0380 +0E0380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FE0380 +FE0380 +FE0380 +F1C380 +F1C380 +F1C380 +F1C380 +F03F80 +F03F80 +F03F80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +003C00 +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 16 0 8 +BITMAP +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 1 +BITMAP +000380 +000380 +000380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F03F80 +F03F80 +F03F80 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +F1C380 +FE0380 +FE0380 +FE0380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +003C00 +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +01C000 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 34 0 4 +BITMAP +003C00 +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 13 24 4 4 +BITMAP +E000 +E000 +E000 +E000 +FFC0 +FFC0 +FFC0 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +E038 +FFC0 +FFC0 +FFC0 +E000 +E000 +E000 +E000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0FFC00 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F03C00 +F03C00 +F03C00 +F1C000 +F1C000 +F1C000 +F1C000 +F03C00 +F03C00 +F03C00 +F00380 +F00380 +F00380 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +0FFC00 +0FFC00 +0FFC00 +000380 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +0FFC00 +0FFC00 +0FFC00 +01C380 +01C380 +01C380 +01C380 +0FFC00 +0FFC00 +0FFC00 +F1C000 +F1C000 +F1C000 +0FFF80 +0FFF80 +0FFF80 +0FFF80 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 23 0 -2 +BITMAP +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00000 +F00000 +F00000 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +003C00 +003C00 +003C00 +0FC000 +0FC000 +0FC000 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 27 4 4 +BITMAP +E000 +E000 +E000 +1C00 +1C00 +1C00 +1C00 +0000 +0000 +0000 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 27 4 4 +BITMAP +03C0 +03C0 +03C0 +1C00 +1C00 +1C00 +1C00 +0000 +0000 +0000 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 27 4 4 +BITMAP +1C00 +1C00 +1C00 +E3C0 +E3C0 +E3C0 +E3C0 +0000 +0000 +0000 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 10 24 4 4 +BITMAP +E3C0 +E3C0 +E3C0 +E3C0 +0000 +0000 +0000 +FC00 +FC00 +FC00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +1C00 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000380 +000380 +000380 +0FFF80 +0FFF80 +0FFF80 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +F1FC00 +F1FC00 +F1FC00 +FE0380 +FE0380 +FE0380 +FE0380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0FC380 +0FC380 +0FC380 +F1FC00 +F1FC00 +F1FC00 +F1FC00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +0FFC00 +0FFC00 +0FFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 16 0 8 +BITMAP +01C000 +01C000 +01C000 +000000 +000000 +000000 +FFFF80 +FFFF80 +FFFF80 +FFFF80 +000000 +000000 +000000 +01C000 +01C000 +01C000 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 17 0 4 +BITMAP +0FFF80 +0FFF80 +0FFF80 +F03F80 +F03F80 +F03F80 +F03F80 +F1C380 +F1C380 +F1C380 +FE0380 +FE0380 +FE0380 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +0E0000 +0E0000 +0E0000 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 27 0 4 +BITMAP +01C000 +01C000 +01C000 +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 24 0 4 +BITMAP +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0FFC00 +0FFC00 +0FFC00 +0FFC00 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 33 0 -2 +BITMAP +003C00 +003C00 +003C00 +01C000 +01C000 +01C000 +01C000 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +01C000 +0E0000 +0E0000 +0E0000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 -2 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFC00 +FFFC00 +FFFC00 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 1440 0 +DWIDTH 20 0 +BBX 17 30 0 -2 +BITMAP +0E3C00 +0E3C00 +0E3C00 +0E3C00 +000000 +000000 +000000 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +F00380 +0E3C00 +0E3C00 +0E3C00 +01C000 +01C000 +01C000 +01C000 +0E0000 +0E0000 +0E0000 +F00000 +F00000 +F00000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-24x48.bdf b/buildroot/share/fonts/marlin-24x48.bdf new file mode 100644 index 0000000000..dba6e07e7f --- /dev/null +++ b/buildroot/share/fonts/marlin-24x48.bdf @@ -0,0 +1,6462 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 40 100 100 +FONTBOUNDINGBOX 26 39 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 38 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +FF00F0 +FF00F0 +FF00F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F00FF0 +F00FF0 +F00FF0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +000F00 +000F00 +000F00 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +FF0000 +FF0000 +FF0000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 19 18 0 7 +BITMAP +00E000 +00F000 +00F800 +00FC00 +00FE00 +00FF00 +00FF80 +FFFFC0 +FFFFE0 +FFFFE0 +FFFFC0 +00FF80 +00FF00 +00FE00 +00FC00 +00F800 +00F000 +00E000 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 19 29 0 4 +BITMAP +004000 +00E000 +01F000 +03F800 +07FC00 +0FFE00 +1FFF00 +3FFF80 +7FFFC0 +FFFFE0 +FFFFE0 +FFFFE0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +FFF000 +FFF000 +FFF000 +FFF000 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 1 +BITMAP +00F000 +00F000 +00F000 +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +FCF3F0 +F8F1F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0FFF0 +F0FFF0 +F0FFF0 +F0FFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +FC03F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 1872 0 +DWIDTH 26 0 +BBX 24 16 0 8 +BITMAP +FE3F80 +7F1FC0 +3F8FE0 +1FC7F0 +0FE3F8 +07F1FC +03F8FE +01FC7F +01FC7F +03F8FE +07F1FC +0FE3F8 +1FC7F0 +3F8FE0 +7F1FC0 +FE3F80 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 1 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 33 0 -2 +BITMAP +01F800 +03FC00 +07FE00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +1F0F80 +3F0FC0 +7F0FE0 +F801F0 +F000F0 +F000F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 10 9 1 15 +BITMAP +1E00 +3F00 +7F80 +F3C0 +E1C0 +F3C0 +7F80 +3F00 +1E00 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 4 24 8 4 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +00 +00 +00 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 10 4 21 +BITMAP +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +F0F0 +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 20 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +FFFFF0 +FFFFF0 +FFFFF0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +FFFFF0 +FFFFF0 +FFFFF0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 1 +BITMAP +00F000 +00F000 +00F000 +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F8F1F0 +F0F0F0 +F0F0F0 +F0F000 +F0F000 +F8F000 +7FFF00 +3FFF80 +1FFFC0 +0FFFE0 +00F1F0 +00F0F0 +00F0F0 +F0F0F0 +F0F0F0 +F8F1F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FF00F0 +FF00F0 +FF00F0 +FF01F0 +FF03F0 +FF07E0 +FF0FC0 +001F80 +003F00 +007E00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +3F0000 +7E0FF0 +FC0FF0 +F80FF0 +F00FF0 +F00FF0 +F00FF0 +F00FF0 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0F0000 +1F8000 +3FC000 +7FE000 +F9F000 +F0F000 +F0F000 +F0F000 +F0F000 +F9F000 +7FE000 +3FC000 +3FC000 +7FE000 +F9F0F0 +F0F9F0 +F07FF0 +F03F80 +F01F00 +F83F80 +7FFFF0 +3FFFF0 +1FF9F0 +0FF0F0 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 4 10 8 21 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +01F0 +03F0 +07F0 +0F80 +1F00 +1E00 +3E00 +3C00 +7C00 +7800 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +7800 +7C00 +3C00 +3E00 +1E00 +1F00 +0F80 +07F0 +03F0 +01F0 +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +F800 +FC00 +FE00 +1F00 +0F80 +0780 +03C0 +03C0 +01E0 +01E0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +01E0 +01E0 +03C0 +03C0 +0780 +0F80 +1F00 +FE00 +FC00 +F000 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +F0F0F0 +F8F1F0 +7CF3E0 +3EF7C0 +1FFF80 +0FFF00 +07FE00 +03FC00 +03FC00 +07FE00 +0FFF00 +1FFF80 +3EF7C0 +7CF3E0 +F8F1F0 +F0F0F0 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 16 0 8 +BITMAP +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 8 10 4 1 +BITMAP +FF +FF +FF +0F +0F +0F +1E +FC +F8 +F0 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 4 0 14 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 8 7 4 4 +BITMAP +FF +FF +FF +FF +FF +FF +FF +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +000070 +0000F0 +0001F0 +0003F0 +0007E0 +000FC0 +001F80 +001F80 +003F00 +007E00 +00FC00 +01FC00 +03F800 +03F000 +07E000 +07C000 +0F8000 +1F8000 +3F0000 +7E0000 +FC0000 +F80000 +F00000 +E00000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F003F0 +F007F0 +F00FF0 +F01FF0 +F03EF0 +F07CF0 +F0F8F0 +F1F0F0 +F3E0F0 +F7C0F0 +FF80F0 +FF00F0 +FE00F0 +FC00F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 24 4 4 +BITMAP +0F00 +1F00 +3F00 +7F00 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +0001F0 +0003E0 +0007C0 +000F80 +001F00 +003E00 +007C00 +00F800 +01F000 +03E000 +07C000 +0F8000 +1F0000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +0000F0 +0001F0 +0003F0 +0007E0 +000FC0 +001F80 +003F00 +007F80 +007FC0 +003FE0 +0001F0 +0000F0 +0000F0 +E000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 25 0 4 +BITMAP +001F00 +003F00 +007F00 +00FF00 +01FF00 +03EF00 +07CF00 +0F8F00 +1F0F00 +3E0F00 +7C0F00 +F80F00 +F00F00 +F00F00 +F00F00 +FFFFF0 +FFFFF0 +FFFFF0 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +FFFF80 +FFFFC0 +FFFFE0 +0001F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +E000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +01FF00 +03FF00 +07FF00 +0FFF00 +1F8000 +3F0000 +7E0000 +FC0000 +F80000 +F00000 +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +0000F0 +0000F0 +0000F0 +0001F0 +0003E0 +0007C0 +000F80 +001F00 +003E00 +007C00 +00F800 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F800F0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +0000F0 +0001F0 +0003F0 +0007E0 +000FC0 +001F80 +0FFF00 +0FFE00 +0FFC00 +0FF800 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 8 17 4 4 +BITMAP +FF +FF +FF +FF +FF +FF +FF +00 +00 +00 +FF +FF +FF +FF +FF +FF +FF +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 8 20 4 1 +BITMAP +FF +FF +FF +FF +FF +FF +FF +00 +00 +00 +FF +FF +FF +0F +0F +0F +1E +FC +F8 +F0 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 13 16 3 8 +BITMAP +0078 +00F8 +03F8 +07E0 +1F80 +3F00 +7C00 +F800 +F800 +7C00 +3F00 +1F80 +07E0 +03F8 +00F8 +0078 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 10 0 11 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +000000 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 13 16 4 8 +BITMAP +F000 +F800 +FE00 +3F00 +0FC0 +07E0 +01F0 +00F8 +00F8 +01F0 +07E0 +0FC0 +3F00 +FE00 +F800 +F000 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +0001F0 +0003E0 +0007C0 +000F80 +001F00 +003E00 +007C00 +00F800 +00F000 +00F000 +000000 +000000 +000000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F07FF0 +F0FFF0 +F0FFF0 +F0F9F0 +F0F0F0 +F0F0F0 +F0F9F0 +F0FFF0 +F0FFF0 +F07FE0 +F00000 +F00000 +F80000 +7FFF00 +3FFF00 +1FFF00 +0FFF00 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +0F01F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F01F0 +0FFFE0 +0FFFC0 +0FFFC0 +0FFFE0 +0F01F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F01F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +0F01F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F01F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00FF0 +F00FF0 +F00FF0 +F00FF0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 24 4 4 +BITMAP +FFF0 +FFF0 +FFF0 +FFF0 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00FFF0 +00FFF0 +00FFF0 +00FFF0 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +000F00 +F00F00 +F00F00 +F81F00 +7FFE00 +3FFC00 +1FF800 +0FF000 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 19 24 0 4 +BITMAP +F001E0 +F003E0 +F007C0 +F00F80 +F01F00 +F03E00 +F07C00 +F0F800 +F1F000 +F3E000 +FFC000 +FF8000 +FF8000 +FFC000 +F3E000 +F1F000 +F0F800 +F07C00 +F03E00 +F01F00 +F00F80 +F007C0 +F003E0 +F001E0 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F801F0 +FC03F0 +FE07F0 +FF0FF0 +FF9FF0 +F7FEF0 +F3FCF0 +F1F8F0 +F0F0F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F800F0 +FC00F0 +FE00F0 +FF00F0 +FF80F0 +F7C0F0 +F3E0F0 +F1F0F0 +F0F8F0 +F07CF0 +F03EF0 +F01FF0 +F00FF0 +F007F0 +F003F0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F001F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F0F8F0 +F0FCF0 +F07EF0 +F03F70 +F01FB0 +F80FC0 +7FF7E0 +3FFBF0 +1FFDF0 +0FFCF0 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFF00 +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F001F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +F1F000 +F0F800 +F07C00 +F03E00 +F01F00 +F00F80 +F007C0 +F003E0 +F001F0 +F000F0 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F00000 +F00000 +F00000 +7FFF00 +3FFF80 +1FFFC0 +0FFFE0 +0001F0 +0000F0 +0000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7C03E0 +3E07C0 +1F0F80 +0F9F00 +07FE00 +03FC00 +01F800 +00F000 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F9F9F0 +7FFFE0 +3FFFC0 +1F9F80 +0F0F00 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7C03E0 +3E07C0 +1F0F80 +0F9F00 +07FE00 +03FC00 +03FC00 +07FE00 +0F9F00 +1F0F80 +3E07C0 +7C03E0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7C03E0 +3E07C0 +1F0F80 +0FFF00 +07FE00 +03FC00 +01F800 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +0000F0 +0001F0 +0003F0 +0007E0 +000FC0 +001F80 +003F00 +007E00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +3F0000 +7E0000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +FFF0 +FFF0 +FFF0 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +F000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +E00000 +F00000 +F80000 +FC0000 +7E0000 +3F0000 +1F8000 +0F8000 +0FC000 +07E000 +03F000 +01F800 +00F800 +007C00 +003E00 +001F00 +001F80 +000FC0 +0007C0 +0007E0 +0003F0 +0001F0 +0000F0 +000070 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +FFF0 +FFF0 +FFF0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +00F0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 11 0 21 +BITMAP +00F000 +01F800 +03FC00 +07FE00 +0F9F00 +1F0F80 +3E07C0 +7C03E0 +F801F0 +F000F0 +E00070 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 3 0 -2 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 11 4 20 +BITMAP +F000 +F800 +FC00 +7E00 +3F00 +1F80 +0FC0 +07E0 +03F0 +01F0 +00F0 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +0FFF80 +0FFFC0 +0FFFE0 +0001F0 +0000F0 +0000F0 +0FFFF0 +1FFFF0 +3FFFF0 +7FFFF0 +F800F0 +F000F0 +F800F0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F001F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +1FFF00 +3FFF00 +7FFF00 +F80000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +1FFFF0 +3FFFF0 +7FFFF0 +F800F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F800F0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F001F0 +FFFFE0 +FFFFC0 +FFFF80 +F00000 +F00000 +F80000 +7FFF00 +3FFF00 +1FFF00 +0FFF00 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00FF00 +01FF80 +03FFC0 +07FFE0 +0F81F0 +0F00F0 +0F0070 +0F0000 +0F0000 +0F0000 +FFF000 +FFF000 +FFF000 +FFF000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +0F0000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F800F0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +0000F0 +0000F0 +0001F0 +0FFFE0 +0FFFC0 +0FFF80 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 24 4 4 +BITMAP +0F00 +0F00 +0F00 +0F00 +0000 +0000 +0000 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 16 30 4 -2 +BITMAP +000F +000F +000F +000F +0000 +0000 +0000 +00FF +00FF +00FF +000F +000F +000F +000F +000F +000F +000F +000F +000F +000F +000F +000F +000F +000F +E00F +F00F +F81F +7FFE +3FFC +1FF8 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F000F0 +F001F0 +F003E0 +F007C0 +F00F80 +F01F00 +F03E00 +FFFC00 +FFF800 +FFFC00 +F03E00 +F01F00 +F00F80 +F007C0 +F003E0 +F001F0 +F000F0 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 24 4 4 +BITMAP +FF00 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +FF0F80 +FF9FC0 +FFFFE0 +F1F9F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F1FF80 +F3FFC0 +F7FFE0 +FF81F0 +FF00F0 +FE00F0 +FC00F0 +F800F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 18 0 4 +BITMAP +0FFF00 +1FFF80 +3FFFC0 +7FFFE0 +F801F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7FFFE0 +3FFFC0 +1FFF80 +0FFF00 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +FFFF80 +FFFFC0 +FFFFE0 +F001F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F001F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +1FFFF0 +3FFFF0 +7FFFF0 +F800F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F800F0 +7FFFF0 +3FFFF0 +1FFFF0 +0FFFF0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F1FF80 +F3FFC0 +F7FFE0 +FF81F0 +FF00F0 +FE0070 +FC0030 +F80000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +1FFFF0 +3FFFF0 +7FFFF0 +F80000 +F00000 +F00000 +F80000 +7FFF80 +3FFFC0 +1FFFE0 +0001F0 +0000F0 +0001F0 +FFFFE0 +FFFFC0 +FFFF80 +FFFF00 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F800 +007FF0 +003FF0 +001FF0 +000FF0 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F001F0 +F003F0 +F007F0 +F00FF0 +F81FF0 +7FFEF0 +3FFCF0 +1FF8F0 +0FF0F0 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7C03E0 +3E07C0 +1F0F80 +0F9F00 +07FE00 +03FC00 +01F800 +00F000 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F9F9F0 +7FFFE0 +3FFFC0 +1F9F80 +0F0F00 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 19 16 0 4 +BITMAP +F803E0 +7C07C0 +3E0F80 +1F1F00 +0FBE00 +07FC00 +03F800 +01F000 +01F000 +03F800 +07BC00 +0F1E00 +1E0F00 +3C0780 +7803C0 +F001E0 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F801F0 +7C03E0 +3E07C0 +1F0F80 +0F9F00 +07FE00 +03FC00 +00F800 +01F000 +03E000 +07C000 +0F8000 +FF0000 +FE0000 +FC0000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +001F80 +003F00 +007E00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +3F0000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +00F0 +01F0 +03E0 +0780 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +1F00 +3F00 +7E00 +F800 +F000 +F000 +F800 +7E00 +3F00 +1F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0780 +03E0 +01F0 +00F0 +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 4 30 8 1 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 1 +BITMAP +F000 +F800 +7C00 +3E00 +1F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F80 +0FC0 +07E0 +01F0 +00F0 +00F0 +01F0 +07E0 +0FC0 +0F80 +0F00 +0F00 +0F00 +0F00 +0F00 +1F00 +3E00 +7C00 +F800 +F000 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 10 0 11 +BITMAP +1F00F0 +3F80F0 +7FC0F0 +F3E0F0 +F1F0F0 +F0F8F0 +F07DF0 +F03FE0 +F01FC0 +F00F80 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 1368 0 +DWIDTH 19 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 4 24 8 4 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +00 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 1 +BITMAP +00F000 +00F000 +00F000 +0FFF00 +0FFF00 +0FFF00 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F000 +F0F000 +F0F000 +F0F0F0 +F0F0F0 +F0F0F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00FF00 +00FF00 +00FF00 +00FF00 +0F00F0 +0F00F0 +0F00F0 +0F0000 +0F0000 +0F0000 +FFF000 +FFF000 +FFF000 +FFF000 +0F0000 +0F0000 +0F0000 +0F00F0 +0F00F0 +0F00F0 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F0F0F0 +F0F0F0 +F0F0F0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 4 24 8 4 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +00 +00 +00 +00 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 16 27 4 4 +BITMAP +0FFF +0FFF +0FFF +F000 +F000 +F000 +F000 +0FF0 +0FF0 +0FF0 +F00F +F00F +F00F +F00F +F00F +F00F +F00F +0FF0 +0FF0 +0FF0 +000F +000F +000F +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 3 4 28 +BITMAP +F0F0 +F0F0 +F0F0 +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 24 24 0 4 +BITMAP +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +F0000F +F0000F +F0000F +F0FF0F +F0FF0F +F0FF0F +F0F00F +F0F00F +F0F00F +F0F00F +F0FF0F +F0FF0F +F0FF0F +F0000F +F0000F +F0000F +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 16 4 18 +BITMAP +0FF0 +0FF0 +0FF0 +F0F0 +F0F0 +F0F0 +0FF0 +0FF0 +0FF0 +0FF0 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +00F0F0 +00F0F0 +00F0F0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +F0F000 +F0F000 +F0F000 +0F0F00 +0F0F00 +0F0F00 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 10 0 8 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +0000F0 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 4 4 14 +BITMAP +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 24 24 0 4 +BITMAP +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +F0000F +F0000F +F0000F +F0FF0F +F0FF0F +F0FF0F +F0F00F +F0F00F +F0F00F +F0F00F +F0F00F +F0F00F +F0F00F +F0000F +F0000F +F0000F +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 3 0 28 +BITMAP +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 16 13 4 21 +BITMAP +0FF0 +0FF0 +0FF0 +F00F +F00F +F00F +F00F +F00F +F00F +F00F +0FF0 +0FF0 +0FF0 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +FFFFF0 +FFFFF0 +FFFFF0 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 16 4 18 +BITMAP +0F00 +0F00 +0F00 +F0F0 +F0F0 +F0F0 +00F0 +00F0 +00F0 +00F0 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 16 4 18 +BITMAP +FF00 +FF00 +FF00 +00F0 +00F0 +00F0 +0F00 +0F00 +0F00 +0F00 +00F0 +00F0 +00F0 +FF00 +FF00 +FF00 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 10 4 21 +BITMAP +00F0 +00F0 +00F0 +0F00 +0F00 +0F00 +0F00 +F000 +F000 +F000 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F00FF0 +F00FF0 +F00FF0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0FFFF0 +0FFFF0 +0FFFF0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +0FF0F0 +0FF0F0 +0FF0F0 +0FF0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 8 7 8 14 +BITMAP +FF +FF +FF +FF +FF +FF +FF +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 6 4 -2 +BITMAP +00F0 +00F0 +00F0 +FF00 +FF00 +FF00 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 16 4 18 +BITMAP +0F00 +0F00 +0F00 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 17 4 21 +BITMAP +0F00 +0F00 +0F00 +0F00 +F0F0 +F0F0 +F0F0 +0F00 +0F00 +0F00 +0000 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +F0F000 +F0F000 +F0F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +00F0F0 +00F0F0 +00F0F0 +0F0F00 +0F0F00 +0F0F00 +F0F000 +F0F000 +F0F000 +F0F000 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +FF0000 +FF0000 +FF0000 +0F00F0 +0F00F0 +0F00F0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0FF000 +0FF000 +0FF000 +0F0F00 +0F0F00 +0F0F00 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +0F0F00 +0F0F00 +0F0F00 +0FFFF0 +0FFFF0 +0FFFF0 +000F00 +000F00 +000F00 +000F00 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +FF0000 +FF0000 +FF0000 +0F00F0 +0F00F0 +0F00F0 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0FF000 +0FF000 +0FF000 +0F0F00 +0F0F00 +0F0F00 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +0000F0 +0000F0 +0000F0 +000F00 +000F00 +000F00 +00FFF0 +00FFF0 +00FFF0 +00FFF0 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +FF0000 +FF0000 +FF0000 +FF0000 +00F000 +00F000 +00F000 +0F00F0 +0F00F0 +0F00F0 +00FF00 +00FF00 +00FF00 +00FF00 +FFF000 +FFF000 +FFF000 +0F0F00 +0F0F00 +0F0F00 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +0F0F00 +0F0F00 +0F0F00 +0FFFF0 +0FFFF0 +0FFFF0 +000F00 +000F00 +000F00 +000F00 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +0F0000 +0F0000 +0F0000 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +000F00 +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +F0F000 +F0F000 +F0F000 +F0F000 +F0F000 +F0F000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F0F000 +F0F000 +F0F000 +F0F000 +F0F000 +F0F000 +F0FFF0 +F0FFF0 +F0FFF0 +F0FFF0 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 -2 +BITMAP +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +000F00 +000F00 +000F00 +0FF000 +0FF000 +0FF000 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +000F00 +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 34 4 4 +BITMAP +F000 +F000 +F000 +F000 +0F00 +0F00 +0F00 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +FFF0 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 34 4 4 +BITMAP +00F0 +00F0 +00F0 +00F0 +0F00 +0F00 +0F00 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +FFF0 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 34 4 4 +BITMAP +0F00 +0F00 +0F00 +0F00 +F0F0 +F0F0 +F0F0 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +FFF0 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 30 4 4 +BITMAP +F0F0 +F0F0 +F0F0 +0000 +0000 +0000 +FFF0 +FFF0 +FFF0 +FFF0 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +0FFF00 +0FFF00 +0FFF00 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +FFF0F0 +FFF0F0 +FFF0F0 +FFF0F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0F00F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FF00F0 +FF00F0 +FF00F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F00FF0 +F00FF0 +F00FF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +000F00 +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 16 0 8 +BITMAP +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 1 +BITMAP +0000F0 +0000F0 +0000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F00FF0 +F00FF0 +F00FF0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +F0F0F0 +FF00F0 +FF00F0 +FF00F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +000F00 +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +00F000 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 34 0 4 +BITMAP +000F00 +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 16 24 4 4 +BITMAP +F000 +F000 +F000 +F000 +FFF0 +FFF0 +FFF0 +F00F +F00F +F00F +F00F +F00F +F00F +F00F +F00F +F00F +F00F +FFF0 +FFF0 +FFF0 +F000 +F000 +F000 +F000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0FFF00 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F00F00 +F00F00 +F00F00 +F0F000 +F0F000 +F0F000 +F0F000 +F00F00 +F00F00 +F00F00 +F000F0 +F000F0 +F000F0 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +0FFF00 +0FFF00 +0FFF00 +0000F0 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +0FFF00 +0FFF00 +0FFF00 +00F0F0 +00F0F0 +00F0F0 +00F0F0 +0FFF00 +0FFF00 +0FFF00 +F0F000 +F0F000 +F0F000 +0FFFF0 +0FFFF0 +0FFFF0 +0FFFF0 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 23 0 -2 +BITMAP +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F00000 +F00000 +F00000 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +000F00 +000F00 +000F00 +0FF000 +0FF000 +0FF000 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 27 4 4 +BITMAP +F000 +F000 +F000 +0F00 +0F00 +0F00 +0F00 +0000 +0000 +0000 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 27 4 4 +BITMAP +00F0 +00F0 +00F0 +0F00 +0F00 +0F00 +0F00 +0000 +0000 +0000 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 27 4 4 +BITMAP +0F00 +0F00 +0F00 +F0F0 +F0F0 +F0F0 +F0F0 +0000 +0000 +0000 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 12 24 4 4 +BITMAP +F0F0 +F0F0 +F0F0 +F0F0 +0000 +0000 +0000 +FF00 +FF00 +FF00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +0F00 +FFF0 +FFF0 +FFF0 +FFF0 +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +0000F0 +0000F0 +0000F0 +0FFFF0 +0FFFF0 +0FFFF0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +F0FF00 +F0FF00 +F0FF00 +FF00F0 +FF00F0 +FF00F0 +FF00F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0FF0F0 +0FF0F0 +0FF0F0 +F0FF00 +F0FF00 +F0FF00 +F0FF00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +0FFF00 +0FFF00 +0FFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 16 0 8 +BITMAP +00F000 +00F000 +00F000 +000000 +000000 +000000 +FFFFF0 +FFFFF0 +FFFFF0 +FFFFF0 +000000 +000000 +000000 +00F000 +00F000 +00F000 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 17 0 4 +BITMAP +0FFFF0 +0FFFF0 +0FFFF0 +F00FF0 +F00FF0 +F00FF0 +F00FF0 +F0F0F0 +F0F0F0 +F0F0F0 +FF00F0 +FF00F0 +FF00F0 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +0F0000 +0F0000 +0F0000 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 27 0 4 +BITMAP +00F000 +00F000 +00F000 +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 24 0 4 +BITMAP +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0FFF00 +0FFF00 +0FFF00 +0FFF00 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 33 0 -2 +BITMAP +000F00 +000F00 +000F00 +00F000 +00F000 +00F000 +00F000 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +00F000 +0F0000 +0F0000 +0F0000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 -2 +BITMAP +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +FFFF00 +FFFF00 +FFFF00 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F00000 +F00000 +F00000 +F00000 +F00000 +F00000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 1728 0 +DWIDTH 24 0 +BBX 20 30 0 -2 +BITMAP +0F0F00 +0F0F00 +0F0F00 +0F0F00 +000000 +000000 +000000 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +F000F0 +0F0F00 +0F0F00 +0F0F00 +00F000 +00F000 +00F000 +00F000 +0F0000 +0F0000 +0F0000 +F00000 +F00000 +F00000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-28x56.bdf b/buildroot/share/fonts/marlin-28x56.bdf new file mode 100644 index 0000000000..1b6a3f5233 --- /dev/null +++ b/buildroot/share/fonts/marlin-28x56.bdf @@ -0,0 +1,7311 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 48 100 100 +FONTBOUNDINGBOX 30 47 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 46 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +FFC03F +FFC01F +FFC01F +FFC01F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F803FF +F803FF +F803FF +FC03FF +7FFFFF +3FFFFF +1FFFFF +0FFFFF +0003E0 +0003E0 +0003E0 +0003E0 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +FFC000 +FFC000 +FFC000 +FFC000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 23 20 0 10 +BITMAP +003C00 +003E00 +003F00 +003F80 +003FC0 +003FE0 +003FF0 +003FF8 +FFFFFC +FFFFFE +FFFFFE +FFFFFC +003FF8 +003FF0 +003FE0 +003FC0 +003F80 +003F00 +003E00 +003C00 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 23 34 0 6 +BITMAP +001000 +003800 +007C00 +00FE00 +01FF00 +03FF80 +07FFC0 +0FFFE0 +1FFFF0 +3FFFF8 +7FFFFC +FFFFFE +FFFFFE +FFFFFE +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 2 +BITMAP +003C00 +003C00 +003C00 +003C00 +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC3C3F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83FFF +F83FFF +F83FFF +F83FFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 2160 0 +DWIDTH 30 0 +BBX 28 20 0 10 +BITMAP +FE1FE000 +FF1FF000 +FF9FF800 +7FCFFC00 +3FE7FE00 +1FF3FF00 +0FF9FF80 +07FCFFC0 +03FE7FE0 +01FF3FF0 +01FF3FF0 +03FE7FE0 +07FCFFC0 +0FF9FF80 +1FF3FF00 +3FE7FE00 +7FCFFC00 +FF9FF800 +FF1FF000 +FE1FE000 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 2 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F83C1F +F83C1F +F83C1F +F83C1F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F83C1F +F83C1F +F83C1F +F83C1F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 -2 +BITMAP +007E00 +00FF00 +01FF80 +03FFC0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +0FC3F0 +1FC3F8 +3FC3FC +7FC3FE +FC003F +F8001F +F8001F +F8001F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 13 12 1 18 +BITMAP +0F80 +1FC0 +3FE0 +7FF0 +F8F8 +F078 +F078 +F8F8 +7FF0 +3FE0 +1FC0 +0F80 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 4 28 10 6 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +00 +00 +00 +00 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 12 5 26 +BITMAP +F87C +F87C +F87C +F87C +F87C +F87C +F87C +F87C +F87C +F87C +F87C +F87C +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 24 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +07C3E0 +07C3E0 +07C3E0 +07C3E0 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 2 +BITMAP +003C00 +003C00 +003C00 +003C00 +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC3C3F +F83C1F +F83C1F +F83C1F +F83C00 +F83C00 +F83C00 +FC3C00 +7FFFF0 +3FFFF8 +1FFFFC +0FFFFE +003C3F +003C1F +003C1F +003C1F +F83C1F +F83C1F +F83C1F +FC3C3F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFC01F +FFC01F +FFC01F +FFC01F +FFC01F +FFC03F +FFC07F +FFC0FF +0003F8 +0007F0 +000FE0 +001FC0 +003F00 +007E00 +00FC00 +01F800 +07F000 +0FE000 +1FC000 +3F8000 +FE03FF +FC03FF +F803FF +F803FF +F803FF +F803FF +F803FF +F803FF +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FC000 +1FE000 +3FF000 +7FF800 +FC7C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +7C7800 +3FF000 +1FE000 +1FF000 +3FF800 +7C7C0F +F83E1F +F81F3F +F80FFE +F807FC +F803F8 +F803F8 +FC07FC +7FFFFE +3FFF3F +1FFE1F +0FFC0F +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 4 12 10 26 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +007C +00FC +01FC +03FC +07C0 +0780 +0F80 +0F00 +1F00 +3E00 +3E00 +7C00 +FC00 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +7C00 +3C00 +3E00 +1F00 +1F00 +0F80 +0FC0 +07E0 +03FC +01FC +00FC +007C +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +F800 +FC00 +FE00 +FF00 +1F80 +0FC0 +07E0 +07E0 +03F0 +03F0 +01F8 +01F8 +00FC +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +00FC +00F8 +01F8 +01F0 +03F0 +03E0 +07E0 +07C0 +0F80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +F83C1F +FC3C3F +7E3C7E +3F3CFC +1FBDF8 +0FFFF0 +07FFE0 +03FFC0 +01FF80 +00FF00 +00FF00 +01FF80 +03FFC0 +07FFE0 +0FFFF0 +1FBDF8 +3F3CFC +7E3C7E +FC3C3F +F83C1F +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 10 +BITMAP +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 9 12 5 2 +BITMAP +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0F80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 4 0 18 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 9 8 5 6 +BITMAP +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +00001F +00003F +00007F +0000FE +0001FC +0003FC +0003F8 +0007F0 +000FE0 +001FE0 +003FC0 +003F80 +007F80 +00FF00 +01FE00 +01FC00 +03FC00 +07F800 +0FF800 +0FF000 +1FE000 +3FC000 +7F8000 +FF0000 +FE0000 +FC0000 +F80000 +F00000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8007F +F800FF +F801FF +F803FF +F807FF +F80FFF +F81FDF +F83F9F +F87F1F +F8FE1F +F9FC1F +FBF81F +FFF01F +FFE01F +FFC01F +FF801F +FF001F +FE001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 28 5 6 +BITMAP +0F80 +1F80 +3F80 +7F80 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +00003F +00007F +0000FE +0001FC +0003F8 +0007F0 +000FE0 +001FC0 +003F80 +007F00 +00FE00 +01FC00 +03F800 +07F000 +0FE000 +1FC000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +00001F +00001F +00003F +00007F +0000FE +0001FC +0003F8 +0007F0 +003FF0 +003FF8 +003FFC +003FFE +00003F +00001F +00001F +00001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 29 0 6 +BITMAP +0007E0 +000FE0 +001FE0 +003FE0 +007FE0 +00FFE0 +01FBE0 +03F3E0 +07E3E0 +0FC3E0 +1F83E0 +3F03E0 +7E03E0 +FC03E0 +F803E0 +F803E0 +F803E0 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +00003F +00001F +00001F +00001F +00001F +00001F +00001F +00001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +00FFE0 +01FFE0 +03FFE0 +07FFE0 +0FE000 +1FC000 +3F8000 +7F0000 +FE0000 +FC0000 +F80000 +F80000 +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +00001F +00001F +00003F +00007E +0000FC +0001F8 +0003F0 +0007E0 +000FC0 +001F80 +003F00 +003E00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC001F +7FFFFF +3FFFFF +1FFFFF +0FFFFF +00001F +00001F +00003F +00007E +0000FC +0001F8 +0003F0 +0007E0 +07FFC0 +07FF80 +07FF00 +07FE00 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 9 20 5 6 +BITMAP +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 9 24 5 2 +BITMAP +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0F80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 21 5 9 +BITMAP +007C +00FC +01F8 +03F0 +07E0 +0FC0 +1F80 +3F00 +7E00 +FC00 +F800 +FC00 +7E00 +3F00 +1F80 +0FC0 +07E0 +03F0 +01F8 +00FC +007C +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 12 0 14 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 10 +BITMAP +FC00 +FE00 +3F00 +1F80 +0FC0 +07E0 +03F0 +01F8 +00FC +007C +007C +00FC +01F8 +03F0 +07E0 +0FC0 +1F80 +3F00 +FE00 +FC00 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8003F +00007E +0000FC +0001F8 +0003F0 +0007E0 +000FC0 +001F80 +003F00 +003E00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +F8003F +F8001F +F8001F +F8001F +F81FFF +F83FFF +F83FFF +F83FFF +F83E1F +F83C1F +F83C1F +F83E3F +F83FFF +F83FFF +F83FFF +F81FFE +F80000 +F80000 +F80000 +FC0000 +7FFFE0 +3FFFE0 +1FFFE0 +0FFFE0 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +07C03F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07FFFE +07FFFC +07FFFC +07FFFE +07C03F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C03F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +07C03F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C03F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F803FF +F803FF +F803FF +F803FF +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 28 5 6 +BITMAP +FFFC +FFFC +FFFC +FFFC +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003FFF +003FFF +003FFF +003FFF +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +F803E0 +F803E0 +F803E0 +FC07E0 +7FFFC0 +3FFF80 +1FFF00 +0FFE00 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8003F +F8007E +F800FC +F801F8 +F803F0 +F807E0 +F80FC0 +F81F80 +F83F00 +F87E00 +F8FC00 +F9F800 +FFF000 +FFE000 +FFE000 +FFF000 +F9F800 +F8FC00 +F87E00 +F83F00 +F81F80 +F80FC0 +F807E0 +F803F0 +F801F8 +F800FC +F8007E +F8003F +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +FC003F +FE007F +FF00FF +FF81FF +FFC3FF +FFE7FF +FFFFFF +F9FF9F +F8FF1F +F87E1F +F83C1F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +FC001F +FE001F +FF001F +FF801F +FFC01F +FFE01F +FBF01F +F9F81F +F8FC1F +F87E1F +F83F1F +F81F9F +F80FDF +F807FF +F803FF +F801FF +F800FF +F8007F +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F83C1F +F83E1F +F83F1F +F83F9F +F81FDF +F80FEF +F807F7 +FC03FB +7FFDFC +3FFEFE +1FFF7F +0FFFBF +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +F8FC00 +F87E00 +F83F00 +F81F80 +F80FC0 +F807E0 +F803F0 +F801F8 +F800FC +F8007E +F8003F +F8001F +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F80000 +F80000 +F80000 +FC0000 +7FFFF0 +3FFFF8 +1FFFFC +0FFFFE +00003F +00001F +00001F +00001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +FE007E +7F00FC +3F81F8 +1FC3F0 +0FE7E0 +07FFC0 +03FF80 +01FF00 +00FE00 +007C00 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F87E3F +7FFFFE +3FFFFC +1FE7F8 +0FC3F0 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 23 28 0 6 +BITMAP +F8003E +F8003E +F8003E +F8003E +FC007E +7E00FC +3F01F8 +1F83F0 +0FC7E0 +07EFC0 +03FF80 +01FF00 +00FE00 +007C00 +007C00 +00FE00 +01FF00 +03FF80 +07EFC0 +0FC7E0 +1F83F0 +3F01F8 +7E00FC +FC007E +F8003E +F8003E +F8003E +F8003E +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7E007E +3F00FC +1F81F8 +0FC3F0 +07FFE0 +03FFC0 +01FF80 +00FF00 +007E00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +00001F +00003F +00007F +0000FE +0001FC +0003F8 +0007F0 +000FE0 +001FC0 +003F80 +007F00 +00FE00 +01FC00 +03F800 +07F000 +0FE000 +1FC000 +3F8000 +7F0000 +FE0000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +FFFC +FFFC +FFFC +FFFC +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F80000 +FC0000 +FE0000 +FF0000 +7F8000 +3F8000 +1FC000 +1FE000 +0FE000 +07F000 +03F800 +03FC00 +01FE00 +00FE00 +007F00 +003F80 +003FC0 +001FC0 +000FE0 +0007F0 +0007F8 +0003F8 +0001FC +0001FE +0000FF +00007F +00003F +00001F +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +FFFC +FFFC +FFFC +FFFC +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +007C +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 12 0 26 +BITMAP +003C00 +00FF00 +01FF80 +03FFC0 +07E7E0 +0FC3F0 +1F81F8 +3F00FC +7E007E +FC003F +F8001F +F0000F +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 4 0 -2 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 12 5 26 +BITMAP +F800 +FC00 +FE00 +FF00 +7FC0 +3FE0 +1FF0 +0FF8 +03FC +01FC +00FC +007C +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +07FFF0 +07FFF8 +07FFFC +07FFFE +00003F +00001F +00001F +00001F +0FFFFF +1FFFFF +3FFFFF +7FFFFF +FC001F +F8001F +F8001F +FC001F +7FFFFF +3FFFFF +1FFFFF +0FFFFF +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +0FFFE0 +1FFFE0 +3FFFE0 +7FFFE0 +FC0000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +00001F +00001F +00001F +00001F +00001F +00001F +00001F +00001F +0FFFFF +1FFFFF +3FFFFF +7FFFFF +FC001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC001F +7FFFFF +3FFFFF +1FFFFF +0FFFFF +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +F80000 +F80000 +F80000 +FC0000 +7FFFE0 +3FFFE0 +1FFFE0 +0FFFE0 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +007FF0 +00FFF8 +01FFFC +03FFFE +07E03F +07C01F +07C01F +07C00F +07C000 +07C000 +07C000 +07C000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +07C000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC001F +7FFFFF +3FFFFF +1FFFFF +0FFFFF +00001F +00001F +00001F +00003F +07FFFE +07FFFC +07FFF8 +07FFF0 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 28 5 6 +BITMAP +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 19 36 5 -2 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +000000 +000000 +000000 +000000 +007FE0 +007FE0 +007FE0 +007FE0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +0003E0 +F803E0 +F803E0 +F803E0 +FC07E0 +7FFFC0 +3FFF80 +1FFF00 +0FFE00 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 23 28 0 6 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F8003E +F8007E +F800FC +F801F8 +F803F0 +F807E0 +F80FC0 +F81F80 +FFFF00 +FFFE00 +FFFE00 +FFFF00 +F81F80 +F80FC0 +F807E0 +F803F0 +F801F8 +F800FC +F8007E +F8003E +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 28 5 6 +BITMAP +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +FFC3F0 +FFE7F8 +FFFFFC +FFFFFE +F87E3F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F87FF0 +F8FFF8 +F9FFFC +FBFFFE +FFE03F +FFC01F +FF801F +FF001F +FE001F +FC001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +0FFFF0 +1FFFF8 +3FFFFC +7FFFFE +FC003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7FFFFE +3FFFFC +1FFFF8 +0FFFF0 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +FFFFF0 +FFFFF8 +FFFFFC +FFFFFE +F8003F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +0FFFFF +1FFFFF +3FFFFF +7FFFFF +FC001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC001F +7FFFFF +3FFFFF +1FFFFF +0FFFFF +00001F +00001F +00001F +00001F +00001F +00001F +00001F +00001F +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F87FF0 +F8FFF8 +F9FFFC +FBFFFE +FFE03F +FFC01F +FF801F +FF000F +FE0000 +FC0000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +0FFFFF +1FFFFF +3FFFFF +7FFFFF +FC0000 +F80000 +F80000 +FC0000 +7FFFF0 +3FFFF8 +1FFFFC +0FFFFE +00003F +00001F +00001F +00003F +FFFFFE +FFFFFC +FFFFF8 +FFFFF0 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003E00 +003FFF +001FFF +000FFF +0007FF +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +F8007F +F800FF +F801FF +F803FF +FC07FF +7FFFDF +3FFF9F +1FFF1F +0FFE1F +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FC003F +7E007E +3F00FC +1F81F8 +0FC3F0 +07E7E0 +03FFC0 +01FF80 +00FF00 +007E00 +003C00 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +FC7E3F +7FFFFE +3FFFFC +1FFFF8 +0FE7F0 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F0000F +F8001F +FC003F +7E007E +3F00FC +1F81F8 +0FC3F0 +07E7E0 +03FFC0 +01FF80 +01FF80 +03FFC0 +07FFE0 +0FE7F0 +1FC3F8 +3F81FC +7F00FE +FE007F +FC003F +F8001F +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8003F +FC007E +FE00FC +7F01F8 +3F83F0 +1FC7E0 +0FFFC0 +07FF80 +03FF00 +01FE00 +00FC00 +01F800 +03F000 +07E000 +0FC000 +1F8000 +FF0000 +FE0000 +FC0000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +0003F8 +0007F0 +000FE0 +001FC0 +003F80 +007F00 +00FE00 +01FC00 +03F800 +07F000 +0FE000 +1FC000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +007C +00FC +01FC +03FC +07C0 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0F80 +1F80 +3F00 +FC00 +F800 +F800 +FC00 +3F00 +1F80 +0F80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +07C0 +03FC +01FC +00FC +007C +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 4 36 10 2 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 2 +BITMAP +F800 +FC00 +FE00 +FF00 +0F80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +07C0 +07E0 +03F0 +00FC +007C +007C +00FC +03F0 +07E0 +07C0 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0F80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 12 0 14 +BITMAP +0FE01F +1FF01F +3FF81F +7FFC1F +FC7C1F +F83C1F +F83C1F +F83E3F +F83FFE +F81FFC +F80FF8 +F807F0 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 1656 0 +DWIDTH 23 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 4 28 10 6 +BITMAP +F0 +F0 +F0 +F0 +00 +00 +00 +00 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 2 +BITMAP +003C00 +003C00 +003C00 +003C00 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F83C1F +F83C1F +F83C1F +F83C1F +F83C00 +F83C00 +F83C00 +F83C00 +F83C1F +F83C1F +F83C1F +F83C1F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003FE0 +003FE0 +003FE0 +003FE0 +07C01F +07C01F +07C01F +07C01F +07C000 +07C000 +07C000 +07C000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +07C000 +07C000 +07C000 +07C000 +07C01F +07C01F +07C01F +07C01F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F83C1F +F83C1F +F83C1F +F83C1F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83C1F +F83C1F +F83C1F +F83C1F +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 4 28 10 6 +BITMAP +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +00 +00 +00 +00 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +F0 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 19 32 5 6 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F80000 +F80000 +F80000 +F80000 +07FC00 +07FC00 +07FC00 +07FC00 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +07FC00 +07FC00 +07FC00 +07FC00 +0003E0 +0003E0 +0003E0 +0003E0 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 4 5 34 +BITMAP +F87C +F87C +F87C +F87C +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 28 28 0 6 +BITMAP +07FFFF00 +07FFFF00 +07FFFF00 +07FFFF00 +F80000F0 +F80000F0 +F80000F0 +F80000F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F80000F0 +F80000F0 +F80000F0 +F80000F0 +07FFFF00 +07FFFF00 +07FFFF00 +07FFFF00 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 22 +BITMAP +07FC +07FC +07FC +07FC +F87C +F87C +F87C +F87C +07FC +07FC +07FC +07FC +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +003C1F +003C1F +003C1F +003C1F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83C00 +F83C00 +F83C00 +F83C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C1F +003C1F +003C1F +003C1F +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 12 0 10 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +00001F +00001F +00001F +00001F +00001F +00001F +00001F +00001F +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 4 5 18 +BITMAP +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 28 28 0 6 +BITMAP +07FFFF00 +07FFFF00 +07FFFF00 +07FFFF00 +F80000F0 +F80000F0 +F80000F0 +F80000F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F83FE0F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F83C00F0 +F80000F0 +F80000F0 +F80000F0 +F80000F0 +07FFFF00 +07FFFF00 +07FFFF00 +07FFFF00 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 4 0 34 +BITMAP +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 19 16 5 26 +BITMAP +07FC00 +07FC00 +07FC00 +07FC00 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +07FC00 +07FC00 +07FC00 +07FC00 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 22 +BITMAP +0780 +0780 +0780 +0780 +F87C +F87C +F87C +F87C +007C +007C +007C +007C +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 22 +BITMAP +FF80 +FF80 +FF80 +FF80 +007C +007C +007C +007C +0780 +0780 +0780 +0780 +007C +007C +007C +007C +FF80 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 12 5 26 +BITMAP +007C +007C +007C +007C +0780 +0780 +0780 +0780 +F800 +F800 +F800 +F800 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F803FF +F803FF +F803FF +F803FF +FFFC1F +FFFC1F +FFFC1F +FFFC1F +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07FFFF +07FFFF +07FFFF +07FFFF +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +07FC1F +07FC1F +07FC1F +07FC1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +003C1F +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 9 8 10 18 +BITMAP +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 8 5 -2 +BITMAP +007C +007C +007C +007C +FF80 +FF80 +FF80 +FF80 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 22 +BITMAP +0780 +0780 +0780 +0780 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 20 5 26 +BITMAP +0780 +0780 +0780 +0780 +F87C +F87C +F87C +F87C +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +F83C00 +F83C00 +F83C00 +F83C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C1F +003C1F +003C1F +003C1F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83C00 +F83C00 +F83C00 +F83C00 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +FFC000 +FFC000 +FFC000 +FFC000 +07C01F +07C01F +07C01F +07C01F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07FC00 +07FC00 +07FC00 +07FC00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83FE0 +F83FE0 +F83FE0 +F83FE0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07FFFF +07FFFF +07FFFF +07FFFF +0003E0 +0003E0 +0003E0 +0003E0 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +FFC000 +FFC000 +FFC000 +FFC000 +07C01F +07C01F +07C01F +07C01F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07FC00 +07FC00 +07FC00 +07FC00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83C1F +F83C1F +F83C1F +F83C1F +00001F +00001F +00001F +00001F +0003E0 +0003E0 +0003E0 +0003E0 +003FFF +003FFF +003FFF +003FFF +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +FFC000 +FFC000 +FFC000 +FFC000 +003C00 +003C00 +003C00 +003C00 +07C01F +07C01F +07C01F +07C01F +003FE0 +003FE0 +003FE0 +003FE0 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F83FE0 +F83FE0 +F83FE0 +F83FE0 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +07FFFF +07FFFF +07FFFF +07FFFF +0003E0 +0003E0 +0003E0 +0003E0 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +07C000 +07C000 +07C000 +07C000 +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07FFFF +07FFFF +07FFFF +07FFFF +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83C00 +F83FFF +F83FFF +F83FFF +F83FFF +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 -2 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +0003E0 +0003E0 +0003E0 +0003E0 +07FC00 +07FC00 +07FC00 +07FC00 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 40 5 6 +BITMAP +F800 +F800 +F800 +F800 +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 40 5 6 +BITMAP +007C +007C +007C +007C +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 40 5 6 +BITMAP +0780 +0780 +0780 +0780 +F87C +F87C +F87C +F87C +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 36 5 6 +BITMAP +F87C +F87C +F87C +F87C +0000 +0000 +0000 +0000 +FFFC +FFFC +FFFC +FFFC +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +FFFC1F +FFFC1F +FFFC1F +FFFC1F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07C01F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFC01F +FFC01F +FFC01F +FFC01F +F83C1F +F83C1F +F83C1F +F83C1F +F803FF +F803FF +F803FF +F803FF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 10 +BITMAP +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 2 +BITMAP +00001F +00001F +00001F +00001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F803FF +F803FF +F803FF +F803FF +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +F83C1F +FFC01F +FFC01F +FFC01F +FFC01F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 19 28 5 6 +BITMAP +F80000 +F80000 +F80000 +F80000 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +F803E0 +FFFC00 +FFFC00 +FFFC00 +FFFC00 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F803E0 +F803E0 +F803E0 +F803E0 +F83C00 +F83C00 +F83C00 +F83C00 +F803E0 +F803E0 +F803E0 +F803E0 +F8001F +F8001F +F8001F +F8001F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +003C1F +003C1F +003C1F +003C1F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F83C00 +F83C00 +F83C00 +F83C00 +07FFFF +07FFFF +07FFFF +07FFFF +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 -2 +BITMAP +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F80000 +F80000 +F80000 +F80000 +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +0003E0 +0003E0 +0003E0 +0003E0 +07FC00 +07FC00 +07FC00 +07FC00 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 32 5 6 +BITMAP +F800 +F800 +F800 +F800 +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 32 5 6 +BITMAP +007C +007C +007C +007C +0780 +0780 +0780 +0780 +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 32 5 6 +BITMAP +0780 +0780 +0780 +0780 +F87C +F87C +F87C +F87C +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 14 28 5 6 +BITMAP +F87C +F87C +F87C +F87C +0000 +0000 +0000 +0000 +FF80 +FF80 +FF80 +FF80 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +0780 +FFFC +FFFC +FFFC +FFFC +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +00001F +00001F +00001F +00001F +07FFFF +07FFFF +07FFFF +07FFFF +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +F83FE0 +F83FE0 +F83FE0 +F83FE0 +FFC01F +FFC01F +FFC01F +FFC01F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07FC1F +07FC1F +07FC1F +07FC1F +F83FE0 +F83FE0 +F83FE0 +F83FE0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +07FFE0 +07FFE0 +07FFE0 +07FFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 10 +BITMAP +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +FFFFFF +FFFFFF +FFFFFF +FFFFFF +000000 +000000 +000000 +000000 +003C00 +003C00 +003C00 +003C00 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 20 0 6 +BITMAP +07FFFF +07FFFF +07FFFF +07FFFF +F803FF +F803FF +F803FF +F803FF +F83C1F +F83C1F +F83C1F +F83C1F +FFC01F +FFC01F +FFC01F +FFC01F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +07C000 +07C000 +07C000 +07C000 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 32 0 6 +BITMAP +003C00 +003C00 +003C00 +003C00 +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 28 0 6 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07FFE0 +07FFE0 +07FFE0 +07FFE0 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 40 0 -2 +BITMAP +0003E0 +0003E0 +0003E0 +0003E0 +003C00 +003C00 +003C00 +003C00 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07C000 +07C000 +07C000 +07C000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 -2 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +FFFFE0 +FFFFE0 +FFFFE0 +FFFFE0 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 2016 0 +DWIDTH 28 0 +BBX 24 36 0 -2 +BITMAP +07C3E0 +07C3E0 +07C3E0 +07C3E0 +000000 +000000 +000000 +000000 +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +F8001F +07C3E0 +07C3E0 +07C3E0 +07C3E0 +003C00 +003C00 +003C00 +003C00 +07C000 +07C000 +07C000 +07C000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-32x64.bdf b/buildroot/share/fonts/marlin-32x64.bdf new file mode 100644 index 0000000000..987f9c974f --- /dev/null +++ b/buildroot/share/fonts/marlin-32x64.bdf @@ -0,0 +1,9870 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 70 100 100 +FONTBOUNDINGBOX 34 69 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 68 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +FFE01FE0 +FFE00FE0 +FFE007E0 +FFE003E0 +FFE003E0 +FFE003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FE00FFE0 +FF00FFE0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 30 37 0 11 +BITMAP +00100000 +00180000 +001C0000 +001E0000 +001F0000 +001F8000 +001FC000 +001FE000 +001FF000 +001FF800 +001FFC00 +001FFE00 +001FFF00 +001FFF80 +001FFFC0 +FFFFFFE0 +FFFFFFF0 +FFFFFFF8 +FFFFFFFC +FFFFFFF8 +FFFFFFF0 +001FFFE0 +001FFFC0 +001FFF80 +001FFF00 +001FFE00 +001FFC00 +001FF800 +001FF000 +001FE000 +001FC000 +001F8000 +001F0000 +001E0000 +001C0000 +00180000 +00100000 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 28 48 0 9 +BITMAP +00060000 +000F0000 +001F8000 +003FC000 +007FE000 +00FFF000 +01FFF800 +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FFFFFFF0 +FFFFFFF0 +FFFFFFF0 +FFFFFFF0 +FFFFFFF0 +FFFFFFF0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 3 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FE1F07E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 2448 0 +DWIDTH 34 0 +BBX 32 29 0 15 +BITMAP +FC07E000 +FE07F000 +FF07F800 +FF87FC00 +FFC7FE00 +7FE3FF00 +3FF1FF80 +1FF8FFC0 +0FFC7FE0 +07FE3FF0 +03FF1FF8 +01FF8FFC +00FFC7FE +007FE3FF +007FE3FF +00FFC7FE +01FF8FFC +03FF1FF8 +07FE3FF0 +0FFC7FE0 +1FF8FFC0 +3FF1FF80 +7FE3FF00 +FFC7FE00 +FF87FC00 +FF07F800 +FE07F000 +FC07E000 +F807C000 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 3 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 58 0 -2 +BITMAP +001F0000 +003F8000 +007FC000 +00FFE000 +01FFF000 +03FFF800 +03F1FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +07E0FC00 +0FE0FE00 +1FE0FF00 +3FE0FF80 +7FE0FFC0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +7FFFFFC0 +3FFFFF80 +1FFFFF00 +0FFFFE00 +07FFFC00 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 17 17 0 27 +BITMAP +03E000 +07F000 +0FF800 +1FFC00 +3FFE00 +7FFF00 +FE3F80 +FC1F80 +FC1F80 +FC1F80 +FE3F80 +7FFF00 +3FFE00 +1FFC00 +0FF800 +07F000 +03E000 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 5 41 11 9 +BITMAP +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +00 +00 +00 +00 +00 +00 +F8 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 18 6 38 +BITMAP +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +F83F +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 35 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 3 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03FFFE00 +07FFFF00 +0FFFFF80 +1FFFFFC0 +3FFFFFE0 +7FFFFFE0 +FE1F07E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FE1F0000 +FFFFFC00 +7FFFFE00 +3FFFFF00 +1FFFFF80 +0FFFFFC0 +07FFFFE0 +001F07E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FE1F07E0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE007E0 +FFE00FE0 +FFE01FE0 +FFE03FC0 +00007F80 +0000FF00 +0001FE00 +0003FC00 +0007F800 +000FF000 +001FE000 +003FC000 +007F8000 +00FF0000 +01FE0000 +03FC0000 +07F80000 +0FF00000 +1FE00000 +3FC00000 +7F800000 +FF00FFE0 +FE00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03E00000 +07F00000 +0FF80000 +1FFC0000 +3FFE0000 +7FFF0000 +FE3F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FE3F0000 +7FFE0000 +3FFC0000 +1FF80000 +1FF00000 +3FF80000 +7FFC0000 +FEFE01E0 +FC7F03E0 +FC3F87E0 +FC1FC7E0 +FC0FFFC0 +FC07FF80 +FC03FF00 +FC01FE00 +FC00FC00 +FC00FC00 +FC00FE00 +FE01FF00 +7FFFFF80 +3FFFFFC0 +1FFFFFE0 +0FFFCFE0 +07FF87E0 +03FF03E0 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 5 18 11 38 +BITMAP +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +003F +007F +00FF +01FE +03FC +07F8 +07F0 +0FE0 +1FC0 +1FC0 +1F80 +1F80 +1F00 +3F00 +3F00 +3F00 +7E00 +7E00 +FE00 +FE00 +FC00 +FC00 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +FC00 +FC00 +FC00 +7E00 +7E00 +3E00 +3F00 +3F00 +1F00 +1F00 +1F80 +1F80 +0FC0 +0FE0 +07F0 +03F8 +01FC +00FE +007F +003F +001F +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +F800 +FC00 +FE00 +FF00 +7F80 +3FC0 +1FC0 +0FE0 +07E0 +07F0 +03F0 +03F8 +01F8 +01F8 +00FC +00FC +007E +007E +007F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +007F +007E +007E +00FC +00FC +01F8 +01F8 +01F8 +03F0 +07F0 +07E0 +07E0 +0FC0 +1FC0 +3F80 +7F00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +F01F01E0 +F81F03E0 +FC1F07E0 +FE1F0FE0 +FF1F1FE0 +7F9F3FC0 +3FDF7F80 +1FFFFF00 +0FFFFE00 +07FFFC00 +03FFF800 +01FFF000 +00FFE000 +007FC000 +007FC000 +007FC000 +00FFE000 +01FFF000 +03FFF800 +07FFFC00 +0FFFFE00 +1FFFFF00 +3FDF7F80 +7F9F3FC0 +FF1F1FE0 +FE1F0FE0 +FC1F07E0 +F81F03E0 +F01F01E0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 15 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 10 18 6 3 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +0FC0 +FFC0 +FF80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 6 0 27 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 10 12 6 9 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +000003E0 +000007E0 +000007E0 +00000FE0 +00000FE0 +00001FE0 +00003FC0 +00003F80 +00007F80 +0000FF00 +0000FF00 +0001FE00 +0001FC00 +0003FC00 +0007F800 +0007F800 +000FF000 +000FF000 +001FE000 +003FC000 +003FC000 +007F8000 +00FF8000 +00FF0000 +01FE0000 +01FE0000 +03FC0000 +07FC0000 +07F80000 +0FF00000 +1FF00000 +1FE00000 +3FE00000 +3FC00000 +7FC00000 +FF800000 +FF000000 +FF000000 +FE000000 +FE000000 +FC000000 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FE0007E0 +FC0007E0 +FC000FE0 +FC001FE0 +FC003FE0 +FC007FE0 +FC00FFE0 +FC01FFE0 +FC03FFE0 +FC07FFE0 +FC0FFFE0 +FC1FFFE0 +FC3FFBE0 +FC7FF3E0 +FCFFE3E0 +FDFFC3E0 +FFFF83E0 +FFFF03E0 +FFFE03E0 +FFFC03E0 +FFF803E0 +FFF003E0 +FFE003E0 +FFC003E0 +FF8003E0 +FF0003E0 +FE0003E0 +FC0003E0 +FE0007E0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 41 6 9 +BITMAP +07C0 +07C0 +0FC0 +1FC0 +3FC0 +7FC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +000003E0 +000003E0 +000003E0 +000007E0 +00000FE0 +00001FE0 +00003FC0 +00007F80 +0000FF00 +0001FE00 +0003FC00 +0007F800 +000FF000 +001FE000 +003FC000 +007F8000 +00FF0000 +01FE0000 +03FC0000 +07F80000 +0FF00000 +1FE00000 +3FC00000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000007E0 +00000FE0 +00001FC0 +00003F80 +00007F00 +0000FE00 +0001FC00 +000FFC00 +001FFE00 +001FFF00 +001FFF80 +001FFFC0 +000007E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +0000FC00 +0000FC00 +0001FC00 +0003FC00 +0007FC00 +000FFC00 +001FFC00 +003FFC00 +007FFC00 +00FFFC00 +01FEFC00 +03FCFC00 +07F8FC00 +0FF0FC00 +1FE0FC00 +3FC0FC00 +7F80FC00 +FF00FC00 +FE00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +00000FE0 +000007E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001FFC00 +003FFC00 +007FFC00 +00FFFC00 +01FFFC00 +03FFFC00 +07F80000 +0FF00000 +1FE00000 +3FC00000 +7F800000 +FF000000 +FE000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000007E0 +00000FC0 +00001F80 +00003F00 +00007E00 +0000FC00 +0001F800 +0003F000 +0007E000 +000FC000 +001F8000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFC0 +3FFFFF80 +1FFFFF00 +1FFFFF00 +3FFFFF80 +7FFFFFC0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000007E0 +00000FE0 +00001FE0 +00003FC0 +00007F80 +0000FF00 +0001FE00 +0003FC00 +03FFF800 +03FFF000 +03FFE000 +03FFC000 +03FF8000 +03FF0000 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 10 29 6 9 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 10 35 6 3 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +0FC0 +1FC0 +FFC0 +FF80 +FF00 +FE00 +FC00 +F800 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 18 28 4 16 +BITMAP +0007C0 +000FC0 +001FC0 +003F80 +007F00 +00FE00 +01FC00 +03F800 +07F000 +0FE000 +1FC000 +3F8000 +7F0000 +FE0000 +FE0000 +7F0000 +3F8000 +1FC000 +0FE000 +07F000 +03F800 +01FC00 +00FE00 +007F00 +003F80 +001FC0 +000FC0 +0007C0 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 17 0 21 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 18 29 6 15 +BITMAP +F80000 +FC0000 +FE0000 +FF0000 +7F8000 +3FC000 +1FE000 +0FF000 +07F800 +03FC00 +01FE00 +00FF00 +007F80 +003FC0 +003FC0 +007F80 +00FF00 +01FE00 +03FC00 +07F800 +0FF000 +1FE000 +3FC000 +7F8000 +FF0000 +FE0000 +FC0000 +F80000 +F00000 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +00001FC0 +00003F80 +00007F00 +0000FE00 +0001FC00 +0003F800 +0007F000 +000FE000 +001FC000 +001F8000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1F83E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F83E0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC0FFFC0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FE000000 +7FFFFC00 +3FFFFC00 +1FFFFC00 +0FFFFC00 +07FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +03E00FE0 +03E007E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E007E0 +03E00FE0 +03FFFFE0 +03FFFFC0 +03FFFF80 +03FFFF00 +03FFFF80 +03FFFFC0 +03E00FE0 +03E007E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E007E0 +03E00FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +03E00FE0 +03E007E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E007E0 +03E00FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 41 6 9 +BITMAP +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FE01FC00 +FF03FC00 +7FFFF800 +3FFFF000 +1FFFE000 +0FFFC000 +07FF8000 +03FF0000 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0001E0 +FC0003E0 +FC0007E0 +FC000FE0 +FC001FC0 +FC003F80 +FC007F00 +FC00FE00 +FC01FC00 +FC03F800 +FC07F000 +FC0FE000 +FC1FC000 +FC3F8000 +FC7F0000 +FCFE0000 +FDFC0000 +FFF80000 +FFF00000 +FFE00000 +FFE00000 +FFF00000 +FFF80000 +FDFC0000 +FCFE0000 +FC7F0000 +FC3F8000 +FC1FC000 +FC0FE000 +FC07F000 +FC03F800 +FC01FC00 +FC00FE00 +FC007F00 +FC003F80 +FC001FC0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0001E0 +FC0000E0 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +FF801FE0 +FFC03FE0 +FFE07FE0 +FFF0FFE0 +FFF9FFE0 +FFFFFFE0 +FDFFFBE0 +FCFFF3E0 +FC7FE3E0 +FC3FC3E0 +FC1F83E0 +FC0F03E0 +FC0603E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +FF8003E0 +FFC003E0 +FFE003E0 +FFF003E0 +FFF803E0 +FFFC03E0 +FFFE03E0 +FDFF03E0 +FCFF83E0 +FC7FC3E0 +FC3FE3E0 +FC1FF3E0 +FC0FFBE0 +FC07FFE0 +FC03FFE0 +FC01FFE0 +FC00FFE0 +FC007FE0 +FC003FE0 +FC001FE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC1E03E0 +FC1F03E0 +FC1F83E0 +FC1FC3E0 +FC1FE3E0 +FC1FF3E0 +FC0FFBE0 +FC07FDE0 +FC03FEE0 +FC01FF60 +FC00FF80 +FC007FC0 +7FFFBFE0 +3FFFDFE0 +1FFFEFE0 +0FFFF7E0 +07FFFBE0 +03FFF9E0 +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FFFFFFE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +FFFE0000 +FDFF0000 +FCFF8000 +FC7FC000 +FC3FE000 +FC1FF000 +FC0FF800 +FC07FC00 +FC03FE00 +FC01FF00 +FC00FF80 +FC007FC0 +FC003FE0 +FC001FE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0001E0 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC000000 +FC000000 +FC000000 +FE000000 +FF000000 +7FFFFC00 +3FFFFE00 +1FFFFF00 +0FFFFF80 +07FFFFC0 +03FFFFE0 +00000FE0 +000007E0 +000003E0 +000003E0 +000003E0 +000003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FE0007E0 +FE000FE0 +7E000FC0 +7F001FC0 +3F001F80 +3F803F80 +1F803F00 +1FC07F00 +0FC07E00 +07E0FE00 +07F1FC00 +03F1F800 +03FFF800 +01FFF000 +01FFF000 +00FFE000 +00FFE000 +007FC000 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FE3F87E0 +FF7FCFE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFBFF00 +07F1FE00 +03E0FC00 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FE000FE0 +FF001FE0 +FF803FE0 +7FC07FE0 +3FE0FFC0 +1FF1FF80 +0FFBFF00 +07FFFE00 +03FFFC00 +01FFF800 +00FFF000 +007FE000 +007FE000 +00FFF000 +01FFF800 +03FFFC00 +07FFFE00 +0FFFFF00 +1FFBFF80 +3FF1FFC0 +7FE0FFE0 +FFC07FE0 +FF803FE0 +FF001FE0 +FE000FE0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FE000FE0 +FF001FE0 +7F803FC0 +3FC07F80 +1FE0FF00 +0FF1FE00 +07FBFC00 +03FFF800 +01FFF000 +00FFE000 +007FC000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +003F8000 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +000003E0 +000003E0 +000007E0 +00000FE0 +00001FE0 +00003FE0 +00007FE0 +0000FFC0 +0001FF80 +0003FF00 +0007FE00 +000FFC00 +001FF800 +003FF000 +007FE000 +00FFC000 +01FF8000 +03FF0000 +07FE0000 +0FFC0000 +1FF80000 +3FF00000 +7FE00000 +FFC00000 +FF800000 +FF000000 +FE000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +F800 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC000000 +FE000000 +FE000000 +FF000000 +FF000000 +FF800000 +7FC00000 +3FC00000 +3FE00000 +1FE00000 +0FF00000 +0FF00000 +07F80000 +07FC0000 +03FC0000 +01FE0000 +01FE0000 +00FF0000 +007F8000 +007F8000 +003FC000 +003FC000 +001FE000 +000FF000 +000FF000 +0007F800 +0003F800 +0003FC00 +0001FC00 +0001FE00 +0000FF00 +0000FF00 +00007F80 +00003F80 +00003FC0 +00001FE0 +00000FE0 +00000FE0 +000007E0 +000007E0 +000003E0 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +003F +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 28 19 0 38 +BITMAP +00040000 +000E0000 +001F0000 +003F8000 +007FC000 +00FFE000 +01FFF000 +03FBF800 +07F1FC00 +0FE0FE00 +1FC07F00 +3F803F80 +7F001FC0 +FE000FE0 +FC0007F0 +F80003F0 +F00001F0 +E00000F0 +C0000070 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 5 0 -2 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 18 6 38 +BITMAP +F000 +F800 +FC00 +FE00 +FF00 +FF80 +FFC0 +7FE0 +3FF0 +1FF8 +0FFC +07FE +03FF +01FF +00FF +007F +003F +001F +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +03FFFC00 +03FFFE00 +03FFFF00 +03FFFF80 +03FFFFC0 +00000FE0 +000007E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +07FFFFE0 +0FFFFFE0 +1FFFFFE0 +3FFFFFE0 +7FFFFFE0 +FF0003E0 +FE0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +07FFFC00 +0FFFFC00 +1FFFFC00 +3FFFFC00 +7FFFFC00 +FF000000 +FE000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +07FFFFE0 +0FFFFFE0 +1FFFFFE0 +3FFFFFE0 +7FFFFFE0 +FF0003E0 +FE0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +07FFFC00 +0FFFFE00 +1FFFFF00 +3FFFFF80 +7FFFFFC0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FE000000 +FF000000 +7FFFFC00 +3FFFFC00 +1FFFFC00 +0FFFFC00 +07FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001FFC00 +003FFE00 +007FFF00 +00FFFF80 +01FFFFC0 +03FFFFE0 +03F80FE0 +03F007E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +07FFFE00 +0FFFFF00 +1FFFFF80 +3FFFFFC0 +7FFFFFE0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000007E0 +00000FE0 +03FFFFC0 +03FFFF80 +03FFFF00 +03FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 41 6 9 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 21 52 6 -2 +BITMAP +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +000000 +000000 +000000 +000000 +000000 +000000 +003FF8 +003FF8 +003FF8 +003FF8 +003FF8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +F800F8 +F800F8 +F800F8 +F800F8 +FC01F8 +FE03F8 +7FFFF0 +3FFFE0 +1FFFC0 +0FFF80 +07FF00 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC0003E0 +FC0007E0 +FC000FE0 +FC001FC0 +FC003F80 +FC007F00 +FC00FE00 +FC01FC00 +FC03F800 +FC07F000 +FC0FE000 +FFFFC000 +FFFF8000 +FFFF0000 +FFFF8000 +FFFFC000 +FFFFE000 +FC0FF000 +FC07F800 +FC03FC00 +FC01FE00 +FC00FF00 +FC007F80 +FC003FC0 +FC001FE0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0001E0 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 41 6 9 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FFE0FC00 +FFF1FE00 +FFFBFF00 +FFFFFF80 +FFFFFFC0 +FC7FCFE0 +FC3F87E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC1FFC00 +FC3FFE00 +FC7FFF00 +FCFFFF80 +FDFFFFC0 +FFFC0FE0 +FFF807E0 +FFF003E0 +FFE003E0 +FFC003E0 +FF8003E0 +FF0003E0 +FE0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +07FFFC00 +0FFFFE00 +1FFFFF00 +3FFFFF80 +7FFFFFC0 +FF000FE0 +FE0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFFFF00 +07FFFE00 +03FFFC00 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +FFFFFC00 +FFFFFE00 +FFFFFF00 +FFFFFF80 +FFFFFFC0 +FC000FE0 +FC0007E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +07FFFFE0 +0FFFFFE0 +1FFFFFE0 +3FFFFFE0 +7FFFFFE0 +FF0003E0 +FE0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0003E0 +FF0003E0 +7FFFFFE0 +3FFFFFE0 +1FFFFFE0 +0FFFFFE0 +07FFFFE0 +03FFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC1FFC00 +FC3FFE00 +FC7FFF00 +FCFFFF80 +FDFFFFC0 +FFFC0FE0 +FFF807E0 +FFF003E0 +FFE003E0 +FFC003E0 +FF8003E0 +FF000000 +FE000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +07FFFFE0 +0FFFFFE0 +1FFFFFE0 +3FFFFFE0 +7FFFFFE0 +FF000000 +FE000000 +FC000000 +FC000000 +FE000000 +FF000000 +7FFFFC00 +3FFFFE00 +1FFFFF00 +0FFFFF80 +07FFFFC0 +03FFFFE0 +00000FE0 +000007E0 +000003E0 +000003E0 +000007E0 +00000FE0 +FFFFFFE0 +FFFFFFC0 +FFFFFF80 +FFFFFF00 +FFFFFE00 +FFFFFC00 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F8000 +001FC000 +001FFFE0 +000FFFE0 +0007FFE0 +0003FFE0 +0001FFE0 +0000FFE0 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0007E0 +FC000FE0 +FC001FE0 +FC003FE0 +FC007FE0 +FC00FFE0 +FE01FFE0 +FF03FFE0 +7FFFFBE0 +3FFFF3E0 +1FFFE3E0 +0FFFC3E0 +07FF83E0 +03FF03E0 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FE000FE0 +7F001FC0 +3F803F80 +1FC07F00 +0FE0FE00 +07F1FC00 +03FFF800 +01FFF000 +00FFE000 +007FC000 +003F8000 +001F0000 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC0007E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FC1F07E0 +FE3F8FE0 +FF7FDFE0 +7FFFFFE0 +3FFFFFC0 +1FFFFF80 +0FFBFF00 +07F1FE00 +03E0FC00 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +F00003E0 +F80007E0 +FC000FE0 +FE001FE0 +FF003FC0 +7F807F80 +3FC0FF00 +1FE1FE00 +0FF3FC00 +07FFF800 +03FFF000 +01FFE000 +00FFC000 +007F8000 +007F8000 +00FFC000 +01FFE000 +03FFF000 +07FFF800 +0FF3FC00 +1FE1FE00 +3FC0FF00 +7F807F80 +FF003FC0 +FE001FE0 +FC000FE0 +F80007E0 +F00003E0 +E00001E0 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FE0007E0 +FF000FE0 +7F801FE0 +3FC03FC0 +1FE07F80 +0FF0FF00 +07F9FE00 +03FFFC00 +01FFF800 +00FFF000 +007FE000 +003FC000 +003F8000 +007F0000 +00FE0000 +01FC0000 +03F80000 +07F00000 +0FE00000 +1FC00000 +3F800000 +7F000000 +FE000000 +FC000000 +F8000000 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +00007FC0 +0000FF80 +0001FF00 +0003FE00 +0007FC00 +000FF800 +001FF000 +003FE000 +007FC000 +00FF8000 +01FF0000 +03FE0000 +07FC0000 +0FF80000 +1FF00000 +3FE00000 +7FC00000 +FF800000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +001F +003F +007F +00FF +01FF +03FE +07F0 +07E0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0FC0 +1FC0 +3FC0 +7FC0 +FE00 +FC00 +F800 +F800 +FC00 +FE00 +7FC0 +3FC0 +1FC0 +0FC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07E0 +07F0 +03FE +01FF +00FF +007F +003F +001F +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 5 53 11 3 +BITMAP +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 3 +BITMAP +F000 +F800 +FC00 +FE00 +FF00 +7F80 +1FC0 +0FC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07E0 +07F0 +07F8 +07FC +07FE +00FF +007F +003F +003F +007F +00FF +07FE +07FC +07F8 +07F0 +07E0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0FC0 +1FC0 +7F80 +FF00 +FE00 +FC00 +F800 +F000 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 17 0 21 +BITMAP +07E003E0 +0FF003E0 +1FF803E0 +3FFC03E0 +7FFE03E0 +FFFF03E0 +FE7F83E0 +FC3FC3E0 +FC1FE3E0 +FC0FF7E0 +FC07FFE0 +FC03FFE0 +FC01FFC0 +FC00FF80 +FC007F00 +FC003E00 +FC001C00 +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 1944 0 +DWIDTH 27 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 5 41 11 9 +BITMAP +F8 +F8 +F8 +F8 +F8 +F8 +00 +00 +00 +00 +00 +00 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 3 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001FFC00 +001FFC00 +001FFC00 +001FFC00 +001FFC00 +001FFC00 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 5 41 11 9 +BITMAP +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +00 +00 +00 +00 +00 +00 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +F8 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 21 47 6 9 +BITMAP +07FFF8 +07FFF8 +07FFF8 +07FFF8 +07FFF8 +07FFF8 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +0000F8 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 6 6 50 +BITMAP +F83F +F83F +F83F +F83F +F83F +F83F +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 32 41 0 9 +BITMAP +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 29 6 33 +BITMAP +07FF +07FF +07FF +07FF +07FF +07FF +F83F +F83F +F83F +F83F +F83F +F83F +07FF +07FF +07FF +07FF +07FF +07FF +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 18 0 15 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 6 6 27 +BITMAP +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 32 41 0 9 +BITMAP +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1FFC1F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC1F001F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +FC00001F +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 6 0 50 +BITMAP +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 21 24 6 38 +BITMAP +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +07FF00 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 29 6 33 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +F83F +F83F +F83F +F83F +F83F +F83F +003F +003F +003F +003F +003F +003F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 29 6 33 +BITMAP +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +003F +003F +003F +003F +003F +003F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +003F +003F +003F +003F +003F +003F +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 18 6 38 +BITMAP +003F +003F +003F +003F +003F +003F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +F800 +F800 +F800 +F800 +F800 +F800 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 11 11 11 27 +BITMAP +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +FFE0 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 11 6 -2 +BITMAP +003F +003F +003F +003F +003F +003F +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 29 6 33 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 30 6 38 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +F83F +F83F +F83F +F83F +F83F +F83F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +001FFFE0 +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +FFE00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +001FFC00 +001FFC00 +001FFC00 +001FFC00 +001FFC00 +001FFC00 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +FFFF0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +FC1FFFE0 +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 52 0 -2 +BITMAP +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 59 6 9 +BITMAP +F800 +F800 +F800 +F800 +F800 +F800 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 59 6 9 +BITMAP +003F +003F +003F +003F +003F +003F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 59 6 9 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +F83F +F83F +F83F +F83F +F83F +F83F +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 53 6 9 +BITMAP +F83F +F83F +F83F +F83F +F83F +F83F +0000 +0000 +0000 +0000 +0000 +0000 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +FFFF03E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03E003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 15 +BITMAP +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 3 +BITMAP +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 59 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 21 41 6 9 +BITMAP +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +F800F8 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +FFFF00 +F80000 +F80000 +F80000 +F80000 +F80000 +F80000 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC00FC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +001F03E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +FC1F0000 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 40 0 -2 +BITMAP +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +03FF0000 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 47 6 9 +BITMAP +F800 +F800 +F800 +F800 +F800 +F800 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 47 6 9 +BITMAP +003F +003F +003F +003F +003F +003F +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 47 6 9 +BITMAP +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +F83F +F83F +F83F +F83F +F83F +F83F +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 16 41 6 9 +BITMAP +F83F +F83F +F83F +F83F +F83F +F83F +0000 +0000 +0000 +0000 +0000 +0000 +FFC0 +FFC0 +FFC0 +FFC0 +FFC0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +07C0 +FFFF +FFFF +FFFF +FFFF +FFFF +FFFF +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 53 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +000003E0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +03FF03E0 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +FC1FFC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 15 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +FFFFFFE0 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 29 0 9 +BITMAP +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +03FFFFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC00FFE0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FC1F03E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFE003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 47 0 9 +BITMAP +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 41 0 9 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +03FFFC00 +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 58 0 -2 +BITMAP +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +0000FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 52 0 -2 +BITMAP +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FFFFFC00 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 2304 0 +DWIDTH 32 0 +BBX 27 52 0 -2 +BITMAP +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +FC0003E0 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +03E0FC00 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +001F0000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +03E00000 +FC000000 +FC000000 +FC000000 +FC000000 +FC000000 +ENDCHAR +ENDFONT diff --git a/buildroot/share/fonts/marlin-8x16.bdf b/buildroot/share/fonts/marlin-8x16.bdf new file mode 100644 index 0000000000..92e73951b5 --- /dev/null +++ b/buildroot/share/fonts/marlin-8x16.bdf @@ -0,0 +1,3701 @@ +STARTFONT 2.1 +COMMENT Exported by Fony v1.4.6 +FONT Fixed +SIZE 16 100 100 +FONTBOUNDINGBOX 10 15 0 -2 +STARTPROPERTIES 6 +COPYRIGHT "Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1" +RESOLUTION_X 100 +RESOLUTION_Y 100 +FONT_ASCENT 14 +FONT_DESCENT 2 +DEFAULT_CHAR 0 +ENDPROPERTIES +CHARS 256 +STARTCHAR 000 +ENCODING 0 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 001 +ENCODING 1 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 6 10 1 1 +BITMAP +40 +78 +E4 +C4 +84 +84 +84 +9C +78 +08 +ENDCHAR +STARTCHAR 002 +ENCODING 2 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +C0 +FE +FE +C2 +C2 +C2 +C2 +C2 +C2 +FE +FE +ENDCHAR +STARTCHAR 003 +ENCODING 3 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 8 0 1 +BITMAP +10 +18 +1C +FE +FE +1C +18 +10 +ENDCHAR +STARTCHAR 004 +ENCODING 4 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +38 +7C +FE +10 +10 +10 +10 +10 +F0 +F0 +ENDCHAR +STARTCHAR 005 +ENCODING 5 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 6 11 1 -1 +BITMAP +20 +78 +A4 +A4 +A4 +BC +84 +84 +84 +78 +20 +ENDCHAR +STARTCHAR 006 +ENCODING 6 +SWIDTH 720 0 +DWIDTH 10 0 +BBX 9 6 0 2 +BITMAP +EE00 +7700 +1980 +1980 +7700 +EE00 +ENDCHAR +STARTCHAR 007 +ENCODING 7 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -1 +BITMAP +FE +92 +92 +82 +82 +82 +82 +82 +82 +92 +92 +FE +ENDCHAR +STARTCHAR 008 +ENCODING 8 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 13 1 -2 +BITMAP +20 +50 +50 +50 +50 +50 +50 +88 +A8 +A8 +A8 +88 +70 +ENDCHAR +STARTCHAR 009 +ENCODING 9 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 3 3 1 5 +BITMAP +40 +A0 +40 +ENDCHAR +STARTCHAR 010 +ENCODING 10 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 011 +ENCODING 11 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 012 +ENCODING 12 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 013 +ENCODING 13 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 014 +ENCODING 14 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 015 +ENCODING 15 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 016 +ENCODING 16 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 017 +ENCODING 17 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 018 +ENCODING 18 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 019 +ENCODING 19 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 020 +ENCODING 20 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 021 +ENCODING 21 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 022 +ENCODING 22 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 023 +ENCODING 23 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 024 +ENCODING 24 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 025 +ENCODING 25 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 026 +ENCODING 26 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 027 +ENCODING 27 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 028 +ENCODING 28 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 029 +ENCODING 29 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 030 +ENCODING 30 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 031 +ENCODING 31 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 032 +ENCODING 32 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 033 +ENCODING 33 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 1 10 3 0 +BITMAP +80 +80 +80 +80 +80 +80 +80 +00 +80 +80 +ENDCHAR +STARTCHAR 034 +ENCODING 34 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 3 4 2 7 +BITMAP +A0 +A0 +A0 +A0 +ENDCHAR +STARTCHAR 035 +ENCODING 35 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 0 +BITMAP +28 +28 +FE +28 +28 +28 +FE +28 +28 +ENDCHAR +STARTCHAR 036 +ENCODING 36 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -1 +BITMAP +10 +3C +52 +92 +90 +70 +1C +12 +92 +54 +3C +10 +ENDCHAR +STARTCHAR 037 +ENCODING 37 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 6 10 1 0 +BITMAP +C4 +C4 +04 +08 +10 +20 +40 +80 +8C +8C +ENDCHAR +STARTCHAR 038 +ENCODING 38 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +20 +60 +90 +90 +60 +60 +92 +8C +52 +32 +ENDCHAR +STARTCHAR 039 +ENCODING 39 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 1 4 3 7 +BITMAP +80 +80 +80 +80 +ENDCHAR +STARTCHAR 040 +ENCODING 40 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 12 2 -1 +BITMAP +30 +40 +40 +40 +80 +80 +80 +80 +40 +40 +40 +30 +ENDCHAR +STARTCHAR 041 +ENCODING 41 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 3 12 2 -1 +BITMAP +80 +40 +40 +40 +20 +20 +20 +20 +40 +40 +40 +80 +ENDCHAR +STARTCHAR 042 +ENCODING 42 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +10 +10 +D6 +38 +10 +10 +38 +D6 +10 +10 +ENDCHAR +STARTCHAR 043 +ENCODING 43 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 2 +BITMAP +10 +10 +10 +FE +10 +10 +10 +ENDCHAR +STARTCHAR 044 +ENCODING 44 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 2 4 2 -1 +BITMAP +C0 +40 +40 +80 +ENDCHAR +STARTCHAR 045 +ENCODING 45 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 2 0 4 +BITMAP +FE +FE +ENDCHAR +STARTCHAR 046 +ENCODING 46 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 2 2 2 0 +BITMAP +C0 +C0 +ENDCHAR +STARTCHAR 047 +ENCODING 47 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 6 10 1 0 +BITMAP +04 +04 +08 +10 +10 +20 +40 +40 +80 +80 +ENDCHAR +STARTCHAR 048 +ENCODING 48 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 6 10 1 0 +BITMAP +30 +48 +84 +8C +94 +A4 +C4 +84 +48 +30 +ENDCHAR +STARTCHAR 049 +ENCODING 49 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 10 1 0 +BITMAP +20 +60 +E0 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 050 +ENCODING 50 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +02 +04 +08 +10 +20 +40 +FE +ENDCHAR +STARTCHAR 051 +ENCODING 51 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +02 +02 +04 +08 +1C +02 +82 +44 +38 +ENDCHAR +STARTCHAR 052 +ENCODING 52 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +04 +0C +14 +24 +44 +84 +FE +04 +04 +04 +ENDCHAR +STARTCHAR 053 +ENCODING 53 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +80 +80 +FC +02 +02 +02 +82 +44 +38 +ENDCHAR +STARTCHAR 054 +ENCODING 54 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +1C +20 +40 +80 +F8 +84 +82 +82 +44 +38 +ENDCHAR +STARTCHAR 055 +ENCODING 55 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +02 +02 +04 +0C +08 +10 +10 +10 +10 +ENDCHAR +STARTCHAR 056 +ENCODING 56 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +82 +44 +38 +44 +82 +44 +38 +ENDCHAR +STARTCHAR 057 +ENCODING 57 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +82 +42 +3E +02 +04 +08 +30 +ENDCHAR +STARTCHAR 058 +ENCODING 58 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 2 5 2 1 +BITMAP +C0 +C0 +00 +C0 +C0 +ENDCHAR +STARTCHAR 059 +ENCODING 59 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 2 7 2 -1 +BITMAP +C0 +C0 +00 +C0 +40 +40 +80 +ENDCHAR +STARTCHAR 060 +ENCODING 60 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 7 2 1 +BITMAP +10 +20 +40 +80 +40 +20 +10 +ENDCHAR +STARTCHAR 061 +ENCODING 61 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 4 0 3 +BITMAP +FE +00 +00 +FE +ENDCHAR +STARTCHAR 062 +ENCODING 62 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 7 2 1 +BITMAP +80 +40 +20 +10 +20 +40 +80 +ENDCHAR +STARTCHAR 063 +ENCODING 63 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +04 +08 +10 +10 +00 +10 +10 +ENDCHAR +STARTCHAR 064 +ENCODING 64 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +9E +92 +92 +9E +80 +40 +3C +ENDCHAR +STARTCHAR 065 +ENCODING 65 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +7C +82 +82 +82 +82 +FE +82 +82 +82 +82 +ENDCHAR +STARTCHAR 066 +ENCODING 66 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +F8 +44 +42 +42 +7C +42 +42 +42 +44 +FC +ENDCHAR +STARTCHAR 067 +ENCODING 67 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +18 +24 +42 +80 +80 +80 +80 +42 +24 +18 +ENDCHAR +STARTCHAR 068 +ENCODING 68 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +F8 +44 +42 +42 +42 +42 +42 +42 +44 +F8 +ENDCHAR +STARTCHAR 069 +ENCODING 69 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +80 +80 +80 +FC +80 +80 +80 +80 +FE +ENDCHAR +STARTCHAR 070 +ENCODING 70 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +80 +80 +80 +FC +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 071 +ENCODING 71 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +80 +80 +80 +8E +42 +24 +18 +ENDCHAR +STARTCHAR 072 +ENCODING 72 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +82 +82 +FE +82 +82 +82 +82 +82 +ENDCHAR +STARTCHAR 073 +ENCODING 73 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 10 1 0 +BITMAP +F8 +20 +20 +20 +20 +20 +20 +20 +20 +F8 +ENDCHAR +STARTCHAR 074 +ENCODING 74 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 0 +BITMAP +3E +08 +08 +08 +08 +08 +88 +48 +30 +ENDCHAR +STARTCHAR 075 +ENCODING 75 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +84 +88 +90 +E0 +E0 +90 +88 +84 +82 +ENDCHAR +STARTCHAR 076 +ENCODING 76 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +80 +80 +80 +80 +80 +80 +80 +80 +80 +FE +ENDCHAR +STARTCHAR 077 +ENCODING 77 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +C6 +AA +92 +82 +82 +82 +82 +82 +82 +ENDCHAR +STARTCHAR 078 +ENCODING 78 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +C2 +A2 +92 +8A +86 +82 +82 +82 +ENDCHAR +STARTCHAR 079 +ENCODING 79 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +82 +82 +82 +82 +82 +44 +38 +ENDCHAR +STARTCHAR 080 +ENCODING 80 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +F8 +84 +82 +82 +84 +F8 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 081 +ENCODING 81 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +38 +44 +82 +82 +82 +82 +82 +8C +46 +3A +ENDCHAR +STARTCHAR 082 +ENCODING 82 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +F8 +84 +82 +82 +84 +F8 +90 +88 +84 +82 +ENDCHAR +STARTCHAR 083 +ENCODING 83 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +18 +24 +42 +80 +40 +3C +02 +82 +44 +38 +ENDCHAR +STARTCHAR 084 +ENCODING 84 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +10 +10 +10 +10 +10 +10 +10 +10 +10 +ENDCHAR +STARTCHAR 085 +ENCODING 85 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +82 +82 +82 +82 +82 +82 +44 +38 +ENDCHAR +STARTCHAR 086 +ENCODING 86 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +82 +82 +82 +82 +44 +44 +28 +10 +ENDCHAR +STARTCHAR 087 +ENCODING 87 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +82 +82 +82 +82 +92 +92 +54 +28 +ENDCHAR +STARTCHAR 088 +ENCODING 88 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +44 +28 +10 +10 +28 +44 +82 +82 +ENDCHAR +STARTCHAR 089 +ENCODING 89 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +82 +82 +44 +28 +10 +10 +10 +10 +10 +10 +ENDCHAR +STARTCHAR 090 +ENCODING 90 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +FE +02 +02 +04 +08 +10 +20 +40 +80 +FE +ENDCHAR +STARTCHAR 091 +ENCODING 91 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 12 2 -1 +BITMAP +F0 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +F0 +ENDCHAR +STARTCHAR 092 +ENCODING 92 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +80 +80 +40 +20 +10 +10 +08 +08 +04 +02 +ENDCHAR +STARTCHAR 093 +ENCODING 93 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 12 2 -1 +BITMAP +F0 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +F0 +ENDCHAR +STARTCHAR 094 +ENCODING 94 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 4 0 7 +BITMAP +10 +28 +44 +82 +ENDCHAR +STARTCHAR 095 +ENCODING 95 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 1 0 -2 +BITMAP +FE +ENDCHAR +STARTCHAR 096 +ENCODING 96 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 4 2 7 +BITMAP +80 +40 +20 +10 +ENDCHAR +STARTCHAR 097 +ENCODING 97 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +3C +02 +02 +3E +C2 +46 +3E +ENDCHAR +STARTCHAR 098 +ENCODING 98 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +80 +80 +80 +FC +82 +82 +82 +82 +84 +F8 +ENDCHAR +STARTCHAR 099 +ENCODING 99 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +7C +80 +80 +80 +82 +44 +38 +ENDCHAR +STARTCHAR 100 +ENCODING 100 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +02 +02 +02 +3E +42 +82 +82 +82 +42 +3E +ENDCHAR +STARTCHAR 101 +ENCODING 101 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +3C +42 +82 +FC +80 +40 +3C +ENDCHAR +STARTCHAR 102 +ENCODING 102 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +08 +14 +22 +20 +20 +F8 +20 +20 +20 +20 +ENDCHAR +STARTCHAR 103 +ENCODING 103 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +3C +42 +82 +82 +82 +42 +3E +02 +3C +ENDCHAR +STARTCHAR 104 +ENCODING 104 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +80 +80 +80 +FC +82 +82 +82 +82 +82 +82 +ENDCHAR +STARTCHAR 105 +ENCODING 105 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 9 2 0 +BITMAP +40 +00 +C0 +40 +40 +40 +40 +40 +F0 +ENDCHAR +STARTCHAR 106 +ENCODING 106 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 11 2 -2 +BITMAP +08 +00 +38 +08 +08 +08 +08 +08 +08 +88 +70 +ENDCHAR +STARTCHAR 107 +ENCODING 107 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +80 +80 +80 +82 +84 +88 +F0 +88 +84 +82 +ENDCHAR +STARTCHAR 108 +ENCODING 108 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 9 2 0 +BITMAP +C0 +40 +40 +40 +40 +40 +40 +40 +F0 +ENDCHAR +STARTCHAR 109 +ENCODING 109 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +EC +92 +92 +92 +92 +92 +92 +ENDCHAR +STARTCHAR 110 +ENCODING 110 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +9C +A2 +C2 +82 +82 +82 +82 +ENDCHAR +STARTCHAR 111 +ENCODING 111 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +38 +44 +82 +82 +82 +44 +38 +ENDCHAR +STARTCHAR 112 +ENCODING 112 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +FC +82 +82 +82 +82 +82 +FC +80 +80 +ENDCHAR +STARTCHAR 113 +ENCODING 113 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +7E +82 +82 +82 +82 +82 +7E +02 +02 +ENDCHAR +STARTCHAR 114 +ENCODING 114 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +9C +A2 +C2 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 115 +ENCODING 115 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +3E +40 +80 +7C +02 +04 +F8 +ENDCHAR +STARTCHAR 116 +ENCODING 116 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +10 +10 +10 +FE +10 +10 +10 +10 +08 +06 +ENDCHAR +STARTCHAR 117 +ENCODING 117 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +82 +82 +82 +82 +86 +8A +72 +ENDCHAR +STARTCHAR 118 +ENCODING 118 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +82 +82 +82 +82 +44 +28 +10 +ENDCHAR +STARTCHAR 119 +ENCODING 119 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +82 +82 +82 +82 +92 +54 +28 +ENDCHAR +STARTCHAR 120 +ENCODING 120 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +82 +44 +28 +10 +28 +44 +82 +ENDCHAR +STARTCHAR 121 +ENCODING 121 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +82 +82 +82 +44 +28 +10 +10 +20 +C0 +ENDCHAR +STARTCHAR 122 +ENCODING 122 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +FE +04 +08 +10 +20 +40 +FE +ENDCHAR +STARTCHAR 123 +ENCODING 123 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 12 2 -1 +BITMAP +30 +40 +40 +40 +40 +80 +80 +40 +40 +40 +40 +30 +ENDCHAR +STARTCHAR 124 +ENCODING 124 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 1 12 3 -1 +BITMAP +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 125 +ENCODING 125 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 3 12 2 -1 +BITMAP +80 +40 +40 +40 +40 +20 +20 +40 +40 +40 +40 +80 +ENDCHAR +STARTCHAR 126 +ENCODING 126 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 4 0 3 +BITMAP +22 +52 +92 +8C +ENDCHAR +STARTCHAR 127 +ENCODING 127 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 128 +ENCODING 128 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 129 +ENCODING 129 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 130 +ENCODING 130 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 131 +ENCODING 131 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 132 +ENCODING 132 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 133 +ENCODING 133 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 134 +ENCODING 134 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 135 +ENCODING 135 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 136 +ENCODING 136 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 137 +ENCODING 137 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 138 +ENCODING 138 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 139 +ENCODING 139 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 140 +ENCODING 140 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 141 +ENCODING 141 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 142 +ENCODING 142 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 143 +ENCODING 143 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 144 +ENCODING 144 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 145 +ENCODING 145 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 146 +ENCODING 146 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 147 +ENCODING 147 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 148 +ENCODING 148 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 149 +ENCODING 149 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 150 +ENCODING 150 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 151 +ENCODING 151 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 152 +ENCODING 152 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 153 +ENCODING 153 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 154 +ENCODING 154 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 155 +ENCODING 155 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 156 +ENCODING 156 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 157 +ENCODING 157 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 158 +ENCODING 158 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 159 +ENCODING 159 +SWIDTH 216 0 +DWIDTH 3 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 160 +ENCODING 160 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 0 0 0 0 +BITMAP +ENDCHAR +STARTCHAR 161 +ENCODING 161 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 1 10 3 0 +BITMAP +80 +80 +00 +80 +80 +80 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 162 +ENCODING 162 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -1 +BITMAP +10 +3C +D2 +D2 +D0 +D2 +3C +3C +10 +ENDCHAR +STARTCHAR 163 +ENCODING 163 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +1C +1C +22 +20 +F0 +F0 +20 +22 +DC +DC +ENDCHAR +STARTCHAR 164 +ENCODING 164 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +D2 +2C +2C +C2 +2C +D2 +D2 +ENDCHAR +STARTCHAR 165 +ENCODING 165 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +C2 +C2 +2C +FE +10 +10 +FE +10 +10 +10 +ENDCHAR +STARTCHAR 166 +ENCODING 166 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 1 10 3 0 +BITMAP +80 +80 +80 +80 +00 +00 +80 +80 +80 +80 +ENDCHAR +STARTCHAR 167 +ENCODING 167 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 11 2 0 +BITMAP +78 +80 +80 +70 +88 +88 +88 +70 +08 +F0 +F0 +ENDCHAR +STARTCHAR 168 +ENCODING 168 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 1 2 10 +BITMAP +B0 +ENDCHAR +STARTCHAR 169 +ENCODING 169 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 8 10 0 0 +BITMAP +3E +3E +C1 +DD +D1 +D1 +DD +C1 +3E +3E +ENDCHAR +STARTCHAR 170 +ENCODING 170 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 6 2 6 +BITMAP +70 +B0 +70 +70 +00 +F0 +ENDCHAR +STARTCHAR 171 +ENCODING 171 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +12 +2C +2C +D0 +2C +12 +12 +ENDCHAR +STARTCHAR 172 +ENCODING 172 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 4 0 2 +BITMAP +FE +FE +02 +02 +ENDCHAR +STARTCHAR 173 +ENCODING 173 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 2 2 4 +BITMAP +F0 +F0 +ENDCHAR +STARTCHAR 174 +ENCODING 174 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 8 10 0 0 +BITMAP +3E +3E +C1 +DD +D1 +D1 +D1 +C1 +3E +3E +ENDCHAR +STARTCHAR 175 +ENCODING 175 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 1 0 10 +BITMAP +FE +ENDCHAR +STARTCHAR 176 +ENCODING 176 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 5 2 7 +BITMAP +70 +88 +88 +88 +70 +ENDCHAR +STARTCHAR 177 +ENCODING 177 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +10 +10 +10 +FE +10 +10 +10 +00 +FE +FE +ENDCHAR +STARTCHAR 178 +ENCODING 178 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 6 2 6 +BITMAP +40 +B0 +30 +30 +40 +F0 +ENDCHAR +STARTCHAR 179 +ENCODING 179 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 6 2 6 +BITMAP +C0 +30 +40 +40 +30 +C0 +ENDCHAR +STARTCHAR 180 +ENCODING 180 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 4 2 7 +BITMAP +30 +40 +40 +80 +ENDCHAR +STARTCHAR 181 +ENCODING 181 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +C2 +C2 +C2 +C2 +CE +F2 +F2 +C0 +C0 +ENDCHAR +STARTCHAR 182 +ENCODING 182 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +3E +F2 +F2 +F2 +F2 +32 +32 +12 +12 +12 +12 +ENDCHAR +STARTCHAR 183 +ENCODING 183 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 3 3 3 4 +BITMAP +E0 +E0 +E0 +ENDCHAR +STARTCHAR 184 +ENCODING 184 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 2 2 -2 +BITMAP +30 +C0 +ENDCHAR +STARTCHAR 185 +ENCODING 185 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 6 2 6 +BITMAP +40 +C0 +40 +40 +40 +F0 +ENDCHAR +STARTCHAR 186 +ENCODING 186 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 7 2 7 +BITMAP +40 +40 +B0 +40 +00 +00 +F0 +ENDCHAR +STARTCHAR 187 +ENCODING 187 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +D0 +2C +2C +12 +2C +D0 +D0 +ENDCHAR +STARTCHAR 188 +ENCODING 188 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +E0 +22 +2C +2C +30 +2C +DC +DC +2C +3E +0C +0C +ENDCHAR +STARTCHAR 189 +ENCODING 189 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +E0 +22 +2C +2C +30 +2C +D2 +D2 +02 +0C +1E +1E +ENDCHAR +STARTCHAR 190 +ENCODING 190 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +E0 +E0 +10 +22 +1C +1C +F0 +2C +DC +DC +2C +3E +0C +0C +ENDCHAR +STARTCHAR 191 +ENCODING 191 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +10 +10 +00 +10 +10 +10 +20 +C2 +3C +3C +ENDCHAR +STARTCHAR 192 +ENCODING 192 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +10 +00 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 193 +ENCODING 193 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +0C +0C +10 +00 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 194 +ENCODING 194 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +10 +10 +2C +00 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 195 +ENCODING 195 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +32 +32 +DC +00 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 196 +ENCODING 196 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 0 +BITMAP +2C +00 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 197 +ENCODING 197 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +10 +10 +2C +10 +3C +3C +C2 +C2 +FE +FE +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 198 +ENCODING 198 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +3E +3E +D0 +D0 +FC +FC +D0 +D0 +DE +DE +ENDCHAR +STARTCHAR 199 +ENCODING 199 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -2 +BITMAP +3C +3C +C2 +C0 +C0 +C0 +C0 +C2 +3C +3C +0C +30 +ENDCHAR +STARTCHAR 200 +ENCODING 200 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +10 +00 +FE +FE +C0 +C0 +FC +FC +C0 +C0 +FE +FE +ENDCHAR +STARTCHAR 201 +ENCODING 201 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +0C +0C +10 +00 +FE +FE +C0 +C0 +FC +FC +C0 +C0 +FE +FE +ENDCHAR +STARTCHAR 202 +ENCODING 202 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +10 +10 +2C +00 +FE +FE +C0 +C0 +FC +FC +C0 +C0 +FE +FE +ENDCHAR +STARTCHAR 203 +ENCODING 203 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 0 +BITMAP +2C +00 +FE +FE +C0 +C0 +FC +FC +C0 +C0 +FE +FE +ENDCHAR +STARTCHAR 204 +ENCODING 204 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 14 2 0 +BITMAP +80 +80 +40 +00 +F0 +F0 +40 +40 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 205 +ENCODING 205 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 14 2 0 +BITMAP +30 +30 +40 +00 +F0 +F0 +40 +40 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 206 +ENCODING 206 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 14 2 0 +BITMAP +40 +40 +B0 +00 +F0 +F0 +40 +40 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 207 +ENCODING 207 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 12 2 0 +BITMAP +B0 +00 +F0 +F0 +40 +40 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 208 +ENCODING 208 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +3C +3C +22 +22 +F2 +F2 +22 +22 +3C +3C +ENDCHAR +STARTCHAR 209 +ENCODING 209 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +32 +32 +DC +00 +C2 +C2 +C2 +E2 +D2 +D2 +CE +C2 +C2 +C2 +ENDCHAR +STARTCHAR 210 +ENCODING 210 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +10 +00 +3C +3C +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 211 +ENCODING 211 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +0C +0C +10 +00 +3C +3C +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 212 +ENCODING 212 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +10 +10 +2C +00 +3C +3C +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 213 +ENCODING 213 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +32 +32 +DC +00 +3C +3C +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 214 +ENCODING 214 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 0 +BITMAP +2C +00 +3C +3C +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 215 +ENCODING 215 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 6 0 2 +BITMAP +C2 +2C +10 +10 +2C +C2 +ENDCHAR +STARTCHAR 216 +ENCODING 216 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -1 +BITMAP +02 +3C +3C +CE +D2 +D2 +D2 +D2 +E2 +3C +3C +C0 +ENDCHAR +STARTCHAR 217 +ENCODING 217 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +20 +20 +10 +00 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 218 +ENCODING 218 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +0C +0C +10 +00 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 219 +ENCODING 219 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +10 +10 +2C +00 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 220 +ENCODING 220 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 0 +BITMAP +2C +00 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 221 +ENCODING 221 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 14 0 0 +BITMAP +0C +0C +10 +00 +C2 +C2 +C2 +2C +10 +10 +10 +10 +10 +10 +ENDCHAR +STARTCHAR 222 +ENCODING 222 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 5 10 2 0 +BITMAP +80 +80 +F0 +88 +88 +88 +88 +F0 +80 +80 +ENDCHAR +STARTCHAR 223 +ENCODING 223 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +3C +3C +C2 +CC +D0 +D0 +CC +C2 +DC +DC +ENDCHAR +STARTCHAR 224 +ENCODING 224 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +20 +10 +10 +00 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 225 +ENCODING 225 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +0C +10 +10 +00 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 226 +ENCODING 226 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +2C +2C +00 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 227 +ENCODING 227 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +32 +DC +DC +00 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 228 +ENCODING 228 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +2C +2C +00 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 229 +ENCODING 229 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +2C +2C +10 +3C +02 +02 +3E +C2 +3E +3E +ENDCHAR +STARTCHAR 230 +ENCODING 230 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +3C +12 +12 +3C +D0 +3E +3E +ENDCHAR +STARTCHAR 231 +ENCODING 231 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 9 0 -2 +BITMAP +3C +C2 +C2 +C0 +C2 +3C +3C +0C +30 +ENDCHAR +STARTCHAR 232 +ENCODING 232 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +20 +10 +10 +00 +3C +C2 +C2 +FC +C0 +3C +3C +ENDCHAR +STARTCHAR 233 +ENCODING 233 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +0C +10 +10 +00 +3C +C2 +C2 +FC +C0 +3C +3C +ENDCHAR +STARTCHAR 234 +ENCODING 234 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +2C +2C +00 +3C +C2 +C2 +FC +C0 +3C +3C +ENDCHAR +STARTCHAR 235 +ENCODING 235 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +2C +2C +00 +3C +C2 +C2 +FC +C0 +3C +3C +ENDCHAR +STARTCHAR 236 +ENCODING 236 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 11 2 0 +BITMAP +80 +40 +40 +00 +C0 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 237 +ENCODING 237 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 11 2 0 +BITMAP +30 +40 +40 +00 +C0 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 238 +ENCODING 238 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 11 2 0 +BITMAP +40 +B0 +B0 +00 +C0 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 239 +ENCODING 239 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 4 10 2 0 +BITMAP +B0 +B0 +00 +C0 +40 +40 +40 +40 +F0 +F0 +ENDCHAR +STARTCHAR 240 +ENCODING 240 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 0 +BITMAP +2C +10 +2C +2C +02 +3E +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 241 +ENCODING 241 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +32 +DC +DC +00 +DC +E2 +E2 +C2 +C2 +C2 +C2 +ENDCHAR +STARTCHAR 242 +ENCODING 242 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +20 +10 +10 +00 +3C +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 243 +ENCODING 243 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +0C +10 +10 +00 +3C +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 244 +ENCODING 244 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +2C +2C +00 +3C +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 245 +ENCODING 245 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +32 +DC +DC +00 +3C +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 246 +ENCODING 246 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +2C +2C +00 +3C +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 247 +ENCODING 247 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 6 0 2 +BITMAP +10 +00 +FE +FE +00 +10 +ENDCHAR +STARTCHAR 248 +ENCODING 248 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 7 0 0 +BITMAP +3E +CE +CE +D2 +E2 +FC +FC +ENDCHAR +STARTCHAR 249 +ENCODING 249 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +20 +10 +10 +00 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 250 +ENCODING 250 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +0C +10 +10 +00 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 251 +ENCODING 251 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 11 0 0 +BITMAP +10 +2C +2C +00 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 252 +ENCODING 252 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 10 0 0 +BITMAP +2C +2C +00 +C2 +C2 +C2 +C2 +C2 +3C +3C +ENDCHAR +STARTCHAR 253 +ENCODING 253 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 13 0 -2 +BITMAP +0C +10 +10 +00 +C2 +C2 +C2 +C2 +2C +10 +10 +20 +C0 +ENDCHAR +STARTCHAR 254 +ENCODING 254 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -2 +BITMAP +C0 +C0 +C0 +FC +C2 +C2 +C2 +C2 +FC +FC +C0 +C0 +ENDCHAR +STARTCHAR 255 +ENCODING 255 +SWIDTH 576 0 +DWIDTH 8 0 +BBX 7 12 0 -2 +BITMAP +2C +2C +00 +C2 +C2 +C2 +C2 +2C +10 +10 +20 +C0 +ENDCHAR +ENDFONT diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index ad88225807..a941eb906a 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -13,11 +13,9 @@ use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" -use_example_configs "Creality/Ender-3 V2/CrealityUI" -opt_disable CLASSIC_JERK +use_example_configs "Creality/Ender-3 V2/MarlinUI" opt_add SDCARD_EEPROM_EMULATION -opt_set TEMP_SENSOR_BED 0 -exec_test $1 $2 "Ender 3 v2, SD EEPROM, no CLASSIC_JERK, no Bed" "$3" +exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" restore_configs opt_set MOTHERBOARD BOARD_CREALITY_V452 SERIAL_PORT 1 diff --git a/ini/features.ini b/ini/features.ini index 2d2363ccd1..fa7d151938 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -45,6 +45,7 @@ I2C_EEPROM = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ +DWIN_MARLINUI_.+ = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ HAS_TOUCH_BUTTONS = src_filter=+ diff --git a/platformio.ini b/platformio.ini index db4d12ea7f..9ee1e76a5b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -48,7 +48,8 @@ extra_scripts = post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py lib_deps = default_src_filter = + - - + - - - - - - - + - - - - - + - - - - - - - - From 104de60d0bbad1233455591842bc67cb4f006f30 Mon Sep 17 00:00:00 2001 From: Chris Pepper Date: Sun, 22 Aug 2021 22:47:37 +0100 Subject: [PATCH 0574/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LPC176x=20M43=20?= =?UTF-8?q?Pins=20Debugging=20(#22611)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/pinsDebug.h | 1 + Marlin/src/HAL/DUE/pinsDebug.h | 1 + Marlin/src/HAL/LINUX/pinsDebug.h | 1 + Marlin/src/HAL/LPC1768/pinsDebug.h | 7 +++---- Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 1 + Marlin/src/HAL/SAMD51/pinsDebug.h | 1 + Marlin/src/HAL/STM32/pinsDebug.h | 1 + Marlin/src/HAL/STM32F1/pinsDebug.h | 1 + Marlin/src/HAL/TEENSY40_41/pinsDebug.h | 1 + Marlin/src/pins/pinsDebug.h | 15 ++++----------- Marlin/src/pins/pinsDebug_list.h | 10 +++++++--- 11 files changed, 22 insertions(+), 18 deletions(-) diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 55fddb05b8..6923e1f902 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -393,3 +393,4 @@ static void pwm_details(uint8_t pin) { #endif #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index a99ca8ecce..02a5e6646f 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -64,6 +64,7 @@ #define PRINT_PORT(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define GET_ARRAY_PIN(p) pin_array[p].pin #define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital #define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h index 8f8543ef59..9803c5d362 100644 --- a/Marlin/src/HAL/LINUX/pinsDebug.h +++ b/Marlin/src/HAL/LINUX/pinsDebug.h @@ -34,6 +34,7 @@ #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // active ADC function/mode/code values for PINSEL registers diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h index f80551604f..c622a2622e 100644 --- a/Marlin/src/HAL/LPC1768/pinsDebug.h +++ b/Marlin/src/HAL/LPC1768/pinsDebug.h @@ -33,7 +33,8 @@ #define PRINT_PORT(p) #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%d.%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities @@ -48,6 +49,4 @@ bool GET_PINMODE(const pin_t pin) { return LPC176x::gpio_direction(pin); } -bool GET_ARRAY_IS_DIGITAL(const pin_t pin) { - return (!LPC176x::pin_has_adc(pin) || !LPC176x::pin_adc_enabled(pin)); -} +#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index 7ba14574d0..7e50492598 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -36,6 +36,7 @@ #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // active ADC function/mode/code values for PINSEL registers diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h index 81376db79a..5c86d0c071 100644 --- a/Marlin/src/HAL/SAMD51/pinsDebug.h +++ b/Marlin/src/HAL/SAMD51/pinsDebug.h @@ -26,6 +26,7 @@ #define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define GET_ARRAY_PIN(p) pin_array[p].pin #define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital #define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL) diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 048f788e3d..ff671a6ebf 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -109,6 +109,7 @@ const XrefInfo pin_xref[] PROGMEM = { #define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL) #define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads #define PRINT_PIN(Q) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine #define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index b018a0fc8c..dcf3a51138 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -41,6 +41,7 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; #define pwm_status(pin) PWM_PIN(pin) #define digitalRead_mod(p) extDigitalRead(p) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(p) print_port(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h index 4ad62d00fe..197cc6f1b2 100644 --- a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h @@ -30,6 +30,7 @@ #define PRINT_PORT(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define GET_ARRAY_PIN(p) pin_array[p].pin #define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital #define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 0c55232969..e29067268d 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -203,11 +203,8 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); - if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { - sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); // analog pin number - SERIAL_ECHO(buffer); - } - else SERIAL_ECHO_SP(8); // add padding if not an analog pin + if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) PRINT_PIN_ANALOG(pin); // analog pin number + else SERIAL_ECHO_SP(8); // add padding if not an analog pin } else { SERIAL_CHAR('.'); @@ -254,12 +251,8 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); - if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { - sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); // analog pin number - SERIAL_ECHO(buffer); - } - else - SERIAL_ECHO_SP(8); // add padding if not an analog pin + if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) PRINT_PIN_ANALOG(pin); // analog pin number + else SERIAL_ECHO_SP(8); // add padding if not an analog pin SERIAL_ECHOPGM(""); if (extended) { diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 78ee71749d..501ae921c2 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -24,14 +24,18 @@ // Pin lists 1.1.x and 2.0.x synchronized 2018-02-17 -#line 28 // set __LINE__ to a known value for both passes +#if TARGET_LPC1768 + #define ANALOG_OK(PN) ((PN) == P0_02 || (PN) == P0_03 || (PN) == P0_23 || (PN) == P0_24 || (PN) == P0_25 || (PN) == P0_26 || (PN) == P1_30 || (PN) == P1_31) +#else + #define ANALOG_OK(PN) ((PN) >= 0 && (PN) < NUM_ANALOG_INPUTS) +#endif + +#line 34 // set __LINE__ to a known value for both passes // // Analog Pin Assignments // -#define ANALOG_OK(PN) ((PN) >= 0 && (PN) < NUM_ANALOG_INPUTS) - #if defined(EXT_AUX_A0) && ANALOG_OK(EXT_AUX_A0) REPORT_NAME_ANALOG(__LINE__, EXT_AUX_A0) #endif From 2c45ac3c1b2acb1f98a92dd80160c560d08600a8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 23 Aug 2021 00:53:22 +0000 Subject: [PATCH 0575/2168] [cron] Bump distribution date (2021-08-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 21efff8495..ec3d43c4a5 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-21" +//#define STRING_DISTRIBUTION_DATE "2021-08-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6bbcca1457..05aec3fa8b 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 "2021-08-21" + #define STRING_DISTRIBUTION_DATE "2021-08-23" #endif /** From 9c51cf3491623a7492e6c6d1e20218da69e3db72 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 24 Aug 2021 00:56:33 +0000 Subject: [PATCH 0576/2168] [cron] Bump distribution date (2021-08-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ec3d43c4a5..ebd1fc9f97 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-23" +//#define STRING_DISTRIBUTION_DATE "2021-08-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 05aec3fa8b..6709b5b46b 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 "2021-08-23" + #define STRING_DISTRIBUTION_DATE "2021-08-24" #endif /** From 7974dcd2aaae741e37d6e2e230492f2ba258ffb4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 23 Aug 2021 19:42:15 -0500 Subject: [PATCH 0577/2168] =?UTF-8?q?=F0=9F=8E=A8=20Define=20FYSETC=20S6?= =?UTF-8?q?=20and=20TH3D=20EZBoard=20EXP1/2=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 97 +++++++++++---- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 126 ++++++++++++-------- 2 files changed, 145 insertions(+), 78 deletions(-) diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index e45f5dbd95..22a6613329 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -27,20 +27,30 @@ #include "env_validate.h" +//#define V3_EZABL_ON_SERVO // As in TH3D Firmware Config + #define BOARD_INFO_NAME "TH3D EZBoard" #define BOARD_WEBSITE_URL "th3dstudio.com" // // Servos // -#define SERVO0_PIN P2_04 +#if ENABLED(V3_EZABL_ON_SERVO) + #define SERVO0_PIN -1 +#else + #define SERVO0_PIN P2_04 +#endif // // Limit Switches // #define X_STOP_PIN P1_24 #define Y_STOP_PIN P1_25 -#define Z_STOP_PIN P1_26 +#if ENABLED(V3_EZABL_ON_SERVO) + #define Z_STOP_PIN P2_04 +#else + #define Z_STOP_PIN P1_26 +#endif // // Filament Runout Sensor @@ -103,13 +113,6 @@ #endif #define TEMP_BED_PIN P0_24_A1 // Analog Input P0_24 -#define TEMP_1_PIN P0_25_A2 // Analog Input P0_25 - -#if ENABLED(FILAMENT_WIDTH_SENSOR) - #define FILWIDTH_PIN P0_26_A3 // Analog Input P0_26 -#else - #define TEMP_2_PIN P0_26_A3 // Analog Input P0_26 -#endif // // Heaters / Fans @@ -141,6 +144,7 @@ #define SDCARD_CONNECTION ONBOARD +//#define SD_DETECT_PIN P0_25 // SD_CD #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 @@ -152,14 +156,14 @@ // /** - * _____ - * 5V | · · | GND - * (LCD_EN) P0_18 | · · | P0_16 (LCD_RS) - * (LCD_D4) P0_15 | · · P3_25 (BTN_EN2) - * (RESET) P2_11 | · · | P3_26 (BTN_EN1) - * (BTN_ENC) P1_30 | · · | P1_31 (BEEPER) - * ----- - * EXP1 + * ______ + * 5V | 1 2 | GND + * P0_18 | 3 4 | P0_16 + * P0_15 | 5 6 P3_25 + * P2_11 | 7 8 | P3_26 + * P1_30 | 9 10 | P1_31 + * ------ + * EXP1 * * LCD_PINS_D5, D6, and D7 are not present in the EXP1 connector, and will need to be * defined to use the REPRAP_DISCOUNT_SMART_CONTROLLER. @@ -167,16 +171,57 @@ * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. */ +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN P3_25 +#define EXP1_07_PIN P2_11 +#define EXP1_08_PIN P3_26 +#define EXP1_09_PIN P1_30 +#define EXP1_10_PIN P1_31 #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN P1_31 - #define BTN_EN1 P3_26 - #define BTN_EN2 P3_25 - #define BTN_ENC P1_30 - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define KILL_PIN P2_11 + /** ______ + * 5V | 1 2 | GND + * LCD_EN | 3 4 | LCD_RS + * LCD_D4 | 5 6 EN2 + * KILL | 7 8 | EN1 + * ENC | 9 10 | BEEPER + * ------ + */ + #define BEEPER_PIN EXP1_10_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define KILL_PIN EXP1_07_PIN + +#elif ENABLED(MKS_MINI_12864) + /** ______ + * 5V | 1 2 | GND + * SPI-MOSI | 3 4 | SPI-CS + * A0 | 5 6 EN2 + * -- | 7 8 | EN1 + * ENC | 9 10 | SPI-SCK + * ------ + */ + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_10_PIN + #define DOGLCD_MOSI EXP1_03_PIN + #define LCD_CONTRAST_INIT 160 + #define LCD_CONTRAST_MIN 120 + #define LCD_CONTRAST_MAX 180 + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + #elif HAS_WIRED_LCD - #error "Only the CR10_STOCKDISPLAY is supported with TH3D EZBoard." + + #error "Only CR10_STOCKDISPLAY or MKS_MINI_12864 are supported with TH3D EZBoard." + +#endif + +#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index c9f528b87b..9de62d372a 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -184,13 +184,6 @@ #define FAN1_PIN PB1 #define FAN2_PIN PB2 -// -// SPI -// -#define SD_SCK_PIN PA5 -#define SD_MISO_PIN PA6 -#define SD_MOSI_PIN PA7 - // // Misc. Functions // @@ -198,84 +191,119 @@ //#define PS_ON_PIN PE11 //#define KILL_PIN PC5 -#define SDSS PA4 -#define SD_DETECT_PIN PB10 +/** + * ______ ______ + * 5V | 1 2 | GND 5V | 1 2 | GND + * PD1 | 3 4 | PD0 RESET | 3 4 | PB10 + * PC12 | 5 6 PC10 PA7 | 5 6 PC7 + * PD2 | 7 8 | PC11 PA4 | 7 8 | PC6 + * PA8 | 9 10 | PC9 PA5 | 9 10 | PA6 + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PD1 +#define EXP1_04_PIN PD0 +#define EXP1_05_PIN PC12 +#define EXP1_06_PIN PC10 +#define EXP1_07_PIN PD2 +#define EXP1_08_PIN PC11 +#define EXP1_09_PIN PA8 +#define EXP1_10_PIN PC9 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB10 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PC7 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PC6 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// SPI / SD Card +// +#define SD_SCK_PIN EXP2_09_PIN +#define SD_MISO_PIN EXP2_10_PIN +#define SD_MOSI_PIN EXP2_05_PIN + +#define SDSS EXP2_07_PIN +#define SD_DETECT_PIN EXP2_04_PIN // // LCD / Controller // #if ENABLED(FYSETC_242_OLED_12864) - #define BTN_EN1 PC9 - #define BTN_EN2 PD1 - #define BTN_ENC PA8 + #define BTN_EN1 EXP1_10_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_09_PIN - #define BEEPER_PIN PC6 + #define BEEPER_PIN EXP2_08_PIN - #define LCD_PINS_DC PC12 - #define LCD_PINS_RS PC7 // LCD_RST - #define DOGLCD_CS PD2 - #define DOGLCD_MOSI PC10 - #define DOGLCD_SCK PC11 + #define LCD_PINS_DC EXP1_05_PIN + #define LCD_PINS_RS EXP2_06_PIN // LCD_RST + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_MOSI EXP1_06_PIN + #define DOGLCD_SCK EXP1_08_PIN #define DOGLCD_A0 LCD_PINS_DC #define FORCE_SOFT_SPI #define KILL_PIN -1 // NC - #define NEOPIXEL_PIN PD0 + #define NEOPIXEL_PIN EXP1_04_PIN #elif HAS_WIRED_LCD - #define BEEPER_PIN PC9 - #define BTN_ENC PA8 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PD0 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 PC11 - #define BTN_EN2 PC10 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE PD1 - #define LCD_PINS_D4 PC12 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #else - #define LCD_PINS_RS PD2 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PC6 - #define BTN_EN2 PC7 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_SDSS PA4 + #define LCD_SDSS EXP2_07_PIN - #define LCD_PINS_ENABLE PC11 - #define LCD_PINS_D4 PC10 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) // See https://wiki.fysetc.com/Mini12864_Panel - #define DOGLCD_CS PC11 - #define DOGLCD_A0 PD2 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN PD0 + #define LCD_BACKLIGHT_PIN EXP1_04_PIN #endif - #define LCD_RESET_PIN PC10 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PC12 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PD0 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PD1 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PC12 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 PC12 - #define LCD_PINS_D6 PD0 - #define LCD_PINS_D7 PD1 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif @@ -287,15 +315,9 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) - #endif + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) #endif #ifndef RGB_LED_R_PIN From 8cf7dc960fbc78b7c9339d30372289d8c1bb0303 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Aug 2021 14:55:12 -0500 Subject: [PATCH 0578/2168] =?UTF-8?q?=E2=9C=A8=20New=20board=20TH3D=5FEZBO?= =?UTF-8?q?ARD=5FLITE=5FV2=20(#22621)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + .../pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h | 264 ++++++++++ .../PeripheralPins.c | 314 +++++++++++ .../MARLIN_TH3D_EZBOARD_LITE_V2/PinNamesVar.h | 50 ++ .../hal_conf_extra.h | 495 ++++++++++++++++++ .../MARLIN_TH3D_EZBOARD_LITE_V2/ldscript.ld | 203 +++++++ .../MARLIN_TH3D_EZBOARD_LITE_V2/variant.cpp | 177 +++++++ .../MARLIN_TH3D_EZBOARD_LITE_V2/variant.h | 148 ++++++ ini/stm32f4.ini | 14 + 10 files changed, 1668 insertions(+) create mode 100644 Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PinNamesVar.h create mode 100755 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 8e84f0b967..6eeed447f7 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -393,6 +393,7 @@ #define BOARD_ANET_ET4 4229 // ANET ET4 V1.x (STM32F407VGT6) #define BOARD_ANET_ET4P 4230 // ANET ET4P V1.x (STM32F407VGT6) #define BOARD_FYSETC_CHEETAH_V20 4231 // FYSETC Cheetah V2.0 +#define BOARD_TH3D_EZBOARD_LITE_V2 4232 // TH3D EZBoard Lite v2.0 // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 0655580f0f..1c3e1ac7cf 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -641,6 +641,8 @@ #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 #elif MB(MKS_MONSTER8) #include "stm32f4/pins_MKS_MONSTER8.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc +#elif MB(TH3D_EZBOARD_LITE_V2) + #include "stm32f4/pins_TH3D_EZBOARD_LITE_V2.h" // STM32F4 env:TH3D_EZBoard_Lite_V2 // // ARM Cortex M7 diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h new file mode 100644 index 0000000000..c04341a243 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h @@ -0,0 +1,264 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#define BOARD_INFO_NAME "TH3D EZBoard Lite V2" +#define BOARD_WEBSITE_URL "th3dstudio.com" + +//#define V3_EZABL_ON_SERVO // As in TH3D Firmware Config + +#define DISABLE_JTAGSWD // Disabling J-tag and Debug via SWD + +// Onboard I2C EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define I2C_SCL_PIN PB6 + #define I2C_SDA_PIN PB7 + #undef NO_EEPROM_SELECTED +#endif + +// +// Neopixels +// +#define NEOPIXEL_PIN PA8 + +// +// Servos +// +#if ENABLED(V3_EZABL_ON_SERVO) + #define SERVO0_PIN -1 +#else + #define SERVO0_PIN PA2 +#endif + +// +// Limit Switches +// +#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + // Sensorless homing pins + #if ENABLED(X_AXIS_SENSORLESS_HOMING) + #define X_STOP_PIN PB4 + #else + #define X_STOP_PIN PC1 + #endif + + #if ENABLED(Y_AXIS_SENSORLESS_HOMING) + #define Y_STOP_PIN PB9 + #else + #define Y_STOP_PIN PC2 + #endif + + //#define Z_STOP_PIN PC15 // Don't use sensorless homing on Z! + + #define E_STOP_PIN PB10 +#else + // Standard Endstop Pins + #define X_STOP_PIN PC1 + #define Y_STOP_PIN PC2 +#endif + +#if ENABLED(V3_EZABL_ON_SERVO) + #define Z_STOP_PIN PA2 +#else + #define Z_STOP_PIN PC3 +#endif + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PC0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PB3 +#define X_DIR_PIN PD2 +#define X_ENABLE_PIN PB5 + +#define Y_STEP_PIN PB8 +#define Y_DIR_PIN PC13 +#define Y_ENABLE_PIN PC12 + +#define Z_STEP_PIN PA3 +#define Z_DIR_PIN PB1 +#define Z_ENABLE_PIN PC14 + +#define E0_STEP_PIN PA15 +#define E0_DIR_PIN PB11 +#define E0_ENABLE_PIN PB2 + +#if HAS_TMC_UART + // + // Hardware Serial on UART4, Single Wire, 0-3 addresses + // + #define X_SERIAL_TX_PIN PC10 + #define X_SERIAL_RX_PIN PC11 + + #define Y_SERIAL_TX_PIN PC10 + #define Y_SERIAL_RX_PIN PC11 + + #define Z_SERIAL_TX_PIN PC10 + #define Z_SERIAL_RX_PIN PC11 + + #define E0_SERIAL_TX_PIN PC10 + #define E0_SERIAL_RX_PIN PC11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temp Sensors +// 3.3V max when defined as an Analog Input! +// +#define TEMP_0_PIN PA1 // Analog Input PA1 +#define TEMP_BED_PIN PA0 // Analog Input PA0 + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PC9 +#define HEATER_0_PIN PC8 +#ifndef FAN_PIN + #define FAN_PIN PC6 +#endif +#define FAN1_PIN PC7 + +// +// Auto fans +// +#define AUTO_FAN_PIN PC7 +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN AUTO_FAN_PIN +#endif +#ifndef E2_AUTO_FAN_PIN + #define E2_AUTO_FAN_PIN AUTO_FAN_PIN +#endif + +// +// SD Card +// + +#define SDCARD_CONNECTION ONBOARD + +//#define SOFTWARE_SPI +#define CUSTOM_SPI_PINS +#define SDSS PA4 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 +#define SD_SS_PIN SDSS +//#define SD_DETECT_PIN -1 +//#define ONBOARD_SD_CS_PIN SDSS + +// +// LCD / Controller +// + +/** + * ______ + * 5V | 1 2 | GND + * PB15 | 3 4 | PB12 + * PB13 | 5 6 PC5 + * ---- | 7 8 | PC4 + * PB0 | 9 10 | PA14 + * ------ + * EXP1 + * + * LCD_PINS_D5, D6, and D7 are not present in the EXP1 connector, and will need to be + * defined to use the REPRAP_DISCOUNT_SMART_CONTROLLER. + * + * A remote SD card is currently not supported because the pins routed to the EXP2 + * connector are shared with the onboard SD card. + */ +#define EXP1_03_PIN PB15 +#define EXP1_04_PIN PB12 +#define EXP1_05_PIN PB13 +#define EXP1_06_PIN PC5 +//#define EXP1_07_PIN -1 +#define EXP1_08_PIN PC4 +#define EXP1_09_PIN PB0 +#define EXP1_10_PIN PA14 + +#if ENABLED(CR10_STOCKDISPLAY) + /** ______ + * 5V | 1 2 | GND + * LCD_EN | 3 4 | LCD_RS + * LCD_D4 | 5 6 EN2 + * RESET | 7 8 | EN1 + * ENC | 9 10 | BEEPER + * ------ + */ + #ifdef DISABLE_JTAGSWD + #define BEEPER_PIN EXP1_10_PIN // Not connected in dev board + #endif + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + //#define KILL_PIN -1 + + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_1 DELAY_NS(600) + #define BOARD_ST7920_DELAY_2 DELAY_NS(750) + #define BOARD_ST7920_DELAY_3 DELAY_NS(750) + +#elif ENABLED(MKS_MINI_12864) + /** ______ + * 5V | 1 2 | GND + * SPI-MOSI | 3 4 | SPI-CS + * A0 | 5 6 EN2 + * -- | 7 8 | EN1 + * ENC | 9 10 | SPI-SCK + * ------ + */ + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_10_PIN + #define DOGLCD_MOSI EXP1_03_PIN + #define LCD_CONTRAST_INIT 160 + #define LCD_CONTRAST_MIN 120 + #define LCD_CONTRAST_MAX 180 + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + +#elif HAS_WIRED_LCD + + #error "Only CR10_STOCKDISPLAY or MKS_MINI_12864 are supported with TH3D EZBoard V2." + +#endif + +#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PeripheralPins.c new file mode 100644 index 0000000000..03d75bbfa8 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PeripheralPins.c @@ -0,0 +1,314 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + * Automatically generated from STM32F405RGTx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Note: Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 TEMP_BED + //{PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 TEMP_BED + //{PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 TEMP_BED + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 TEMP_0 + //{PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 + //{PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 SERVO0 + //{PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 + //{PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 + //{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 Z_STEP + //{PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + //{PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 + //{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 SPI-SEL ONBOARD SD + //{PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + //{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 SPI-SCK + //{PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + //{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 SPI-MISO + //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + //{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 SPI-MOSI + //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 BTN_ENC + //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + //{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 I2C1 EEPROM + //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + //{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 FIL_RUNOUT + //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + //{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 + //{PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 X_STOP + //{PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + //{PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 + //{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Y_STOP + //{PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + //{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 + //{PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 Z_STOP + //{PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + //{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 + //{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 BTN_EN1 + //{PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + //{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 BTN_EN2 + //{PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + //{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + //{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // I2C1 SDA (EEPROM) + //{PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // YDIAG + //{PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, // E0_DIR + //{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, // BED / HEATER1 + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_I2C_SCL[] = { + //{PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, // NEOPIXEL + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // I2C1 SCL (EEPROM) + //{PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // Y_STEP + //{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, // EDIAG + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 TEMP_BED + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 TEMP_0 + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 SERVO0 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 Z_STEP + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 SPI-SCK + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 SPI-MISO + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N SPI-MOSI + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 NEOPIXEL + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 SERIAL_TX (HEADER) + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 SERIAL_RX (HEADER) + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 USB H + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 E0_STEP + + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N BTN_ENC + //{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N Z_DIR + //{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 X_STEP + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 XDIAG + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 X_ENABLE + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 I2C1_SCL (EEPROM) + //{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C1_SDA (EEPROM) + + //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 Y_STEP + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 YDIAG + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 EDIAG + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 E0_DIR + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N LCD_PINS_D4 + + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N LCD-MISO + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N LCD_PINS_ENABLE + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 FAN + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 FAN1 / AUTO_FAN + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER0 + //{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 BED / HEATER1 + //{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // TEMP_BED + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // SERVO0 + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // SERIAL_TX (HEADER) + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // I2C1_SCL (EEPROM) + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // EDIAG + //{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, // FAN + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // SERIAL_TX (TMC) + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // SERIAL_TX (TMC) + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, // Y_ENABLE + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RX[] = { + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // TEMP_0 + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // Z_STEP + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // SERIAL_RX (HEADER) + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // I2C1 SDA (EEPROM) + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // E_DIR + //{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, // FAN1 / AUTO_FAN + {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // SERIAL_RX (TMC) + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // SERIAL_RX (TMC) + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, // X_DIR + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_RTS[] = { + //{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // TEMP_0 + //{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB D + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // LCD-MISO + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_UART_CTS[] = { + //{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // TEMP_BED / WKUP + //{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB H + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // LCD-SCK + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SPI1 MOSI (SD) + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // X_ENABLE + //{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // SPI2 MOSI (LCD) + //{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // Z_STOP + //{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, // Y_ENABLE + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SPI1 MOSI (SD) + //{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // XDIAG + //{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // SPI2 MISO (LCD) + //{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // Y_STOP + //{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, // SERIAL_RX (TMC) + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SPI1 CLK (SD) + //{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // X_STEP + //{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // EDIAG + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // SPI2 SCK (LCD) + //{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, // SERIAL_TX (TMC) + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SPI1 CS (SD) + //{PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // E0_STEP + //{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + //{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // YDIAG + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // SPI2 CS (LCD) + {NC, NP, 0} +}; +#endif + +//*** No CAN *** + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + //{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF NEOPIXEL + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS SERIAL_TX (HEADER) + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID SERIAL_RX (HEADER) + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM USB H + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP USB D + {NC, NP, 0} +}; + +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + //{PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF CS (SD) + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID CS (LCD) + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS LCD_PINS_D4 + //{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM MISO (LCD) + //{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP LCD_PINS_ENABLE +#else + //{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 Z_STEP + //{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK SPI-SCK + //{PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 BTN_ENC + //{PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 I2C1 (EEPROM) + //{PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 X_ENABLE + //{PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 EDIAG + //{PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4 FAN + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 CS (LCD) + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 LCD_PINS_D4 + //{PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP FIL_RUNOUT + //{PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR Y_STOP + //{PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT Z_STOP +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif + +//*** No SDIO *** diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PinNamesVar.h new file mode 100644 index 0000000000..2424885937 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/PinNamesVar.h @@ -0,0 +1,50 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h new file mode 100755 index 0000000000..8c46edb50e --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h @@ -0,0 +1,495 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_conf_template.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32f4xx_hal_conf.h. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CONF_H +#define __STM32F4xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DCMI_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +//#define HAL_DMA2D_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_SDRAM_MODULE_ENABLED +//#define HAL_HASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +//#define HAL_EXTI_MODULE_ENABLED +//#define HAL_I2C_MODULE_ENABLED +//#define HAL_SMBUS_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_LTDC_MODULE_ENABLED +//#define HAL_DSI_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +//#define HAL_QSPI_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RNG_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SAI_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +#define HAL_USART_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +#define HAL_PCD_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_FMPI2C_MODULE_ENABLED +//#define HAL_SPDIFRX_MODULE_ENABLED +//#define HAL_DFSDM_MODULE_ENABLED +//#define HAL_LPTIM_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_ENABLE 1U + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +//#define USE_FULL_ASSERT 1U + +/* ################## Ethernet peripheral configuration ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848 PHY Address*/ +#define DP83848_PHY_ADDRESS 0x01U +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY 0x000000FFU +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY 0x00000FFFU + +#define PHY_READ_TO 0x0000FFFFU +#define PHY_WRITE_TO 0x0000FFFFU + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */ +#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */ +#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */ + +#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ +#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ + +#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ +#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ + +#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ +#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 0U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32f4xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f4xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f4xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32f4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f4xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f4xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f4xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_FMPI2C_MODULE_ENABLED + #include "stm32f4xx_hal_fmpi2c.h" +#endif /* HAL_FMPI2C_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f4xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32f4xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/ldscript.ld new file mode 100644 index 0000000000..e07c5e4ace --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/ldscript.ld @@ -0,0 +1,203 @@ +/* +***************************************************************************** +** +** File : LinkerScript.ld +** +** +** Abstract : Linker script for STM32F4x5RGTx series +** 1024Kbytes FLASH and 192Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 STMicroelectronics

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE +CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x08000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text ALIGN(8): + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata ALIGN(4): + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.cpp new file mode 100644 index 0000000000..034f685dce --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.cpp @@ -0,0 +1,177 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, // Digital pin 0 + PA_1, // Digital pin 1 + PA_2, // Digital pin 2 + PA_3, // Digital pin 3 + PA_4, // Digital pin 4 + PA_5, // Digital pin 5 + PA_6, // Digital pin 6 + PA_7, // Digital pin 7 + PA_8, // Digital pin 8 + PA_9, // Digital pin 9 + PA_10, // Digital pin 10 + PA_11, // Digital pin 11 + PA_12, // Digital pin 12 + PA_13, // Digital pin 13 + PA_14, // Digital pin 14 + PA_15, // Digital pin 15 + + PB_0, // Digital pin 16 + PB_1, // Digital pin 17 + PB_2, // Digital pin 18 + PB_3, // Digital pin 19 + PB_4, // Digital pin 20 + PB_5, // Digital pin 21 + PB_6, // Digital pin 22 + PB_7, // Digital pin 23 + PB_8, // Digital pin 24 + PB_9, // Digital pin 25 + PB_10, // Digital pin 26 + PB_11, // Digital pin 27 + PB_12, // Digital pin 28 + PB_13, // Digital pin 29 + PB_14, // Digital pin 30 + PB_15, // Digital pin 31 + + PC_0, // Digital pin 32 + PC_1, // Digital pin 33 + PC_2, // Digital pin 34 + PC_3, // Digital pin 35 + PC_4, // Digital pin 36 + PC_5, // Digital pin 37 + PC_6, // Digital pin 38 + PC_7, // Digital pin 39 + PC_8, // Digital pin 40 + PC_9, // Digital pin 41 + PC_10, // Digital pin 42 + PC_11, // Digital pin 43 + PC_12, // Digital pin 44 + PC_13, // Digital pin 45 + PC_14, // Digital pin 46 + PC_15, // Digital pin 47 + + PD_2, // Digital pin 48 + + PH_0, // Digital pin 49, used by the external oscillator + PH_1 // Digital pin 40, used by the external oscillator +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC2 + 35, // A13, PC3 + 36, // A14, PC4 + 37 // A15, PC5 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ + +WEAK void SetSysClock_PLL_HSE(void) { + + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + + /**Configure the main internal regulator output voltage + */ + __HAL_RCC_PWR_CLK_ENABLE(); + + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = (HSE_VALUE / 1000000); + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + _Error_Handler(__FILE__, __LINE__); + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) + _Error_Handler(__FILE__, __LINE__); +} + +WEAK void SystemClock_Config(void) { + SetSysClock_PLL_HSE(); + + /* Ensure CCM RAM clock is enabled */ + __HAL_RCC_CCMDATARAMEN_CLK_ENABLE(); + + /* Output clock on MCO2 pin(PC9) for debugging purpose */ + //HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_SYSCLK, RCC_MCODIV_4); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.h new file mode 100644 index 0000000000..ec6e498b21 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/variant.h @@ -0,0 +1,148 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library 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 Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins (STM32F405RG and STM32F415RG) + *----------------------------------------------------------------------------*/ + +// | DIGITAL | ANALOG IN | ANALOG OUT | UART/USART | TWI | SPI | SPECIAL | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PA0 PIN_A0 // | 0 | A0 (ADC1) | | UART4_TX | | | | +#define PA1 PIN_A1 // | 1 | A1 (ADC1) | | UART4_RX | | | | +#define PA2 PIN_A2 // | 2 | A2 (ADC1) | | USART2_TX | | | | +#define PA3 PIN_A3 // | 3 | A3 (ADC1) | | USART2_RX | | | | +#define PA4 PIN_A4 // | 4 | A4 (ADC1) | DAC_OUT1 | | | SPI1_SS, (SPI3_SS) | | +#define PA5 PIN_A5 // | 5 | A5 (ADC1) | DAC_OUT2 | | | SPI1_SCK | | +#define PA6 PIN_A6 // | 6 | A6 (ADC1) | | | | SPI1_MISO | | +#define PA7 PIN_A7 // | 7 | A7 (ADC1) | | | | SPI1_MOSI | | +#define PA8 8 // | 8 | | | | TWI3_SCL | | | +#define PA9 9 // | 9 | | | USART1_TX | | SPI2_SCK | | +#define PA10 10 // | 10 | | | USART1_RX | | | | +#define PA11 11 // | 11 | | | | | | | +#define PA12 12 // | 12 | | | | | | | +#define PA13 13 // | 13 | | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | | SPI3_SS, (SPI1_SS) | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PB0 PIN_A8 // | 16 | A8 (ADC1) | | | | | | +#define PB1 PIN_A9 // | 17 | A9 (ADC1) | | | | | | +#define PB2 18 // | 18 | | | | | | BOOT1 | +#define PB3 19 // | 19 | | | | | SPI3_SCK, (SPI1_SCK) | | +#define PB4 20 // | 20 | | | | | SPI3_MISO, (SPI1_MISO) | | +#define PB5 21 // | 21 | | | | | SPI3_MOSI, (SPI1_MOSI) | | +#define PB6 22 // | 22 | | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | | TWI1_SDA | SPI2_SS | | +#define PB10 26 // | 26 | | | USART3_TX | TWI2_SCL | SPI2_SCK | | +#define PB11 27 // | 27 | | | USART3_RX | TWI2_SDA | | | +#define PB12 28 // | 28 | | | | | SPI2_SS | | +#define PB13 29 // | 29 | | | | | SPI2_SCK | | +#define PB14 30 // | 30 | | | | | SPI2_MISO | | +#define PB15 31 // | 31 | | | | | SPI2_MOSI | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PC0 PIN_A10 // | 32 | A10 (ADC1) | | | | | | +#define PC1 PIN_A11 // | 33 | A11 (ADC1) | | | | | | +#define PC2 PIN_A12 // | 34 | A12 (ADC1) | | | | SPI2_MISO | | +#define PC3 PIN_A13 // | 35 | A13 (ADC1) | | | | SPI2_MOSI | | +#define PC4 PIN_A14 // | 36 | A14 (ADC1) | | | | | | +#define PC5 PIN_A15 // | 37 | A15 (ADC1) | | | | | | +#define PC6 38 // | 38 | | | USART6_TX | | | | +#define PC7 39 // | 39 | | | USART3_RX | | SPI2_SCK | | +#define PC8 40 // | 40 | | | | | | | +#define PC9 41 // | 41 | | | | TWI3_SDA | | | +#define PC10 42 // | 42 | | | USART3_TX, (UART4_TX) | | SPI3_SCK | | +#define PC11 43 // | 43 | | | USART3_RX, (UART4_RX) | | SPI3_MISO | | +#define PC12 44 // | 44 | | | UART5_TX | | SPI3_MOSI | | +#define PC13 45 // | 45 | | | | | | | +#define PC14 46 // | 46 | | | | | | OSC32_IN | +#define PC15 47 // | 47 | | | | | | OSC32_OUT | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PD2 48 // | 48 | | | UART5_RX | | | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PH0 49 // | 49 | | | | | | OSC_IN | +#define PH1 50 // | 50 | | | | | | OSC_OUT | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| + +/// This must be a literal +#define NUM_DIGITAL_PINS 51 +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN +#define LED_BUILTIN PA5 +#endif +#define LED_GREEN LED_BUILTIN + +// On-board user button +#ifndef USER_BTN +#define USER_BTN PC13 +#endif + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#define TIMER_TONE TIM5 +#define TIMER_SERVO TIM7 + +// UART Definitions +// Define here Serial instance number to map on Serial generic name +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial' instance +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +/* Extra HAL modules */ +#define HAL_DAC_MODULE_ENABLED + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #define SERIAL_PORT_MONITOR Serial + #define SERIAL_PORT_HARDWARE Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index e2e93eaa43..29dd933078 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -439,3 +439,17 @@ extends = env:mks_monster8_usb_flash_drive build_flags = ${env:mks_monster8_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC build_unflags = -DUSBD_USE_CDC + +# +# TH3D EZBoard Lite v2.0 (STM32F405RGT6 ARM Cortex-M4) +# +[env:TH3D_EZBoard_Lite_V2] +platform = ${common_stm32.platform} +extends = stm32_variant +board = genericSTM32F405RG +board_build.variant = MARLIN_TH3D_EZBOARD_LITE_V2 +board_build.offset = 0xC000 +board_upload.offset_address = 0x0800C000 +build_flags = ${stm32_variant.build_flags} -DHSE_VALUE=12000000U -O0 +debug_tool = stlink +upload_protocol = stlink From 4f35858c9ef4de8e291d8006041aca0969c9d825 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Aug 2021 18:07:41 -0500 Subject: [PATCH 0579/2168] =?UTF-8?q?=F0=9F=8E=A8=20EXP1/2=20headers=20and?= =?UTF-8?q?=20pins=20cleanup=20(#22628)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32F1/onboard_sd.cpp | 2 +- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 3 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 8 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 72 +++---- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 5 +- Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 3 +- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 3 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 167 ++++++++------- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 3 +- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h | 3 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 +- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 3 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 123 ++++++----- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 6 +- Marlin/src/pins/ramps/pins_RAMPS.h | 4 +- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 2 - Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 6 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 8 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 1 - Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 75 +++++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 4 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 18 +- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 6 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 6 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 6 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 6 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 4 +- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 2 +- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 109 ++++++---- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 6 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 24 ++- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 174 ++++++++-------- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 195 ++++++++++-------- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 16 +- 40 files changed, 593 insertions(+), 496 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index e26947145d..df98c2c057 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -158,7 +158,7 @@ static void sd_power_on() { ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setDataMode(SPI_MODE0); - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); // Set CS# high + CS_HIGH(); } // Disable SPI function diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 5131069f6b..9211a6a793 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -85,7 +85,6 @@ #define FAN1_PIN P0_26 #define LCD_SDSS P0_16 // LCD SD chip select -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #if ENABLED(AZSMZ_12864) #define BEEPER_PIN P1_30 @@ -109,6 +108,7 @@ #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." 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 c6a44123a0..c01afccaca 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -54,7 +54,7 @@ /** - * ______ ______ + * ------ ------ * NC | 1 2 | GND 5V | 1 2 | GND * RESET | 3 4 | 1.31 NC | 3 4 | NC * 0.18 | 5 6 3.25 NC | 5 6 0.15 @@ -82,7 +82,6 @@ #define EXP2_09_PIN P0_15 #define EXP2_10_PIN P0_17 - /** * LCD / Controller * diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index b922f057f1..1ce6aed700 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -184,7 +184,7 @@ #endif /** - * ______ ______ + * ------ ------ * NC | 1 2 | GND 5V | 1 2 | GND * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) @@ -230,7 +230,7 @@ * The ANET_FULL_GRAPHICS_LCD connector plug: * * BEFORE AFTER - * ______ ______ + * ------ ------ * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 @@ -386,11 +386,11 @@ /** * Creality Ender-2 display pinout - * _____ + * ----- * 5V | 1 2 | GND * (MOSI) P1_23 | 3 4 | P1_22 (LCD_CS) * (LCD_A0) P1_21 | 5 6 P1_20 (BTN_EN2) - * RESET P1_19 | 7 8 | P1_18 (BTN_EN1) + * (RESET) P1_19 | 7 8 | P1_18 (BTN_EN1) * (BTN_ENC) P0_28 | 9 10| P1_30 (SCK) * ----- * EXP1 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 2c9e608e49..ae6456a3ce 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -239,14 +239,14 @@ #define TMC_BAUD_RATE 19200 #endif -/* _____ _____ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 1.23 | 3 4 | 1.22 - * 0.18 | 5 6 3.25 1.21 | 5 6 1.20 - * 0.16 | 7 8 | 3.26 1.19 | 7 8 | 1.18 - * 0.15 | 9 10| 0.17 0.28 | 9 10| 1.30 - * ----- ----- - * EXP2 EXP1 +/** ------ ------ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | 1.31 1.23 | 3 4 | 1.22 + * 0.18 | 5 6 3.25 1.21 | 5 6 1.20 + * 0.16 | 7 8 | 3.26 1.19 | 7 8 | 1.18 + * 0.15 | 9 10| 0.17 0.28 | 9 10| 1.30 + * ------ ------ + * EXP2 EXP1 */ #define EXP1_03_PIN P1_23 @@ -267,27 +267,15 @@ #define EXP2_09_PIN P0_15 #define EXP2_10_PIN P0_17 -/** - * _____ _____ - * NC | · · | GND 5V | · · | GND - * RESET | · · | 1.31 (SD_DETECT) (LCD_D7) 1.23 | · · | 1.22 (LCD_D6) - * (MOSI) 0.18 | · · 3.25 (BTN_EN2) (LCD_D5) 1.21 | · · 1.20 (LCD_D4) - * (SD_SS) 0.16 | · · | 3.26 (BTN_EN1) (LCD_RS) 1.19 | · · | 1.18 (LCD_EN) - * (SCK) 0.15 | · · | 0.17 (MISO) (BTN_ENC) 0.28 | · · | 1.30 (BEEPER) - * ----- ----- - * EXP2 EXP1 - */ - -#if ENABLED(DWIN_CREALITY_LCD) +#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD - #define BTN_ENC P1_20 - #define BTN_EN1 P1_23 - #define BTN_EN2 P1_22 + #define BTN_ENC EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN #ifndef BEEPER_PIN - #define BEEPER_PIN P1_21 - #undef SPEAKER + #define BEEPER_PIN EXP1_05_PIN #endif #elif HAS_WIRED_LCD && !BTT_MOTOR_EXPANSION @@ -304,13 +292,13 @@ * The ANET_FULL_GRAPHICS_LCD_ALT_WIRING connector plug: * * BEFORE AFTER - * _____ _____ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * open | 7 8 | BTN_ENC open | 7 8 | BTN_ENC - * CLK | 9 10| Beeper CLK | 9 10| Beeper - * ----- ----- + * ------ ------ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * open | 7 8 | BTN_ENC open | 7 8 | BTN_ENC + * CLK | 9 10| BEEPER CLK | 9 10| BEEPER + * ------ ------ * LCD LCD */ @@ -337,15 +325,15 @@ * * The ANET_FULL_GRAPHICS_LCD connector plug: * - * BEFORE AFTER - * ______ ______ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC - * CLK | 9 10 | Beeper open | 9 10 | Beeper - * ------ ------ - * LCD LCD + * BEFORE AFTER + * ------ ------ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC + * CLK | 9 10 | BEEPER open | 9 10 | BEEPER + * ------ ------ + * LCD LCD */ #define LCD_PINS_RS EXP1_03_PIN @@ -372,7 +360,7 @@ #elif ENABLED(ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout - * ______ + * ------ * 5V | 1 2 | GND * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) * (LCD_A0) 1.21 | 5 6 1.20 (BTN_EN2) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 9e04fc0479..52f34ed0f0 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -126,8 +126,6 @@ #endif #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) && ENABLED(SKR_USE_LCD_SD_CARD_PINS_FOR_CS) #error "SDCARD_CONNECTION must not be 'LCD' with SKR_USE_LCD_SD_CARD_PINS_FOR_CS." #endif @@ -145,13 +143,14 @@ #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** ______ ______ + /** ------ ------ * NC | 1 2 | GND NC | 1 2 | GND * NC | 3 4 | M1EN M2EN | 3 4 | M3EN * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 1feaeb13b5..eee3ede713 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -155,8 +155,6 @@ #define SDCARD_CONNECTION LCD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) #define SD_SCK_PIN P0_15 #define SD_MISO_PIN P0_17 @@ -167,5 +165,6 @@ #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index a2235dc28a..d1d1eccc45 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -165,8 +165,6 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(CUSTOM_CABLE) /** @@ -199,6 +197,7 @@ #define SD_SS_PIN P0_28 #else #define SD_DETECT_PIN P0_27 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #endif #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 449d9a93ce..49dad8b07b 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -215,7 +215,7 @@ // Power Supply Control // #if ENABLED(MKS_PWC) - #define PS_ON_PIN P2_00 // SERVO + #define PS_ON_PIN P2_00 // SERVO1 #define KILL_PIN P1_24 // Z+ #define KILL_PIN_STATE HIGH #endif @@ -228,42 +228,79 @@ #define LED3_PIN P1_20 #define LED4_PIN P1_21 -/** - * _____ _____ - * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) - * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | · · 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · 0.9 (SD_MOSI) - * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST - * GND | · · | 5V GND | · · | NC - * ----- ----- - * EXP1 EXP2 +/** ------ ------ + * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) + * (LCD_D4) 0.15 | 6 5 0.17 (LCD_D5) (BTN_EN2) 3.26 | 6 5 0.9 (SD_MOSI) + * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ + +#define EXP1_03_PIN P1_22 +#define EXP1_04_PIN P1_00 +#define EXP1_05_PIN P0_17 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_16 +#define EXP1_08_PIN P0_18 +#define EXP1_09_PIN P1_30 +#define EXP1_10_PIN P1_31 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN P0_27 +#define EXP2_05_PIN P0_09 +#define EXP2_06_PIN P3_26 +#define EXP2_07_PIN P0_28 +#define EXP2_08_PIN P3_25 +#define EXP2_09_PIN P0_07 +#define EXP2_10_PIN P0_08 + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #if SD_CONNECTION_IS(ONBOARD) + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card + #define SD_SS_PIN ONBOARD_SD_CS_PIN + #else + #define SD_SS_PIN EXP2_07_PIN + #endif +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "No custom SD drive cable defined for this board." +#endif + #if HAS_WIRED_LCD - #define BEEPER_PIN P1_31 - #define BTN_ENC P1_30 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS P1_00 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 P0_18 - #define BTN_EN2 P0_15 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE P1_22 - #define LCD_PINS_D4 P0_17 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN P1_00 - #define TFT_A0_PIN P1_22 - #define TFT_DC_PIN P1_22 - #define TFT_MISO_PIN P0_08 - #define TFT_BACKLIGHT_PIN P0_18 - #define TFT_RESET_PIN P0_16 + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_A0_PIN EXP1_03_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_RESET_PIN EXP1_07_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN P0_17 - #define TOUCH_CS_PIN P0_15 + #define TOUCH_INT_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_06_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 @@ -278,8 +315,8 @@ #define TFT_QUEUE_SIZE 6144 #endif - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #elif IS_TFTGLCD_PANEL @@ -287,74 +324,74 @@ #undef BTN_ENC #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_25 + #define TFTGLCD_CS EXP2_08_PIN #endif #else - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_SDSS P0_28 + #define LCD_SDSS EXP2_07_PIN #if ENABLED(MKS_12864OLED_SSD1306) - #define LCD_PINS_DC P0_17 - #define DOGLCD_CS P0_16 + #define LCD_PINS_DC EXP1_05_PIN + #define DOGLCD_CS EXP1_07_PIN #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_SCK EXP1_06_PIN + #define DOGLCD_MOSI EXP1_08_PIN - #define LCD_PINS_RS P1_00 - #define LCD_PINS_D7 P1_22 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #define KILL_PIN -1 // NC #else // !MKS_12864OLED_SSD1306 - #define LCD_PINS_RS P0_16 + #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS P0_18 - #define DOGLCD_A0 P0_16 - #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P0_09 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN P0_15 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P0_17 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_00 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_22 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P0_17 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P0_17 - #define DOGLCD_A0 P1_00 + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 P0_17 - #define LCD_PINS_D6 P1_00 - #define LCD_PINS_D7 P1_22 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -370,29 +407,9 @@ #endif // HAS_WIRED_LCD -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - -#if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN P0_27 - #define SD_SCK_PIN P0_07 - #define SD_MISO_PIN P0_08 - #define SD_MOSI_PIN P0_09 - #if SD_CONNECTION_IS(ONBOARD) - #define SD_SS_PIN ONBOARD_SD_CS_PIN - #else - #define SD_SS_PIN P0_28 - #endif -#elif SD_CONNECTION_IS(CUSTOM_CABLE) - #error "No custom SD drive cable defined for this board." -#endif - // // Other Pins // //#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) //#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -//#define PS_ON_PIN P1_23 // SERVO P1.23 +//#define PS_ON_PIN P1_23 // SERVO0 P1.23 diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 62127f5504..ce5d5ad7c6 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -455,8 +455,6 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) #define SD_SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 #define SD_MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 @@ -467,6 +465,7 @@ #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index 80a91d2cbc..f3ecebde46 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -198,8 +198,6 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) #define SD_SCK_PIN P0_15 #define SD_MISO_PIN P0_17 @@ -210,6 +208,7 @@ #define SD_SCK_PIN P0_07 #define SD_MISO_PIN P0_08 #define SD_MOSI_PIN P0_09 + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 44ceb9b7cc..c2d2621bc1 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -179,7 +179,7 @@ #endif /** - * ______ + * ------ * 5V | 1 2 | GND * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) @@ -203,7 +203,7 @@ /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo - * ______ ______ RX 8 --> 5 P0_15 + * ------ ------ RX 8 --> 5 P0_15 * 5V | 1 2 | GND 5V | 1 2 | GND TX 7 --> 9 P0_16 * (BTN_E1) A | 3 4 | B (BTN_E2) (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) BEEPER 5 --> 10 P2_08 * BEEPER | 5 6 ENT (BTN_ENC) (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 57b4521453..ea2e0b7082 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -229,8 +229,6 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) #define SD_SCK_PIN P0_07 // (52) system defined J3-9 & AUX-3 #define SD_MISO_PIN P0_08 // (50) system defined J3-10 & AUX-3 @@ -239,6 +237,7 @@ #define SD_SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin #else #undef SD_DETECT_PIN + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index ff7aa11daf..a8a4d2de4e 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -231,7 +231,7 @@ // Power Supply Control // #if ENABLED(MKS_PWC) - #define PS_ON_PIN P2_00 // SERVO + #define PS_ON_PIN P2_00 // SERVO1 #define KILL_PIN P1_24 // Z+ #define KILL_PIN_STATE HIGH #endif @@ -256,7 +256,7 @@ #endif /** - * _____ _____ + * ----- ----- * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 0.9 (SD_MOSI) @@ -265,60 +265,78 @@ * ----- ----- * EXP1 EXP2 */ +#define EXP1_03_PIN P1_22 +#define EXP1_04_PIN P1_00 +#define EXP1_05_PIN P0_17 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_16 +#define EXP1_08_PIN P0_18 +#define EXP1_09_PIN P1_30 +#define EXP1_10_PIN P1_31 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN P0_27 +#define EXP2_05_PIN P0_09 +#define EXP2_06_PIN P3_26 +#define EXP2_07_PIN P0_28 +#define EXP2_08_PIN P3_25 +#define EXP2_09_PIN P0_07 +#define EXP2_10_PIN P0_08 + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_25 + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN P0_27 + #define SD_DETECT_PIN EXP2_04_PIN #elif HAS_WIRED_LCD - #define BEEPER_PIN P1_31 - #define BTN_ENC P1_30 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS P1_00 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 P0_18 - #define BTN_EN2 P0_15 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE P1_22 - #define LCD_PINS_D4 P0_17 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #else - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_SDSS P0_28 + #define LCD_SDSS EXP2_07_PIN #if ENABLED(MKS_12864OLED_SSD1306) - #define LCD_PINS_DC P0_17 - #define DOGLCD_CS P0_16 + #define LCD_PINS_DC EXP1_05_PIN + #define DOGLCD_CS EXP1_07_PIN #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_SCK EXP1_06_PIN + #define DOGLCD_MOSI EXP1_08_PIN - #define LCD_PINS_RS P1_00 - #define LCD_PINS_D7 P1_22 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #define KILL_PIN -1 // NC #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN P1_00 - #define TFT_A0_PIN P1_22 - #define TFT_DC_PIN P1_22 - #define TFT_MISO_PIN P0_08 - #define TFT_BACKLIGHT_PIN P0_18 - #define TFT_RESET_PIN P0_16 + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_A0_PIN EXP1_03_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_RESET_PIN EXP1_07_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN P0_17 - #define TOUCH_CS_PIN P0_15 + #define TOUCH_INT_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_06_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 @@ -335,50 +353,50 @@ #else // !MKS_12864OLED_SSD1306 - #define LCD_PINS_RS P0_16 + #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS P0_18 - #define DOGLCD_A0 P0_16 - #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P0_09 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN P0_15 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P0_17 + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_00 + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_22 + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P0_17 + #define NEOPIXEL_PIN EXP1_05_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS P0_17 - #define DOGLCD_A0 P1_00 + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 P0_17 - #define LCD_PINS_D6 P1_00 - #define LCD_PINS_D7 P1_22 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -398,17 +416,16 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card - #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN P0_27 - #define SD_SCK_PIN P0_07 - #define SD_MISO_PIN P0_08 - #define SD_MOSI_PIN P0_09 + #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN #if SD_CONNECTION_IS(ONBOARD) + #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #else - #define SD_SS_PIN P0_28 + #define SD_SS_PIN EXP2_07_PIN #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." @@ -419,4 +436,4 @@ // //#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) //#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -//#define PS_ON_PIN P1_23 // SERVO P1.23 +//#define PS_ON_PIN P1_23 // SERVO0 P1.23 diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 22a6613329..dc7dcd6db6 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -156,7 +156,7 @@ // /** - * ______ + * ------ * 5V | 1 2 | GND * P0_18 | 3 4 | P0_16 * P0_15 | 5 6 P3_25 @@ -181,7 +181,7 @@ #define EXP1_10_PIN P1_31 #if ENABLED(CR10_STOCKDISPLAY) - /** ______ + /** ------ * 5V | 1 2 | GND * LCD_EN | 3 4 | LCD_RS * LCD_D4 | 5 6 EN2 @@ -196,7 +196,7 @@ #define KILL_PIN EXP1_07_PIN #elif ENABLED(MKS_MINI_12864) - /** ______ + /** ------ * 5V | 1 2 | GND * SPI-MOSI | 3 4 | SPI-CS * A0 | 5 6 EN2 diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index b141fdbf85..1683ccf5c8 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -434,7 +434,7 @@ /** * LCD adapter. Please note: These comes in two variants. The socket keys can be * on either side, and may be backwards on some boards / displays. - * _____ _____ + * ----- ----- * D37 |10 9 | D35 (MISO) D50 |10 9 | D52 (SCK) * D17 | 8 7 | D16 D31 | 8 7 | D53 * D23 6 5 D25 D33 6 5 D51 (MOSI) @@ -778,7 +778,7 @@ * FYSETC TFT-81050 display pinout * * Board Display - * _____ _____ + * ----- ----- * (SCK) D52 | 1 2 | D50 (MISO) MISO | 1 2 | SCK * (SD_CS) D53 | 3 4 | D33 (BNT_EN2) (BNT_EN2) MOD_RESET | 3 4 | SD_CS * (MOSI) D51 | 5 6 D31 (BNT_EN1) (BNT_EN1) LCD_CS | 5 6 MOSI diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 225392de1b..d4915c9cca 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -137,7 +137,7 @@ /** * EXP1 Connector EXP1 as CR10 STOCKDISPLAY - * _____ _____ + * ----- ----- * PA4 | 6 5 | PC0 BEEPER_PIN | 6 5 | BTN_ENC * PD3 | 7 4 | RESET BTN_EN1 | 7 4 | RESET * PD2 8 3 | PA1 BTN_EN2 8 3 | LCD_PINS_D4 (ST9720 CLK) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index bd5f2068f1..c614a2dbb9 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -158,8 +158,6 @@ // SD Card // -#define HAS_ONBOARD_SD - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 6ed2869141..dae43d3c13 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -156,7 +156,7 @@ #define USB_CONNECT_INVERTING false /** - * _____ + * ----- * 5V | 1 2 | GND * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) @@ -195,7 +195,7 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout - * _____ + * ----- * 5V | 1 2 | GND * (MOSI) PB7 | 3 4 | PB8 (LCD_RS) * (LCD_A0) PB9 | 5 6 PA10 (BTN_EN2) @@ -229,7 +229,7 @@ /** FYSETC TFT TFT81050 display pinout * * Board Display - * _____ _____ + * ----- ----- * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 8f305542a9..fe4fd3a4a7 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -117,7 +117,7 @@ /** * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 - * ______ ______ + * ------ ------ * 5V | 1 2 | GND 5V | 1 2 | GND * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) @@ -134,7 +134,7 @@ #define EXP1_3 PB7 #endif -#if ENABLED(DWIN_CREALITY_LCD) +#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) /** * ------ ------ ------ * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC @@ -205,7 +205,7 @@ * TFTGLCD_PANEL_SPI display pinout * * Board Display - * ______ ______ + * ------ ------ * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) @@ -248,7 +248,7 @@ * FYSETC TFT TFT81050 display pinout * * Board Display - * ______ ______ + * ------ ------ * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 6b3d2832d0..441f9350e3 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -98,7 +98,7 @@ // /** - * _____ _____ + * ----- ----- * NC | · · | GND 5V | · · | GND * RESET | · · | PB9 (SD_DETECT) (LCD_D7) PC14 | · · | PC15 (LCD_D6) * (MOSI) PB5 | · · | PB8 (BTN_EN2) (LCD_D5) PB7 | · · | PC13 (LCD_D4) diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 7b61f55d4f..c2edcd3678 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -122,7 +122,7 @@ #define NEOPIXEL_PIN PC7 // The NEOPIXEL LED driving pin /** - * 1 _____ 2 + * 1 ----- 2 * PB5 | · · | PB6 * PA2 | · · | RESET * PA3 | · · | PB8 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 0437156c0c..056fdf4c29 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -194,7 +194,6 @@ //#define LCD_LED_PIN PB2 #ifndef BEEPER_PIN #define BEEPER_PIN PB13 - //#undef SPEAKER #endif #elif ENABLED(DWIN_VET6_CREALITY_LCD) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index f971f65628..7694130a3e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -156,35 +156,67 @@ #define SDIO_SUPPORT #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer -#if ENABLED(CR10_STOCKDISPLAY) && NONE(RET6_12864_LCD, VET6_12864_LCD) - #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." -#endif +#if ENABLED(CR10_STOCKDISPLAY) -#if ENABLED(RET6_12864_LCD) + #if ENABLED(RET6_12864_LCD) - // RET6 12864 LCD - #define LCD_PINS_RS PB12 - #define LCD_PINS_ENABLE PB15 - #define LCD_PINS_D4 PB13 + /** + * RET6 12864 LCD + * ------ + * PC6 |10 9 | PB2 + * PB10 | 8 7 | PE8 + * PB14 | 6 5 | PB13 + * PB12 | 4 3 | PB15 + * GND | 2 1 | 5V + * ------ + * EXP1 + */ + #define EXP1_03_PIN PB15 + #define EXP1_04_PIN PB12 + #define EXP1_05_PIN PB13 + #define EXP1_06_PIN PB14 + #define EXP1_07_PIN PE8 + #define EXP1_08_PIN PB10 + #define EXP1_09_PIN PB2 + #define EXP1_10_PIN PC6 - #define BTN_ENC PB2 - #define BTN_EN1 PB10 - #define BTN_EN2 PB14 + #define BEEPER_PIN EXP1_10_PIN - #define BEEPER_PIN PC6 + #elif ENABLED(VET6_12864_LCD) -#elif ENABLED(VET6_12864_LCD) + /** + * VET6 12864 LCD + * ------ + * ? |10 9 | PC5 + * PB10 | 8 7 | ? + * PA6 | 6 5 | PA5 + * PA4 | 4 3 | PA7 + * GND | 2 1 | 5V + * ------ + * EXP1 + */ + #define EXP1_03_PIN PA7 + #define EXP1_04_PIN PA4 + #define EXP1_05_PIN PA5 + #define EXP1_06_PIN PA6 + #define EXP1_07_PIN -1 + #define EXP1_08_PIN PB10 + #define EXP1_09_PIN PC5 + #define EXP1_10_PIN -1 - // VET6 12864 LCD - #define LCD_PINS_RS PA4 - #define LCD_PINS_ENABLE PA7 - #define LCD_PINS_D4 PA5 + #else + #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." + #endif - #define BTN_ENC PC5 - #define BTN_EN1 PB10 - #define BTN_EN2 PA6 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN -#elif ENABLED(DWIN_CREALITY_LCD) + #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + +#elif EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD #define BTN_ENC PB14 @@ -194,7 +226,6 @@ //#define LCD_LED_PIN PB2 #ifndef BEEPER_PIN #define BEEPER_PIN PB13 - #undef SPEAKER #endif #elif ENABLED(DWIN_VET6_CREALITY_LCD) diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 552ad9ac57..2060ad86fe 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -132,8 +132,8 @@ /* * EXP1 pinout for the LCD according to Fysetcs schematic for the Cheetah board -* _____ -* (Beeper) PC9 | 1 2 | PC12 (BTN_ENC) +* ----- +* (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) * (BTN_EN2) PC11 | 3 4 | PB14 (LCD_RS / MISO) * (BTN_EN1) PC10 5 6 | PB13 (SCK) * (LCD_EN) PB12 | 7 8 | PB15 (MOSI) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index c568e42df2..60d342c602 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -133,7 +133,7 @@ #endif /** - * _____ _____ _____ + * ----- ----- ----- * (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) 5V | 1 2 | GND * (LCD_EN) PA4 | 3 4 | PA5 (LCD_RS) (BTN_EN1) PB11 | 3 4 | PA15 (SD_SS) (LCD_EN) PA4 | 3 4 | PA5 (LCD_RS) * (LCD_D4) PA6 | 5 6 PA7 (LCD_D5) (BTN_EN2) PB0 | 5 6 PB15 (SD_MOSI) (LCD_D4) PA6 | 5 6 PB0 (BTN_EN2) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 1f3efee6e5..6e19b441c6 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -299,14 +299,16 @@ #endif -#ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #endif #endif #define HAS_SPI_FLASH 1 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index bad5db7125..0d413d3651 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -201,9 +201,9 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_06_PIN #define BTN_ENC EXP1_04_PIN - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(200) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(200) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index 8a6bb4b5f8..3674f10ce7 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -332,9 +332,9 @@ #endif #if HAS_MARLINUI_U8GLIB - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif // Remap SERVO0 PIN for BLTouch diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index 5bbf43bbfa..017195edee 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -305,9 +305,9 @@ #endif #if HAS_MARLINUI_U8GLIB - #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns - #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns + #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns + #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns #endif // Remap SERVO0 PIN for BLTouch diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 481c38f515..a768088c37 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -183,7 +183,7 @@ /** * BTT E3 RRF - * _____ + * ----- * 5V | 1 2 | GND * (LCD_EN) PE11 | 3 4 | PB1 (LCD_RS) * (LCD_D4) PE10 | 5 6 PB2 (BTN_EN2) @@ -248,7 +248,7 @@ * TFTGLCD_PANEL_SPI display pinout * * Board Display - * _____ _____ + * ----- ----- * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) LCD_CS | 3 4 | SD_CS (PB2) * (FREE) PE10 | 5 6 | PB2 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) @@ -303,7 +303,7 @@ /** FYSETC TFT TFT81050 display pinout * * Board Display - * _____ _____ + * ----- ----- * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) MOD_RESET | 3 4 | SD_CS (PB2) * (FREE) PE10 | 5 6 | PB2 (SD_CS) (PB1) LCD_CS | 5 6 | MOSI (SPI1-MOSI) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 92e7b5d374..ec9ca32f7e 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -311,7 +311,7 @@ #endif /** - * ______ ______ + * ------ ------ * NC | 1 2 | GND 5V | 1 2 | GND * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) @@ -366,7 +366,7 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** - * ______ ______ + * ------ ------ * NC | 1 2 | GND NC | 1 2 | GND * NC | 3 4 | M1EN M2EN | 3 4 | M3EN * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index e43cc4e5a0..6daa34e059 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -367,7 +367,7 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** _____ _____ + /** ----- ----- * NC | . . | GND NC | . . | GND * NC | . . | M1EN M2EN | . . | M3EN * M1STP | . . M1DIR M1RX | . . M1DIAG diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index dc2ee99aff..e049f8fbd9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -350,7 +350,7 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** _____ _____ + /** ----- ----- * NC | . . | GND NC | . . | GND * NC | . . | M1EN M2EN | . . | M3EN * M1STP | . . M1DIR M1RX | . . M1DIAG diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 728e753543..27ad7179df 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -175,17 +175,39 @@ #define FAN4_PIN PE13 #define FAN5_PIN PB11 +/** + * ------ ------ + * PB10 |10 9 | PE15 PB14 |10 9 | PB13 + * PE14 | 8 7 | PE12 PC5 | 8 7 | PF11 + * PE10 6 5 | PE9 PC4 6 5 | PB15 + * PE8 | 4 3 | PE7 PB2 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 + */ + +#define EXP1_03_PIN PE7 +#define EXP1_04_PIN PE8 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE10 +#define EXP1_07_PIN PE12 +#define EXP1_08_PIN PE14 +#define EXP1_09_PIN PE15 +#define EXP1_10_PIN PB10 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB2 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PC4 +#define EXP2_07_PIN PF11 +#define EXP2_08_PIN PC5 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 + // // Onboard SD support // - -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 //#define SD_CARD_DETECT_PIN PC13 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD @@ -194,37 +216,37 @@ #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - #ifndef SDIO_SUPPORT + + #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif #elif SD_CONNECTION_IS(LCD) - #define SD_SCK_PIN PB13 - #define SD_MISO_PIN PB14 - #define SD_MOSI_PIN PB15 - #define SDSS PF11 - #define SD_DETECT_PIN PB2 + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SDSS EXP2_07_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif // // Trinamic Software SPI // - #if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 + #ifndef TMC_SW_SCK + #define TMC_SW_SCK EXP2_09_PIN #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 + #define TMC_SW_MISO EXP2_10_PIN #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI EXP2_05_PIN #endif #endif @@ -264,17 +286,18 @@ // // LCD / Controller // - -#define BEEPER_PIN PB10 -#define LCD_PINS_RS PE12 -#define LCD_PINS_ENABLE PE14 -#define LCD_PINS_D4 PE10 -#define LCD_PINS_D5 PE9 -#define LCD_PINS_D6 PE8 -#define LCD_PINS_D7 PE7 -#define BTN_EN1 PC4 -#define BTN_EN2 PC5 -#define BTN_ENC PE15 +#if IS_RRD_SC + #define BEEPER_PIN EXP1_10_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_08_PIN + #define BTN_ENC EXP1_09_PIN +#endif // // Filament runout @@ -285,12 +308,14 @@ // // ST7920 Delays // -#ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) -#endif -#ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) -#endif -#ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index ef1c14aae0..b50f1e4966 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -138,7 +138,7 @@ #endif /** - * _____ _____ + * ----- ----- * 5V | 1 2 | GND 5V | 1 2 | GND * RESET | 3 4 | PC3 (SD_DETECT) (LCD_D7) PB7 | 3 4 | PB6 (LCD_D6) * (SD_MOSI) PA7 5 6 | PC11 (BTN_EN2) (LCD_D5) PB14 5 6 | PB13 (LCD_D4) @@ -149,7 +149,7 @@ */ /** -* _____ +* ----- * (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) * (BTN_EN1) PC10 | 3 4 | PB14 (LCD_D5/MISO) * (BTN_EN2) PC11 5 6 | PB13 (LCD_D4/SCK) @@ -258,7 +258,7 @@ #define BOARD_ST7920_DELAY_2 DELAY_NS(48) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 9de62d372a..9ce8d33fa8 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -192,12 +192,12 @@ //#define KILL_PIN PC5 /** - * ______ ______ - * 5V | 1 2 | GND 5V | 1 2 | GND - * PD1 | 3 4 | PD0 RESET | 3 4 | PB10 - * PC12 | 5 6 PC10 PA7 | 5 6 PC7 - * PD2 | 7 8 | PC11 PA4 | 7 8 | PC6 - * PA8 | 9 10 | PC9 PA5 | 9 10 | PA6 + * ------ ------ + * PC9 |10 9 | PA8 PA6 |10 9 | PA5 + * PC11 | 8 7 | PD2 PC6 | 8 7 | PA4 + * PC10 | 6 5 PC12 PC7 | 6 5 PA7 + * PD0 | 4 3 | PD1 PB10 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ * EXP1 EXP2 */ @@ -315,9 +315,15 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) + #endif #endif #ifndef RGB_LED_R_PIN diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index adc8b2a8bd..38714d7da9 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -225,22 +225,46 @@ // Power Supply Control // #if ENABLED(MKS_PWC) - #define PS_ON_PIN PW_OFF - #define KILL_PIN PW_DET + #define PS_ON_PIN PW_OFF + #define KILL_PIN PW_DET #define KILL_PIN_STATE HIGH #endif // Random Info #define USB_SERIAL -1 // USB Serial +/** + * ------ ------ + * (BEEPER) PB2 |10 9 | PE10 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) + * (LCD_EN) PE11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PE9 | 8 7 | PA4 (SPI1 CS) + * (LCD_D4) PD9 | 6 5 PD8 (LCD_D5) (BTN_EN2) PE8 | 6 5 PA7 (SPI1 MOSI) + * (LCD_D6) PE15 | 4 3 | PE7 (LCD_D7) (SPI1_RS) PB11 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PE7 +#define EXP1_04_PIN PE15 +#define EXP1_05_PIN PD8 +#define EXP1_06_PIN PD9 +#define EXP1_07_PIN PD10 +#define EXP1_08_PIN PE11 +#define EXP1_09_PIN PE10 +#define EXP1_10_PIN PB2 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB11 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PE8 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PE9 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif -// -// Onboard SD card -// -// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI3 #define SD_SS_PIN -1 @@ -248,31 +272,49 @@ #define SD_SCK_PIN PC10 #define SD_MISO_PIN PC11 #define SD_MOSI_PIN PC12 - #define SD_DETECT_PIN PC4 -// -// LCD SD -// + #define SD_DETECT_PIN PC4 // SD_DETECT_PIN doesn't work with NO_SD_HOST_DRIVE disabled #elif SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS PA4 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PB11 + #define SDSS EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif -/** - * _____ _____ - * (BEEPER)PB2 | · · | PE10(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) - * (LCD_EN)PE11 | · · | PD10(LCD_RS) (BTN_EN1) PE9 | · · | PA4 (SPI1 CS) - * (LCD_D4)PD9 | · · PD8(LCD_D5) (BTN_EN2) PE8 | · · PA7 (SPI1 MOSI) - * (LCD_D6)PE15 | · · | PE7(LCD_D7) (SPI1_RS) PB11 | · · | RESET - * GND | · · | 5V GND | · · | 3.3V - *  ̄ ̄ ̄  ̄ ̄ ̄ - * EXP1 EXP2 - */ - #if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_RST_PIN EXP1_07_PIN + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_SIZE 14400 + #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 #endif @@ -289,51 +331,10 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif - #define TFT_CS_PIN PE15 - #define TFT_SCK_PIN PA5 - #define TFT_MISO_PIN PA6 - #define TFT_MOSI_PIN PA7 - #define TFT_DC_PIN PE7 - #define TFT_RST_PIN PD10 - #define TFT_A0_PIN TFT_DC_PIN - - #define TFT_RESET_PIN PD10 - #define TFT_BACKLIGHT_PIN PE11 - - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - - #define LCD_BACKLIGHT_PIN PE11 - #ifndef TFT_WIDTH - #define TFT_WIDTH 480 - #endif - #ifndef TFT_HEIGHT - #define TFT_HEIGHT 320 - #endif - - #define TOUCH_CS_PIN PD9 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define BTN_EN1 PE9 - #define BTN_EN2 PE8 - #define BEEPER_PIN PB2 - #define BTN_ENC PE10 - - #define LCD_READ_ID 0xD3 - #define LCD_USE_DMA_SPI - - #define TFT_BUFFER_SIZE 14400 - #elif HAS_WIRED_LCD - #define BEEPER_PIN PB2 - #define BTN_ENC PE10 - #define LCD_PINS_ENABLE PE11 - #define LCD_PINS_RS PD10 - #define BTN_EN1 PE9 - #define BTN_EN2 PE8 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) @@ -341,19 +342,19 @@ //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 #define DOGLCD_A0 PD11 - #define DOGLCD_CS PE15 - //#define DOGLCD_SCK PA5 - //#define DOGLCD_MOSI PA7 + #define DOGLCD_CS EXP1_04_PIN + //#define DOGLCD_SCK EXP2_09_PIN + //#define DOGLCD_MOSI EXP2_05_PIN #elif ENABLED(MKS_MINI_12864_V3) - #define DOGLCD_CS PE11 - #define DOGLCD_A0 PD10 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PD9 - #define NEOPIXEL_PIN PD8 - #define DOGLCD_MOSI PA7 - #define DOGLCD_SCK PA5 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif @@ -361,17 +362,24 @@ #else - #define LCD_PINS_D4 PD9 + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PD8 - #define LCD_PINS_D6 PE15 - #define LCD_PINS_D7 PE7 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #endif #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif // !MKS_MINI_12864 #endif // HAS_WIRED_LCD + +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, HAS_WIRED_LCD) + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN +#endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 8008310f5a..5b5c24899f 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -41,10 +41,12 @@ // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation -#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB -#define I2C_SCL_PIN PB6 -#define I2C_SDA_PIN PB7 +#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #define I2C_SCL_PIN PB6 + #define I2C_SDA_PIN PB7 +#endif // // Release PB4 (Z_DIR_PIN) from JTAG NRST role @@ -253,25 +255,11 @@ #define SD_DETECT_PIN PD12 #endif -// -// LCD SD -// -#if SD_CONNECTION_IS(LCD) - #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 -#endif - -// -// LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 -#define SPI_DEVICE 2 -#define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) + #define HAS_SPI_FLASH 1 + #define SPI_DEVICE 2 + #define SPI_FLASH_SIZE 0x1000000 #define SPI_FLASH_CS_PIN PB12 #define SPI_FLASH_MOSI_PIN PC3 #define SPI_FLASH_MISO_PIN PC2 @@ -279,17 +267,82 @@ #endif /** - * _____ _____ - * (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) - * (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS) - * (LCD_D4)PE14 | · · PE15(LCD_D5) (BTN_EN2) PE11 | · · PA7 (SPI1 MOSI) - * (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI1_RS) PE12 | · · | RESET - * GND | · · | 5V GND | · · | 3.3V - *  ̄ ̄ ̄  ̄ ̄ ̄ - * EXP1 EXP2 + * ------ ------ + * (BEEPER) PC5 |10 9 | PE13 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) + * (LCD_EN) PD13 | 8 7 | PC6 (LCD_RS) (BTN_EN1) PE8 | 8 7 | PE10 (SPI1 CS) + * (LCD_D4) PE14 6 5 | PE15 (LCD_D5) (BTN_EN2) PE11 6 5 | PA7 (SPI1 MOSI) + * (LCD_D6) PD11 | 4 3 | PD10 (LCD_D7) (SPI1_RS) PE12 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 */ +#define EXP1_03_PIN PD10 +#define EXP1_04_PIN PD11 +#define EXP1_05_PIN PE15 +#define EXP1_06_PIN PE14 +#define EXP1_07_PIN PC6 +#define EXP1_08_PIN PD13 +#define EXP1_09_PIN PE13 +#define EXP1_10_PIN PC5 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PE12 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PE11 +#define EXP2_07_PIN PE10 +#define EXP2_08_PIN PE8 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// SPI SD Card +// +#if SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN +#endif + +// +// LCD / Controller +// #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_RST_PIN EXP1_07_PIN + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_SIZE 14400 + #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 #endif @@ -306,93 +359,59 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif - #define TFT_CS_PIN PD11 - #define TFT_SCK_PIN PA5 - #define TFT_MISO_PIN PA6 - #define TFT_MOSI_PIN PA7 - #define TFT_DC_PIN PD10 - #define TFT_RST_PIN PC6 - #define TFT_A0_PIN TFT_DC_PIN - - #define TFT_RESET_PIN PC6 - #define TFT_BACKLIGHT_PIN PD13 - - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - - #define LCD_BACKLIGHT_PIN PD13 - #ifndef TFT_WIDTH - #define TFT_WIDTH 480 - #endif - #ifndef TFT_HEIGHT - #define TFT_HEIGHT 320 - #endif - - #define TOUCH_CS_PIN PE14 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI - - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 - - #define LCD_READ_ID 0xD3 - #define LCD_USE_DMA_SPI - - #define TFT_BUFFER_SIZE 14400 - #elif HAS_WIRED_LCD - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 PD11 - #define DOGLCD_CS PE15 - //#define DOGLCD_SCK PA5 - //#define DOGLCD_MOSI PA7 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + //#define DOGLCD_SCK EXP2_09_PIN + //#define DOGLCD_MOSI EXP2_05_PIN // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B //#undef SHOW_BOOTSCREEN #elif ENABLED(MKS_MINI_12864_V3) - #define DOGLCD_CS PD13 - #define DOGLCD_A0 PC6 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PE14 - #define NEOPIXEL_PIN PE15 - #define DOGLCD_MOSI PA7 - #define DOGLCD_SCK PA5 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif //#define LCD_SCREEN_ROT_180 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PE14 + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PE15 - #define LCD_PINS_D6 PD11 - #define LCD_PINS_D7 PD10 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #endif #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif // !MKS_MINI_12864 #endif // HAS_WIRED_LCD + +#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI, HAS_WIRED_LCD) + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_09_PIN +#endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index a56889fc7e..88e2d1804e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -258,13 +258,13 @@ #endif /** - * _____ _____ + * ----- ----- * (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) * (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS) * (LCD_D4)PE14 | · · | PE15(LCD_D5) (BTN_EN2) PE11 | · · | PA7 (SPI1 MOSI) * (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI DET) PE12 | · · | RESET * GND | · · | 5V GND | · · | 3.3V - *  ̄ ̄ ̄  ̄ ̄ ̄ + * ----- ----- * EXP1 EXP2 */ @@ -355,15 +355,9 @@ #define LCD_PINS_D7 PD10 #endif - #ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(600) - #endif + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif // !MKS_MINI_12864 From 7dec5c2674d0d3c7e2ddebba0b3568dfee18434d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 25 Aug 2021 00:57:08 +0000 Subject: [PATCH 0580/2168] [cron] Bump distribution date (2021-08-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ebd1fc9f97..11e6508ba7 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-24" +//#define STRING_DISTRIBUTION_DATE "2021-08-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6709b5b46b..c7e8ed9934 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 "2021-08-24" + #define STRING_DISTRIBUTION_DATE "2021-08-25" #endif /** From 71c96db932134ce845855fd51d910a86d044261e Mon Sep 17 00:00:00 2001 From: Ryan V1 <55478432+V1EngineeringInc@users.noreply.github.com> Date: Tue, 24 Aug 2021 20:34:10 -0700 Subject: [PATCH 0581/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Multi-Endstop=20?= =?UTF-8?q?stepping=20(#22625)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.cpp | 109 +++++++++++++++++++--------------- 1 file changed, 61 insertions(+), 48 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 882f5efc35..86e469827d 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -257,25 +257,30 @@ xyze_int8_t Stepper::count_direction{0}; }; #endif -#define DUAL_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (ENABLED(A##_HOME_TO_MIN)) { \ - if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ - if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ - } \ - else { \ - if (TERN0(HAS_##A##_MAX, !(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ - if (TERN0(HAS_##A##2_MAX, !(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ - } \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ +#define MINDIR(A) (count_direction[_AXIS(A)] < 0) +#define MAXDIR(A) (count_direction[_AXIS(A)] > 0) + +#define STEPTEST(A,M,I) TERN0(HAS_ ##A## ##I## _ ##M, !(TEST(endstops.state(), A## ##I## _ ##M) && M## DIR(A)) && !locked_ ##A## ##I## _motor) + +#define DUAL_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ + if (STEPTEST(A,MIN, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MIN,2)) A##2_STEP_WRITE(V); \ + } \ + else if (ENABLED(A##_HOME_TO_MAX)) { \ + if (STEPTEST(A,MAX, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MAX,2)) A##2_STEP_WRITE(V); \ + } \ + } \ + else { \ + A##_STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ } #define DUAL_SEPARATE_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (!locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!locked_##A## _motor) A## _STEP_WRITE(V); \ if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \ } \ else { \ @@ -283,60 +288,68 @@ xyze_int8_t Stepper::count_direction{0}; A##2_STEP_WRITE(V); \ } -#define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (ENABLED(A##_HOME_TO_MIN)) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - } \ - else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - } \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ - A##3_STEP_WRITE(V); \ +#define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ + if (STEPTEST(A,MIN, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MIN,2)) A##2_STEP_WRITE(V); \ + if (STEPTEST(A,MIN,3)) A##3_STEP_WRITE(V); \ + } \ + else if (ENABLED(A##_HOME_TO_MAX)) { \ + if (STEPTEST(A,MAX, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MAX,2)) A##2_STEP_WRITE(V); \ + if (STEPTEST(A,MAX,3)) A##3_STEP_WRITE(V); \ + } \ + } \ + else { \ + A##_STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ + A##3_STEP_WRITE(V); \ } #define TRIPLE_SEPARATE_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (!locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!locked_##A## _motor) A## _STEP_WRITE(V); \ if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \ } \ else { \ - A##_STEP_WRITE(V); \ + A## _STEP_WRITE(V); \ A##2_STEP_WRITE(V); \ A##3_STEP_WRITE(V); \ } -#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##_MIN, A##_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##2_MIN, A##2_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##3_MIN, A##3_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##4_MIN, A##4_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ - A##3_STEP_WRITE(V); \ - A##4_STEP_WRITE(V); \ +#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ + if (STEPTEST(A,MIN, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MIN,2)) A##2_STEP_WRITE(V); \ + if (STEPTEST(A,MIN,3)) A##3_STEP_WRITE(V); \ + if (STEPTEST(A,MIN,4)) A##4_STEP_WRITE(V); \ + } \ + else if (ENABLED(A##_HOME_TO_MAX)) { \ + if (STEPTEST(A,MAX, )) A## _STEP_WRITE(V); \ + if (STEPTEST(A,MAX,2)) A##2_STEP_WRITE(V); \ + if (STEPTEST(A,MAX,3)) A##3_STEP_WRITE(V); \ + if (STEPTEST(A,MAX,4)) A##4_STEP_WRITE(V); \ + } \ + } \ + else { \ + A## _STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ + A##3_STEP_WRITE(V); \ + A##4_STEP_WRITE(V); \ } #define QUAD_SEPARATE_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (!locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!locked_##A## _motor) A## _STEP_WRITE(V); \ if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \ if (!locked_##A##4_motor) A##4_STEP_WRITE(V); \ } \ else { \ - A##_STEP_WRITE(V); \ + A## _STEP_WRITE(V); \ A##2_STEP_WRITE(V); \ A##3_STEP_WRITE(V); \ A##4_STEP_WRITE(V); \ From 181530db767b619e998c3c3c5f9b102bb008edfa Mon Sep 17 00:00:00 2001 From: Jin <3448324+jinhong-@users.noreply.github.com> Date: Thu, 26 Aug 2021 06:33:08 +0800 Subject: [PATCH 0582/2168] =?UTF-8?q?=F0=9F=A9=B9=20Use=20?= =?UTF-8?q?=20in=20MAX31865=20lib=20(#22618)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/MAX31865.cpp | 26 +++++++++----------------- Marlin/src/libs/MAX31865.h | 1 + 2 files changed, 10 insertions(+), 17 deletions(-) diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 909adb3807..86c31edee9 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -44,7 +44,7 @@ //#define MAX31865_DEBUG //#define MAX31865_DEBUG_SPI -//TODO: switch to SPIclass/SoftSPI +#include #include "../inc/MarlinConfig.h" @@ -62,7 +62,7 @@ SPISettings MAX31865::spiConfig = SPISettings( 500000 #endif , MSBFIRST - , SPI_MODE_1 // CPOL0 CPHA1 + , SPI_MODE1 // CPOL0 CPHA1 ); #ifndef LARGE_PINMAP @@ -157,10 +157,9 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { #ifdef MAX31865_DEBUG SERIAL_ECHOLN("Initializing MAX31865 Software SPI"); #endif - - OUT_WRITE(_sclk, LOW); - SET_OUTPUT(_mosi); - SET_INPUT(_miso); + + swSpiBegin(_sclk, _miso, _mosi); + } else { // start and configure hardware SPI #ifdef MAX31865_DEBUG @@ -170,6 +169,9 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { SPI.begin(); } + // SPI Begin must be called first, then init + _spi_speed = swSpiInit(SPI_QUARTER_SPEED, _sclk, _mosi); + setWires(wires); enableBias(false); autoConvert(false); @@ -484,17 +486,7 @@ uint8_t MAX31865::spixfer(uint8_t x) { if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) return SPI.transfer(x); - uint8_t reply = 0; - for (int i = 7; i >= 0; i--) { - reply <<= 1; - WRITE(_sclk, HIGH); - WRITE(_mosi, x & (1 << i)); - WRITE(_sclk, LOW); - if (READ(_miso)) - reply |= 1; - } - - return reply; + return swSpiTransfer(x, _spi_speed, _sclk, _miso, _mosi); } #endif // HAS_MAX31865 && !LIB_USR_MAX31865 diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 5d50e870ec..13a117447d 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -90,6 +90,7 @@ private: static SPISettings spiConfig; TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; + uint8_t _spi_speed; float Rzero, Rref; void setConfig(uint8_t config, bool enable); From 88816548b65e464f2a3f77141197b74520d9c142 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Thu, 26 Aug 2021 01:05:06 +0200 Subject: [PATCH 0583/2168] =?UTF-8?q?=F0=9F=94=A8=20Melzi=20with=20OptiBoo?= =?UTF-8?q?t=20build=20(#22630)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- Marlin/src/pins/sanguino/pins_ANET_10.h | 18 +++++++++++++++++- ini/avr.ini | 1 + 3 files changed, 19 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 1c3e1ac7cf..86283dae24 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -329,7 +329,7 @@ #elif MB(OMCA) #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino644p #elif MB(ANET_10) - #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p env:sanguino1284p_optimized + #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p env:sanguino1284p_optimized env:melzi_optiboot #elif MB(SETHI) #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index ac8fa80eb8..e54209ed6a 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -86,8 +86,24 @@ * Many thanks to Hans Raaf (@oderwat) for developing the Anet-specific software and supporting the Anet community. */ +/** + * OptiBoot Bootloader: + * Optiboot is an alternative bootloader that can be flashed on the board to free up space for a larger firmware build. + * See https://github.com/Optiboot/optiboot for more information. + * + * Install Marlin with Arduino IDE: + * For a board with the stock bootloader, select 'Sanguino' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' + * For a board with OptiBoot, select 'Sanguino (Optiboot)' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' + * + * Install Marlin with PlatformIO IDE: + * (NOTE: You can set a default build environment by editing the value of 'default_env' in 'platformio.ini'. + * For the best user experience install the "Auto Build Marlin" extension.) + * For a board with the stock bootloader use Build / Upload under the 'sanguino1284p' or 'sanguino1284p_optimized' target. + * For a board with OptiBoot, use Build / Upload under the 'melzi_optiboot' target. + */ + #if NOT_TARGET(__AVR_ATmega1284P__) - #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' (For PlatformIO, use 'melzi' or 'melzi_optiboot.')" + #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' (For PlatformIO, use 'sanguino1284p' or 'sanguino1284p_optimized'. With optiboot, use 'melzi_optiboot.')" #endif #define BOARD_INFO_NAME "Anet 1.0" diff --git a/ini/avr.ini b/ini/avr.ini index 88f54a723c..e4d64de712 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -141,6 +141,7 @@ platform = atmelavr extends = common_avr8 board = sanguino_atmega1284p upload_speed = 115200 +board_upload.maximum_size = 130048 # # Melzi and clones (Zonestar Melzi2 with tuned flags) From 8889e68088ff8a71c5cafecdc8eb6455b1522627 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 26 Aug 2021 01:08:27 +0200 Subject: [PATCH 0584/2168] =?UTF-8?q?=F0=9F=A9=B9=20Tweak=20startup=20mess?= =?UTF-8?q?age=20(#22633)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 3 +-- Marlin/src/feature/ethernet.cpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 39ff4393d7..6d4e0eab90 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1279,14 +1279,13 @@ void setup() { HAL_clear_reset_source(); SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); - SERIAL_EOL(); #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( " Last Updated: " STRING_DISTRIBUTION_DATE " | Author: " STRING_CONFIG_H_AUTHOR ); #endif - SERIAL_ECHO_MSG("Compiled: " __DATE__); + SERIAL_ECHO_MSG(" Compiled: " __DATE__); SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment diff --git a/Marlin/src/feature/ethernet.cpp b/Marlin/src/feature/ethernet.cpp index d4a95fa051..c5bfa932cb 100644 --- a/Marlin/src/feature/ethernet.cpp +++ b/Marlin/src/feature/ethernet.cpp @@ -147,7 +147,7 @@ void MarlinEthernet::check() { " | Author: " STRING_CONFIG_H_AUTHOR ); #endif - telnetClient.println("Compiled: " __DATE__); + telnetClient.println(" Compiled: " __DATE__); SERIAL_ECHOLNPGM("Client connected"); have_telnet_client = true; From 51160ee9879e03878d7774870bf4e30b48d0149f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 26 Aug 2021 00:55:12 +0000 Subject: [PATCH 0585/2168] [cron] Bump distribution date (2021-08-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 11e6508ba7..6a858d22a0 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-25" +//#define STRING_DISTRIBUTION_DATE "2021-08-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c7e8ed9934..81fcb736be 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 "2021-08-25" + #define STRING_DISTRIBUTION_DATE "2021-08-26" #endif /** From 0c4085da01433c230731828a45ee7a91ae11b794 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 27 Aug 2021 01:01:36 +0000 Subject: [PATCH 0586/2168] [cron] Bump distribution date (2021-08-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6a858d22a0..09cdc0b3fe 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-26" +//#define STRING_DISTRIBUTION_DATE "2021-08-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 81fcb736be..54a368c2aa 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 "2021-08-26" + #define STRING_DISTRIBUTION_DATE "2021-08-27" #endif /** From 36e40b68c9d34c254dccea2cc135b1dca5a80ce9 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 27 Aug 2021 23:06:45 +0200 Subject: [PATCH 0587/2168] =?UTF-8?q?=F0=9F=94=A8=20Set=20Longer3D=20timer?= =?UTF-8?q?s=20in=20variant=20(#22632)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../variants/MARLIN_F103VE_LONGER/PeripheralPins.c | 1 + .../variants/MARLIN_F103VE_LONGER/variant.h | 14 +++++++------- ini/stm32f1.ini | 2 +- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c index 99226a739d..23c1344fe9 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/PeripheralPins.c @@ -154,6 +154,7 @@ WEAK const PinMap PinMap_PWM[] = { {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 3, 0)}, // TIM1_CH3 {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM1_ENABLE, 4, 0)}, // TIM1_CH4 #endif // if 0 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM2_PARTIAL_1, 1, 0)}, // TIM2_CH1 Part Fan {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 1, 0)}, // TIM4_CH1 TFT Backlight {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, AFIO_TIM4_ENABLE, 2, 0)}, // TIM4_CH2 Servo connector {NC, NP, 0} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h index b0f2ddf0c2..56ae719077 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/variant.h @@ -117,13 +117,13 @@ extern "C" { #define PIN_WIRE_SCL PB10 // Timer Definitions -// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin -#ifndef TIMER_TONE - #define TIMER_TONE TIM6 -#endif -#ifndef TIMER_SERVO - #define TIMER_SERVO TIM7 -#endif +// Leave TIMER 2 for optional Fan PWM +#define TEMP_TIMER 3 +// Leave TIMER 4 for TFT backlight PWM or Servo freq... +#define STEP_TIMER 5 +#define TIMER_TONE TIM6 +#define TIMER_SERVO TIM7 +#define TIMER_SERIAL TIM8 // UART Definitions // Define here Serial instance number to map on Serial generic name diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index dc9607ef84..f1cb078fd8 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -338,7 +338,7 @@ board_build.variant = MARLIN_F103VE_LONGER board_build.rename = project.bin board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 -build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103VE -DSTEP_TIMER=5 -DU20 -DTS_V12 +build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103VE -DU20 -DTS_V12 build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED extra_scripts = ${stm32_variant.extra_scripts} monitor_speed = 250000 From f6dc56d97933d0f7566f9fb1f8e775663d014d53 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 27 Aug 2021 17:23:08 -0500 Subject: [PATCH 0588/2168] =?UTF-8?q?=F0=9F=93=9D=20AlephObjects=20=3D>=20?= =?UTF-8?q?LulzBot?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 6 +++--- Marlin/src/inc/SanityCheck.h | 2 ++ .../lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h | 2 +- Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h | 6 +++--- Marlin/src/sd/usb_flashdrive/lib-uhs2/README.txt | 5 +---- Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt | 4 +--- 6 files changed, 11 insertions(+), 14 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 8a07b5c97b..80606df733 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1737,7 +1737,7 @@ //#define LCD_4DSYSTEMS_4DLCD_FT843 // 4D Systems 4.3" (480x272) //#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272) //#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480) - //#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI + //#define LCD_LULZBOT_CLCD_UI // LulzBot Color LCD UI //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480) //#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815 //#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813 @@ -1748,8 +1748,8 @@ //#define TOUCH_UI_800x480 // Mappings for boards with a standard RepRapDiscount Display connector - //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping - //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping + //#define AO_EXP1_PINMAP // LulzBot CLCD UI EXP1 mapping + //#define AO_EXP2_PINMAP // LulzBot CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping //#define F6_TFT_PINMAP // FYSETC F6 pin mapping diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index b679f2cb53..e02e903551 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -589,6 +589,8 @@ #warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." #elif MOTHERBOARD == BOARD_BTT_SKR_E3_TURBO && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) #warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." +#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) + #warning "LCD_ALEPHOBJECTS_CLCD_UI is now LCD_LULZBOT_CLCD_UI." #endif constexpr float arm[] = AXIS_RELATIVE_MODES; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h index 19f926d8e0..5168ef76af 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h @@ -138,7 +138,7 @@ * Settings for the Aleph Objects Color LCD User Interface * Datasheet https://www.hantronix.com/files/data/s1501799605s500-gh7.pdf */ -#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) +#elif defined(LCD_LULZBOT_CLCD_UI) #if !HAS_RESOLUTION #define TOUCH_UI_800x480 #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h index 04cdbe96db..7c0bdd88e9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h @@ -53,7 +53,7 @@ #elif ENABLED(AO_EXP1_DEPRECATED_PINMAP) /** - * This AlephObjects pinout re-purposes the UltraLCD + * This LulzBot pinout re-purposes the UltraLCD * connector EXP1 for Software SPI (rev B, obsolete) */ @@ -74,7 +74,7 @@ /** * AO_EXP1_PINMAP with TOUCH_UI_ULTIPANEL * - * This AlephObjects mapping re-purposes the UltraLCD + * This LulzBot mapping re-purposes the UltraLCD * connector EXP1 for Software SPI for display (rev C): * * EXP2: FTDI: SD -or- USB [1]: ULTRA_LCD: @@ -106,7 +106,7 @@ /** * AO_EXP2_PINMAP with TOUCH_UI_ULTIPANEL * - * The AlephObjects mapping for re-purposing the UltraLCD + * The LulzBot mapping for re-purposing the UltraLCD * connector EXP2 for hardware SPI for display and SD card * or USB (rev C): * diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/README.txt b/Marlin/src/sd/usb_flashdrive/lib-uhs2/README.txt index 5abcc8f2ad..4e9bd84b9c 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/README.txt +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/README.txt @@ -40,7 +40,4 @@ under the "MIT" license, as documented here: ==== MARLIN INTEGRATION WORK ==== -All additional work done to integrate USB into Marlin was performed by AlephObjects, Inc. -and is licensed under the GPLv3. - --- marcio@alephobjects.com +All additional work done to integrate USB into Marlin was performed by LulzBot and is licensed under the GPLv3. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt index 710b3f20b5..378786f940 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt @@ -16,7 +16,7 @@ usb_flashdrive/lib github.com/felis/UHS30 GPLv2 or later ==== MARLIN INTEGRATION WORK ==== All additional work done to integrate USB into Marlin was performed by -AlephObjects, Inc. and is licensed under the GPLv3. +LulzBot and is licensed under the GPLv3. This version of UHS3 has been modified for better compatibility with Marlin. The upstream version of UHS 3.0 runs a frame timer interrupt every 1 ms to @@ -27,5 +27,3 @@ IRQ. SKIP_PAGE3F and USB_NO_TEST_UNIT_READY were added to work around bugs with certain devices. - --- marcio@alephobjects.com From 3a8c509a9fea4c67227648ce9ac35f7434bd0f9e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 28 Aug 2021 00:54:18 +0000 Subject: [PATCH 0589/2168] [cron] Bump distribution date (2021-08-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 09cdc0b3fe..e1dd602e1e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-27" +//#define STRING_DISTRIBUTION_DATE "2021-08-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 54a368c2aa..2dff3aa92f 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 "2021-08-27" + #define STRING_DISTRIBUTION_DATE "2021-08-28" #endif /** From d818a019c5d80e8b2238f0ea8311ad53154be4ec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 28 Aug 2021 15:27:52 -0500 Subject: [PATCH 0590/2168] =?UTF-8?q?=F0=9F=8E=A8=20EXP=20headers,=20ST792?= =?UTF-8?q?0=20delays=20(#22641)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL.h | 13 ++ Marlin/src/HAL/LINUX/HAL.h | 6 +- Marlin/src/HAL/LPC1768/HAL.h | 12 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 6 +- Marlin/src/HAL/STM32/HAL.h | 7 + Marlin/src/HAL/STM32F1/HAL.h | 7 + Marlin/src/HAL/TEENSY31_32/HAL.h | 6 +- Marlin/src/HAL/TEENSY35_36/HAL.h | 6 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 6 +- Marlin/src/inc/Conditionals_LCD.h | 15 ++- .../dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp | 54 -------- Marlin/src/pins/esp32/pins_MRR_ESPE.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 1 - Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 17 ++- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 19 ++- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 1 - .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 1 - Marlin/src/pins/mega/pins_OVERLORD.h | 2 +- Marlin/src/pins/mega/pins_SILVER_GATE.h | 5 +- Marlin/src/pins/pins_postprocess.h | 38 +++++- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 6 + Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 7 + Marlin/src/pins/rambo/pins_MINIRAMBO.h | 8 +- Marlin/src/pins/rambo/pins_RAMBO.h | 7 + Marlin/src/pins/ramps/pins_3DRAG.h | 7 + Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h | 6 +- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 7 + Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 6 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 15 +-- Marlin/src/pins/ramps/pins_K8600.h | 21 --- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 69 ++++------ Marlin/src/pins/ramps/pins_RAMPS.h | 122 ++++++++++------- Marlin/src/pins/sanguino/pins_MELZI.h | 13 ++ .../src/pins/sanguino/pins_MELZI_CREALITY.h | 28 ++-- Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h | 13 -- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 15 +-- Marlin/src/pins/sanguino/pins_MELZI_V2.h | 15 +-- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 23 ---- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 7 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 126 ++++++++++-------- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 52 ++++---- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 99 ++++++++------ Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 15 +-- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 15 +-- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 15 +-- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 15 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 12 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 119 +++++++++++------ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 15 +-- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 6 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 15 +-- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 3 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 3 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 15 +-- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 14 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 14 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 32 ++--- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 24 ++-- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 5 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 19 +-- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 14 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 14 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 1 - Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 19 +-- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 14 +- 65 files changed, 623 insertions(+), 691 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index a5896a0e97..dc0a4f2074 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -39,6 +39,19 @@ #include #include +// +// Default graphical display delays +// +#if F_CPU >= 20000000 + #define CPU_ST7920_DELAY_1 DELAY_NS(150) + #define CPU_ST7920_DELAY_2 DELAY_NS( 0) + #define CPU_ST7920_DELAY_3 DELAY_NS(150) +#elif F_CPU == 16000000 + #define CPU_ST7920_DELAY_1 DELAY_NS(125) + #define CPU_ST7920_DELAY_2 DELAY_NS( 0) + #define CPU_ST7920_DELAY_3 DELAY_NS(188) +#endif + #ifndef pgm_read_ptr // Compatibility for avr-libc 1.8.0-4.1 included with Ubuntu for // Windows Subsystem for Linux on Windows 10 as of 10/18/2019 diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 36906bffc8..07ab85a9a0 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -63,9 +63,9 @@ uint8_t _getc(); extern MSerialT usb_serial; #define MYSERIAL1 usb_serial -#define ST7920_DELAY_1 DELAY_NS(600) -#define ST7920_DELAY_2 DELAY_NS(750) -#define ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) // // Interrupts diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 3f9cd2dfbd..f0a1185ff2 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -50,15 +50,9 @@ extern "C" volatile uint32_t _millis; // // Default graphical display delays // -#ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(600) -#endif -#ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(750) -#endif -#ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(750) -#endif +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index d5c5782c36..400fafd711 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -99,9 +99,9 @@ extern MSerialT serial_stream_3; #endif -#define ST7920_DELAY_1 DELAY_NS(600) -#define ST7920_DELAY_2 DELAY_NS(750) -#define ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) // // Interrupts diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 02bee57ba3..d73f8b2d54 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -37,6 +37,13 @@ #include +// +// Default graphical display delays +// +#define CPU_ST7920_DELAY_1 DELAY_NS(300) +#define CPU_ST7920_DELAY_2 DELAY_NS( 40) +#define CPU_ST7920_DELAY_3 DELAY_NS(340) + // // Serial Ports // diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index b3d8dc9d0b..7efb761c28 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -51,6 +51,13 @@ // Defines // ------------------------ +// +// Default graphical display delays +// +#define CPU_ST7920_DELAY_1 DELAY_NS(300) +#define CPU_ST7920_DELAY_2 DELAY_NS( 40) +#define CPU_ST7920_DELAY_3 DELAY_NS(340) + #ifndef STM32_FLASH_SIZE #if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE) #define STM32_FLASH_SIZE 512 diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 8baa7936f5..d4b3c0a772 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,9 +36,9 @@ #include -#define ST7920_DELAY_1 DELAY_NS(600) -#define ST7920_DELAY_2 DELAY_NS(750) -#define ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) //#undef MOTHERBOARD //#define MOTHERBOARD BOARD_TEENSY31_32 diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 26c35223bd..0b82a569f9 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,9 +37,9 @@ #include #include -#define ST7920_DELAY_1 DELAY_NS(600) -#define ST7920_DELAY_2 DELAY_NS(750) -#define ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) // ------------------------ // Defines diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 1d00447fe8..14f14bf446 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,9 +41,9 @@ #include "../../feature/ethernet.h" #endif -//#define ST7920_DELAY_1 DELAY_NS(600) -//#define ST7920_DELAY_2 DELAY_NS(750) -//#define ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 DELAY_NS(600) +#define CPU_ST7920_DELAY_2 DELAY_NS(750) +#define CPU_ST7920_DELAY_3 DELAY_NS(750) // ------------------------ // Defines diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index c4309db144..bfbe5ba6cf 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -237,11 +237,18 @@ #elif ENABLED(CR10_STOCKDISPLAY) #define IS_RRD_FG_SC 1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define LCD_ST7920_DELAY_1 DELAY_NS(125) + #define LCD_ST7920_DELAY_2 DELAY_NS(125) + #define LCD_ST7920_DELAY_3 DELAY_NS(125) -#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) +#elif ENABLED(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) + + #define IS_RRD_FG_SC 1 + #define LCD_ST7920_DELAY_1 DELAY_NS(150) + #define LCD_ST7920_DELAY_2 DELAY_NS(150) + #define LCD_ST7920_DELAY_3 DELAY_NS(150) + +#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) #define IS_RRD_FG_SC 1 diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp index 4abf91edbd..20c8cec0cf 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -33,60 +33,6 @@ #include "ultralcd_st7920_u8glib_rrd_AVR.h" -#if F_CPU >= 20000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(150) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(150) -#elif MB(3DRAG, K8200, K8400) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(188) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(MINIRAMBO, EINSY_RAMBO, EINSY_RETRO, SILVER_GATE) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(250) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(RAMBO) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(0) -#elif MB(BQ_ZUM_MEGA_3D) - #define CPU_ST7920_DELAY_1 DELAY_NS(0) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(189) -#elif defined(ARDUINO_ARCH_STM32) - #define CPU_ST7920_DELAY_1 DELAY_NS(300) - #define CPU_ST7920_DELAY_2 DELAY_NS(40) - #define CPU_ST7920_DELAY_3 DELAY_NS(340) -#elif F_CPU == 16000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(125) - #define CPU_ST7920_DELAY_2 DELAY_NS(0) - #define CPU_ST7920_DELAY_3 DELAY_NS(188) -#else - #error "No valid condition for delays in 'ultralcd_st7920_u8glib_rrd_AVR.h'" -#endif - -#ifndef ST7920_DELAY_1 - #ifdef BOARD_ST7920_DELAY_1 - #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 - #else - #define ST7920_DELAY_1 CPU_ST7920_DELAY_1 - #endif -#endif -#ifndef ST7920_DELAY_2 - #ifdef BOARD_ST7920_DELAY_2 - #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 - #else - #define ST7920_DELAY_2 CPU_ST7920_DELAY_2 - #endif -#endif -#ifndef ST7920_DELAY_3 - #ifdef BOARD_ST7920_DELAY_3 - #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 - #else - #define ST7920_DELAY_3 CPU_ST7920_DELAY_3 - #endif -#endif - // Optimize this code with -O3 #pragma GCC optimize (3) diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index f156efd2e8..8b4ec8b197 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -122,7 +122,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_MARLINUI_U8GLIB +#if HAS_WIRED_LCD #define LCD_PINS_RS 13 #define LCD_PINS_ENABLE 17 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 c01afccaca..b74870b30f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -63,7 +63,6 @@ * ------ ------ * EXP2 EXP1 */ - #define EXP1_03_PIN -1 #define EXP1_04_PIN -1 #define EXP1_05_PIN -1 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 1ce6aed700..56944273e3 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -184,16 +184,15 @@ #endif /** - * ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 (SD_DETECT) (LCD_D7) 1.23 | 3 4 | 1.22 (LCD_D6) - * (MOSI) 0.18 | 5 6 3.25 (BTN_EN2) (LCD_D5) 1.21 | 5 6 1.20 (LCD_D4) - * (SD_SS) 0.16 | 7 8 | 3.26 (BTN_EN1) (LCD_RS) 1.19 | 7 8 | 1.18 (LCD_EN) - * (SCK) 0.15 | 9 10 | 0.17 (MISO) (BTN_ENC) 0.28 | 9 10 | 1.30 (BEEPER) - * ------ ------ - * EXP2 EXP1 + * ------ ------ + * (BEEPER) 1.30 |10 9 | 0.28 (BTN_ENC) (MISO) 0.17 |10 9 | 0.15 (SCK) + * (LCD_EN) 1.18 | 8 7 | 1.19 (LCD_RS) (BTN_EN1) 3.26 | 8 7 | 0.16 (SD_SS) + * (LCD_D4) 1.20 6 5 | 1.21 (LCD_D5) (BTN_EN2) 3.25 6 5 | 0.18 (MOSI) + * (LCD_D6) 1.22 | 4 3 | 1.23 (LCD_D7) (SD_DETECT) 1.31 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - #define EXP1_03_PIN P1_23 #define EXP1_04_PIN P1_22 #define EXP1_05_PIN P1_21 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 ae6456a3ce..58f2ac2808 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -239,16 +239,15 @@ #define TMC_BAUD_RATE 19200 #endif -/** ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 1.23 | 3 4 | 1.22 - * 0.18 | 5 6 3.25 1.21 | 5 6 1.20 - * 0.16 | 7 8 | 3.26 1.19 | 7 8 | 1.18 - * 0.15 | 9 10| 0.17 0.28 | 9 10| 1.30 - * ------ ------ - * EXP2 EXP1 +/** ------ ------ + * 1.30 |10 9 | 0.28 0.17 |10 9 | 0.15 + * 1.18 | 8 7 | 1.19 3.26 | 8 7 | 0.16 + * 1.20 6 5 | 1.21 3.25 6 5 | 0.18 + * 1.22 | 4 3 | 1.23 1.31 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - #define EXP1_03_PIN P1_23 #define EXP1_04_PIN P1_22 #define EXP1_05_PIN P1_21 @@ -258,7 +257,7 @@ #define EXP1_09_PIN P0_28 #define EXP1_10_PIN P1_30 -#define EXP2_03_PIN -1 +#define EXP2_03_PIN -1 // RESET #define EXP2_04_PIN P1_31 #define EXP2_05_PIN P0_18 #define EXP2_06_PIN P3_25 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 49dad8b07b..fe2a71ae03 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -237,7 +237,6 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_03_PIN P1_22 #define EXP1_04_PIN P1_00 #define EXP1_05_PIN P0_17 diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index c2d2621bc1..af7b7d7e58 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -188,7 +188,6 @@ * ------ * EXP */ - #define EXP1_03_PIN P0_18 #define EXP1_04_PIN P0_17 #define EXP1_05_PIN P0_15 diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 161820b67a..0884d8ecb5 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -119,7 +119,7 @@ // // LCD / Controller // -#if HAS_MARLINUI_U8GLIB +#if HAS_WIRED_LCD // OVERLORD OLED pins #define LCD_PINS_RS 20 #define LCD_PINS_D5 21 diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 41cbe5e0e0..0828b32aa9 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -72,7 +72,7 @@ #define HEATER_BED_PIN 8 #define TEMP_BED_PIN 6 -#if HAS_MARLINUI_U8GLIB +#if HAS_WIRED_LCD #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 #define LCD_PINS_RS 30 #define LCD_PINS_ENABLE 20 @@ -86,6 +86,9 @@ #define KILL_PIN 21 #define HOME_PIN 28 #endif + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) #endif #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index fc82e600df..aa2bc07908 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -1221,23 +1221,47 @@ // // Default DOGLCD SPI delays // -#if HAS_MARLINUI_U8GLIB - #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) - #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 +#if ENABLED(U8GLIB_ST7920) + #ifndef ST7920_DELAY_1 + #ifdef LCD_ST7920_DELAY_1 + #define ST7920_DELAY_1 LCD_ST7920_DELAY_1 + #elif defined(BOARD_ST7920_DELAY_1) + #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 + #elif defined(CPU_ST7920_DELAY_1) + #define ST7920_DELAY_1 CPU_ST7920_DELAY_1 + #endif #endif - #if !defined(ST7920_DELAY_2) && defined(BOARD_ST7920_DELAY_2) - #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 + #ifndef ST7920_DELAY_2 + #ifdef LCD_ST7920_DELAY_2 + #define ST7920_DELAY_2 LCD_ST7920_DELAY_2 + #elif defined(BOARD_ST7920_DELAY_2) + #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 + #elif defined(CPU_ST7920_DELAY_2) + #define ST7920_DELAY_2 CPU_ST7920_DELAY_2 + #endif #endif - #if !defined(ST7920_DELAY_3) && defined(BOARD_ST7920_DELAY_3) - #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 + #ifndef ST7920_DELAY_3 + #ifdef LCD_ST7920_DELAY_3 + #define ST7920_DELAY_3 LCD_ST7920_DELAY_3 + #elif defined(BOARD_ST7920_DELAY_3) + #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 + #elif defined(CPU_ST7920_DELAY_3) + #define ST7920_DELAY_3 CPU_ST7920_DELAY_3 + #endif #endif #else #undef ST7920_DELAY_1 #undef ST7920_DELAY_2 #undef ST7920_DELAY_3 + #undef LCD_ST7920_DELAY_1 + #undef LCD_ST7920_DELAY_2 + #undef LCD_ST7920_DELAY_3 #undef BOARD_ST7920_DELAY_1 #undef BOARD_ST7920_DELAY_2 #undef BOARD_ST7920_DELAY_3 + #undef CPU_ST7920_DELAY_1 + #undef CPU_ST7920_DELAY_2 + #undef CPU_ST7920_DELAY_3 #endif #if !NEED_CASE_LIGHT_PIN diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 78465dd7a8..dbb34f6585 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -205,4 +205,10 @@ #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_WIRED_LCD +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) +#endif + #undef MK3_FAN_PINS diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 0c072745d5..5d8ffc07aa 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -199,3 +199,10 @@ #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE + +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) +#endif diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index ec44cc3b36..6257550697 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -69,7 +69,7 @@ #define E0_DIR_PIN 43 #define E0_ENABLE_PIN 26 -// Microstepping pins - Mapping not from fastio.h (?) +// Microstepping pins #define X_MS1_PIN 40 #define X_MS2_PIN 41 #define Y_MS1_PIN 69 @@ -192,3 +192,9 @@ #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL + +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(250) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) +#endif diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index f2d34dc00d..a77cb3d93f 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -268,3 +268,10 @@ #endif // !IS_NEWPANEL #endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(0) + #define BOARD_ST7920_DELAY_3 DELAY_NS(0) +#endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index e78f7683f6..3f38ecb211 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -80,6 +80,7 @@ #if IS_ULTRA_LCD && IS_NEWPANEL #undef BEEPER_PIN + // TODO: Remap EXP1/2 based on adapter #undef LCD_PINS_RS #undef LCD_PINS_ENABLE #undef LCD_PINS_D4 @@ -107,6 +108,12 @@ #endif // IS_ULTRA_LCD && IS_NEWPANEL +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) +#endif + /** * M3/M4/M5 - Spindle/Laser Control * diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index 97ef1b4fd8..4d7a792635 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -38,12 +38,10 @@ #define SPINDLE_DIR_PIN 67 #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM -#include "pins_RAMPS.h" - // // Temperature Sensors // -#undef TEMP_0_PIN -#undef TEMP_1_PIN #define TEMP_0_PIN 9 // Analog Input #define TEMP_1_PIN 11 // Analog Input + +#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 99cf484de7..5b3ed4c6a5 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -123,3 +123,10 @@ #undef HEATER_BED_PIN #define HEATER_BED_PIN 8 #endif + +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_3 DELAY_NS(189) +#endif diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index 8dc93c833b..4f25110ca2 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -39,10 +39,8 @@ #define FIL_RUNOUT2_PIN 14 #endif -// -// LCD delays -// -#if HAS_MARLINUI_U8GLIB +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #define BOARD_ST7920_DELAY_2 DELAY_NS(250) #define BOARD_ST7920_DELAY_3 DELAY_NS(250) diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 5f645e5d95..0398d36f93 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -198,14 +198,9 @@ #define LCD_PINS_D7 29 #endif -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(200) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(200) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(200) - #endif +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(200) + #define BOARD_ST7920_DELAY_2 DELAY_NS(200) + #define BOARD_ST7920_DELAY_3 DELAY_NS(200) #endif diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 47b52e75e8..9049308ba8 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -60,30 +60,9 @@ // // Steppers // -#undef X_STEP_PIN -#undef X_DIR_PIN -#undef X_ENABLE_PIN -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 - -#undef Y_STEP_PIN -#undef Y_DIR_PIN -#undef Y_ENABLE_PIN -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 - #undef Z_ENABLE_PIN #define Z_ENABLE_PIN 63 -#undef E0_STEP_PIN -#undef E0_DIR_PIN -#undef E0_ENABLE_PIN -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 - // // Heaters / Fans // diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 08dd0f44bd..4742ac9b0d 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -54,6 +54,9 @@ #include "pins_RAMPS.h" +#undef EXP2_03_PIN +#define EXP2_03_PIN -1 // RESET + // // LCD / Controller // @@ -81,19 +84,21 @@ * * This configuration uses the following arrangement: * - * EXP1 D37 = EN2 D35 = EN1 EXP2 D50 = MISO D52 = SCK - * D17 = BLUE D16 = RED D31 = ENC D53 = SDCS - * D23 = KILL D25 = BUZZ D33 = --- D51 = MOSI - * D27 = A0 D29 = LCS D49 = SDCD RST = --- - * GND = GND 5V = 5V GND = --- D41 = --- + * ------ ------ + * ENCB |10 9 | ENCA MISO |10 9 | SCK + * BLUE_LED | 8 7 | RED_LED ENCBTN | 8 7 | SDCS + * KILL 6 5 | BEEPER 6 5 | MOSI + * A0 | 4 3 | LCD_CS SDCD | 4 3 | + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - + #undef SD_DETECT_PIN #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC #undef DOGLCD_A0 #undef DOGLCD_CS - #undef SD_DETECT_PIN #undef BEEPER_PIN #undef KILL_PIN #undef STAT_LED_RED_PIN @@ -102,46 +107,24 @@ // // VIKI2 12-wire lead // + #define SD_DETECT_PIN EXP2_04_PIN // SDCD orange/white + #define BTN_EN1 EXP1_09_PIN // ENCA white + #define BTN_EN2 EXP1_10_PIN // ENCB green + #define BTN_ENC EXP2_08_PIN // ENCBTN purple + #define DOGLCD_A0 EXP1_04_PIN // A0 brown + #define DOGLCD_CS EXP1_03_PIN // LCS green/white - // orange/white SDCD - #define SD_DETECT_PIN 49 + // EXP2_10_PIN gray MISO + // EXP2_05_PIN yellow MOSI + // EXP2_09_PIN orange SCK - // white ENCA - #define BTN_EN1 35 - - // green ENCB - #define BTN_EN2 37 - - // purple ENCBTN - #define BTN_ENC 31 - - // brown A0 - #define DOGLCD_A0 27 - - // green/white LCS - #define DOGLCD_CS 29 - - // 50 gray MISO - // 51 yellow MOSI - // 52 orange SCK - - // blue SDCS - //#define SDSS 53 + //#define SDSS EXP2_07_PIN // SDCS blue // // VIKI2 4-wire lead // - - // blue BTN - #define KILL_PIN 23 - - // green BUZZER - #define BEEPER_PIN 25 - - // yellow RED-LED - #define STAT_LED_RED_PIN 16 - - // white BLUE-LED - #define STAT_LED_BLUE_PIN 17 - + #define KILL_PIN EXP1_06_PIN // BTN blue + #define BEEPER_PIN EXP1_05_PIN // BUZZER green + #define STAT_LED_RED_PIN EXP1_07_PIN // RED-LED yellow + #define STAT_LED_BLUE_PIN EXP1_08_PIN // BLUE-LED white #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 1683ccf5c8..b51d212f4f 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -120,14 +120,14 @@ #define X_DIR_PIN 55 #define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN EXP2_07_PIN + #define X_CS_PIN AUX3_03_PIN #endif #define Y_STEP_PIN 60 #define Y_DIR_PIN 61 #define Y_ENABLE_PIN 56 #ifndef Y_CS_PIN - #define Y_CS_PIN EXP2_04_PIN + #define Y_CS_PIN AUX3_07_PIN #endif #ifndef Z_STEP_PIN @@ -242,7 +242,7 @@ // Misc. Functions // #ifndef SDSS - #define SDSS EXP2_07_PIN + #define SDSS AUX3_03_PIN #endif #define LED_PIN 13 @@ -424,58 +424,79 @@ #endif // -// Aux 3 GND D52 D50 5V -// NC D53 D51 D49 +// AUX3 : GND D52 D50 5V +// NC D53 D51 D49 + +#define AUX3_03_PIN 53 +#define AUX3_04_PIN 52 +#define AUX3_05_PIN 51 +#define AUX3_06_PIN 50 +#define AUX3_07_PIN 49 // -// Aux 4 D16 D17 D23 D25 D27 D29 D31 D33 D35 D37 D39 D41 D43 D45 D47 D32 GND 5V +// AUX4 : D16 D17 D23 D25 D27 D29 D31 D33 D35 D37 D39 D41 D43 D45 D47 D32 GND 5V // +#define AUX4_03_PIN 32 +#define AUX4_04_PIN 47 +#define AUX4_05_PIN 45 +#define AUX4_06_PIN 43 +#define AUX4_07_PIN 41 +#define AUX4_08_PIN 39 +#define AUX4_09_PIN 37 +#define AUX4_10_PIN 35 +#define AUX4_11_PIN 33 +#define AUX4_12_PIN 31 +#define AUX4_13_PIN 29 +#define AUX4_14_PIN 27 +#define AUX4_15_PIN 25 +#define AUX4_16_PIN 23 +#define AUX4_17_PIN 17 +#define AUX4_18_PIN 16 + /** - * LCD adapter. Please note: These comes in two variants. The socket keys can be + * LCD adapter. NOTE: These come in two variants. The socket keys can be * on either side, and may be backwards on some boards / displays. - * ----- ----- - * D37 |10 9 | D35 (MISO) D50 |10 9 | D52 (SCK) - * D17 | 8 7 | D16 D31 | 8 7 | D53 - * D23 6 5 D25 D33 6 5 D51 (MOSI) - * D27 | 4 3 | D29 D49 | 4 3 | D41 - * GND | 2 1 | 5V GND | 2 1 | NC - * ----- ----- - * EXP1 EXP2 + * ------ ------ + * D37 |10 9 | D35 (MISO) D50 |10 9 | D52 (SCK) + * D17 | 8 7 | D16 D31 | 8 7 | D53 + * D23 6 5 D25 D33 6 5 D51 (MOSI) + * D27 | 4 3 | D29 D49 | 4 3 | D41 + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - #ifndef EXP1_03_PIN - #define EXP1_03_PIN 29 - #define EXP1_04_PIN 27 - #define EXP1_05_PIN 25 - #define EXP1_06_PIN 23 - #define EXP1_07_PIN 16 - #define EXP1_08_PIN 17 - #define EXP1_09_PIN 35 - #define EXP1_10_PIN 37 + #define EXP1_03_PIN AUX4_13_PIN + #define EXP1_04_PIN AUX4_14_PIN + #define EXP1_05_PIN AUX4_15_PIN + #define EXP1_06_PIN AUX4_16_PIN + #define EXP1_07_PIN AUX4_18_PIN + #define EXP1_08_PIN AUX4_17_PIN + #define EXP1_09_PIN AUX4_10_PIN + #define EXP1_10_PIN AUX4_09_PIN - #define EXP2_03_PIN 41 - #define EXP2_04_PIN 49 - #define EXP2_05_PIN 51 - #define EXP2_06_PIN 33 - #define EXP2_07_PIN 53 - #define EXP2_08_PIN 31 - #define EXP2_09_PIN 52 - #define EXP2_10_PIN 50 + #define EXP2_03_PIN AUX4_07_PIN + #define EXP2_04_PIN AUX3_07_PIN + #define EXP2_05_PIN AUX3_05_PIN + #define EXP2_06_PIN AUX4_11_PIN + #define EXP2_07_PIN AUX3_03_PIN + #define EXP2_08_PIN AUX4_12_PIN + #define EXP2_09_PIN AUX3_04_PIN + #define EXP2_10_PIN AUX3_06_PIN #endif ////////////////////////// // LCDs and Controllers // ////////////////////////// -// GLCD features -// Uncomment screen orientation -//#define LCD_SCREEN_ROT_90 -//#define LCD_SCREEN_ROT_180 -//#define LCD_SCREEN_ROT_270 - #if HAS_WIRED_LCD + // Uncomment screen orientation + //#define LCD_SCREEN_ROT_90 + //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_270 + // // LCD Display output pins // @@ -587,7 +608,7 @@ #endif #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN AUX4_08_PIN #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -599,9 +620,9 @@ #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 + #define BTN_EN1 AUX4_04_PIN + #define BTN_EN2 AUX4_06_PIN + #define BTN_ENC AUX4_03_PIN #define LCD_SDSS SDSS #define KILL_PIN EXP2_03_PIN @@ -725,13 +746,23 @@ // Pins only defined for RAMPS_SMART currently + #elif ENABLED(G3D_PANEL) + + #define BEEPER_PIN EXP2_06_PIN + + #define SD_DETECT_PIN EXP2_04_PIN + #define KILL_PIN EXP2_03_PIN + + #define BTN_EN1 EXP1_10_PIN + #define BTN_EN2 EXP1_09_PIN + #define BTN_ENC EXP2_08_PIN + #elif IS_TFTGLCD_PANEL #define SD_DETECT_PIN EXP2_04_PIN #else - // Beeper on AUX-4 #define BEEPER_PIN EXP2_06_PIN // Buttons are directly attached to AUX-2 @@ -745,11 +776,6 @@ #define BTN_ENC EXP2_08_PIN #endif - #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN EXP2_04_PIN - #define KILL_PIN EXP2_03_PIN - #endif - #endif #endif // IS_NEWPANEL diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index de4dd1b01d..8f2729f8f0 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -31,4 +31,17 @@ #define IS_MELZI 1 +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #endif +#endif + #include "pins_SANGUINOLOLU_12.h" diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index d4915c9cca..81ccf5977e 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -36,16 +36,10 @@ #define BOARD_INFO_NAME "Melzi (Creality)" // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif #include "pins_MELZI.h" @@ -137,11 +131,11 @@ /** * EXP1 Connector EXP1 as CR10 STOCKDISPLAY - * ----- ----- - * PA4 | 6 5 | PC0 BEEPER_PIN | 6 5 | BTN_ENC - * PD3 | 7 4 | RESET BTN_EN1 | 7 4 | RESET - * PD2 8 3 | PA1 BTN_EN2 8 3 | LCD_PINS_D4 (ST9720 CLK) - * PA3 | 9 2 | PC1 (ST9720 CS) LCD_PINS_RS | 9 2 | LCD_PINS_ENABLE (ST9720 DAT) - * GND |10 1 | 5V GND |10 1 | 5V - * ----- ----- + * ------ ------ + * PA4 |10 9 | PC0 BEEPER_PIN |10 9 | BTN_ENC + * PD3 | 8 7 | RESET BTN_EN1 | 8 7 | RESET + * PD2 6 5 | PA1 BTN_EN2 6 5 | LCD_PINS_D4 (ST9720 CLK) + * PA3 | 4 3 | PC1 (ST9720 CS) LCD_PINS_RS | 4 3 | LCD_PINS_ENABLE (ST9720 DAT) + * GND | 2 1 | 5V GND | 2 1 | 5V + * ------ ------ */ diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index 8b4faeeaf9..3bf8f80457 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -27,19 +27,6 @@ #define BOARD_INFO_NAME "Melzi (Malyan)" -// Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif -#endif - #include "pins_MELZI.h" #undef LCD_SDSS diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index f878941037..e88a38561d 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -27,16 +27,11 @@ #define BOARD_INFO_NAME "Melzi (Tronxy)" -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) - #endif +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) #endif #include "pins_MELZI.h" diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index e0369923c7..c1fb7fb6f7 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -24,16 +24,11 @@ #define BOARD_INFO_NAME "Melzi V2" -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(400) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) - #endif +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_2 DELAY_NS(400) + #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) #endif #include "pins_MELZI.h" diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index d79ad7a3dd..8dd6171b92 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -165,16 +165,6 @@ #define KILL_PIN 10 #define BEEPER_PIN 27 - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) - #endif - #elif ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI @@ -185,19 +175,6 @@ // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. #define BEEPER_PIN 27 - - #if IS_RRD_FG_SC - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) - #endif - #endif - #else // Sanguinololu >=1.3 #define LCD_PINS_RS 4 #define LCD_PINS_ENABLE 17 diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 0265ae0a64..cb2dec1600 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -189,10 +189,9 @@ #endif #define LCD_PINS_D4 10 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) - // Alter timing for graphical display - #define ST7920_DELAY_1 DELAY_2_NOP - #define ST7920_DELAY_2 DELAY_2_NOP - #define ST7920_DELAY_3 DELAY_2_NOP + #define BOARD_ST7920_DELAY_1 DELAY_2_NOP + #define BOARD_ST7920_DELAY_2 DELAY_2_NOP + #define BOARD_ST7920_DELAY_3 DELAY_2_NOP #elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) // diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 441f9350e3..5d23466071 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -68,7 +68,7 @@ #define E0_DIR_PIN PB0 #define E0_ENABLE_PIN PC4 -#if ENABLED(TMC_USE_SW_SPI) +#if ENABLED(TMC_USE_SW_SPI) // Shared with EXP2 #ifndef TMC_SW_SCK #define TMC_SW_SCK PB3 #endif @@ -93,33 +93,48 @@ #define TEMP_BED_PIN PB1 // Analog Input #define TEMP_0_PIN PA0 // Analog Input -// -// LCD Pins -// - -/** - * ----- ----- - * NC | · · | GND 5V | · · | GND - * RESET | · · | PB9 (SD_DETECT) (LCD_D7) PC14 | · · | PC15 (LCD_D6) - * (MOSI) PB5 | · · | PB8 (BTN_EN2) (LCD_D5) PB7 | · · | PC13 (LCD_D4) - * (SD_SS) PA15 | · · | PD2 (BTN_EN1) (LCD_RS) PC12 | · · | PB6 (LCD_EN) - * (SCK) PB3 | · · | PB4 (MISO) (BTN_ENC) PC11 | · · | PC10 (BEEPER) - * ----- ----- - * EXP2 EXP1 +/** ------ ------ + * (BEEPER) PC10 |10 9 | PC11 (BTN_ENC) (MISO) PB4 |10 9 | PB3 (SCK) + * (LCD_EN) PB6 | 8 7 | PC12 (LCD_RS) (BTN_EN1) PD2 | 8 7 | PA15 (SD_SS) + * (LCD_D4) PC13 | 6 5 | PB7 (LCD_D5) (BTN_EN2) PB8 | 6 5 | PB5 (MOSI) + * (LCD_D6) PC15 | 4 3 | PC14 (LCD_D7) (SD_DETECT) PB9 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ +#define EXP1_03_PIN PC14 +#define EXP1_04_PIN PC15 +#define EXP1_05_PIN PB7 +#define EXP1_06_PIN PC13 +#define EXP1_07_PIN PC12 +#define EXP1_08_PIN PB6 +#define EXP1_09_PIN PC11 +#define EXP1_10_PIN PC10 +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB9 +#define EXP2_05_PIN PB5 +#define EXP2_06_PIN PB8 +#define EXP2_07_PIN PA15 +#define EXP2_08_PIN PD2 +#define EXP2_09_PIN PB3 +#define EXP2_10_PIN PB4 + +// +// LCD / Controller +// #if HAS_WIRED_LCD - #define BEEPER_PIN PC10 - #define BTN_ENC PC11 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PC15 + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 PB6 - #define BTN_EN2 PC13 + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE PC14 - #define LCD_PINS_D4 PB7 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #elif IS_TFTGLCD_PANEL @@ -127,56 +142,56 @@ #undef BTN_ENC #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS PD2 + #define TFTGLCD_CS EXP2_08_PIN #endif - #define SD_DETECT_PIN PB9 + #define SD_DETECT_PIN EXP2_04_PIN #else - #define LCD_PINS_RS PC12 + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 PD2 - #define BTN_EN2 PB8 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN - #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_ENABLE EXP1_08_PIN #if ENABLED(FYSETC_MINI_12864) #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PC13 - #define DOGLCD_A0 PC12 - #define DOGLCD_CS PB6 - #define DOGLCD_SCK PB3 - #define DOGLCD_MOSI PB5 + #define LCD_RESET_PIN EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #define FORCE_SOFT_SPI // SPI MODE3 - #define LED_PIN PB7 // red pwm - //#define LED_PIN PC15 // green - //#define LED_PIN PC14 // blue + #define LED_PIN EXP1_05_PIN // red pwm + //#define LED_PIN EXP1_04_PIN // green + //#define LED_PIN EXP1_03_PIN // blue //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN - // #define RGB_LED_R_PIN PB7 + // #define RGB_LED_R_PIN EXP1_05_PIN // #endif // #ifndef RGB_LED_G_PIN - // #define RGB_LED_G_PIN PC15 + // #define RGB_LED_G_PIN EXP1_04_PIN // #endif // #ifndef RGB_LED_B_PIN - // #define RGB_LED_B_PIN PC14 + // #define RGB_LED_B_PIN EXP1_03_PIN // #endif //#elif ENABLED(FYSETC_MINI_12864_2_1) - // #define NEOPIXEL_PIN PB7 + // #define NEOPIXEL_PIN EXP1_05_PIN //#endif #else // !FYSETC_MINI_12864 - #define LCD_PINS_D4 PC13 + #define LCD_PINS_D4 EXP1_06_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 PB7 - #define LCD_PINS_D6 PC15 - #define LCD_PINS_D7 PC14 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -186,16 +201,11 @@ #endif // !FYSETC_MINI_12864 - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif #endif @@ -214,11 +224,11 @@ #if SD_CONNECTION_IS(LCD) #define SPI_DEVICE 3 - #define SD_DETECT_PIN PB9 - #define SD_SCK_PIN PB3 - #define SD_MISO_PIN PB4 - #define SD_MOSI_PIN PB5 - #define SD_SS_PIN PA15 + #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_SS_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PA3 #define SD_SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index c2edcd3678..2ce1d49bb8 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -122,41 +122,43 @@ #define NEOPIXEL_PIN PC7 // The NEOPIXEL LED driving pin /** - * 1 ----- 2 - * PB5 | · · | PB6 - * PA2 | · · | RESET - * PA3 | · · | PB8 - * PB7 | · · | PA4 - * GND | · · | VCC5 - * 9 ----- 10 - * LCD EXP + * ------ + * PB5 |10 9 | PB6 + * PA2 | 8 7 | RESET + * PA3 6 5 | PB8 + * PB7 | 4 3 | PA4 + * GND | 2 1 | VCC5 + * ------ + * EXP1 */ +#define EXP1_03_PIN PA4 +#define EXP1_04_PIN PB7 +#define EXP1_05_PIN PB8 +#define EXP1_06_PIN PA3 +#define EXP1_07_PIN -1 // RESET +#define EXP1_08_PIN PA2 +#define EXP1_09_PIN PB6 +#define EXP1_10_PIN PB5 // // LCD / Controller // #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN PB5 - #define BTN_EN1 PA2 - #define BTN_EN2 PA3 - #define BTN_ENC PB6 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_09_PIN - #define LCD_PINS_RS PB7 // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 PB8 // SCLK - #define LCD_PINS_ENABLE PA4 // DATA MOSI + #define LCD_PINS_RS EXP1_04_PIN // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 EXP1_05_PIN // SCLK + #define LCD_PINS_ENABLE EXP1_03_PIN // DATA MOSI #endif // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 08efa9a04e..7d0e15f57a 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -83,13 +83,13 @@ #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 + #define TMC_SW_MOSI EXP2_05_PIN #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 + #define TMC_SW_MISO EXP2_10_PIN #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 + #define TMC_SW_SCK EXP2_09_PIN #endif #endif @@ -120,52 +120,69 @@ #define TEMP_BED_PIN PC0 // Analog Input #define TEMP_0_PIN PC1 // Analog Input -// -// LCD Pins -// +/** ------ ------ + * (BEEPER) PC14 |10 9 | PC13 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SD_SCK) + * (LCD_EN) PB9 | 8 7 | PB8 (LCD_RS) (BTN_EN1) PB3 | 8 7 | PB12 (SD_CS2) + * (LCD_D4) PB7 | 6 5 PB6 (LCD_D5) (BTN_EN2) PD2 | 6 5 PB15 (SD_MOSI) + * (LCD_D6) PB5 | 4 3 | PB4 (LCD_D7) (SD_DETECT) PB11 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PB4 +#define EXP1_04_PIN PB5 +#define EXP1_05_PIN PB6 +#define EXP1_06_PIN PB7 +#define EXP1_07_PIN PB8 +#define EXP1_08_PIN PB9 +#define EXP1_09_PIN PC13 +#define EXP1_10_PIN PC14 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB11 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PD2 +#define EXP2_07_PIN PB12 +#define EXP2_08_PIN PB3 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 // // LCD / Controller // -#define SPI_DEVICE 2 -#define SD_SS_PIN PB12 -#define SD_SCK_PIN PB13 -#define SD_MISO_PIN PB14 -#define SD_MOSI_PIN PB15 +#if HAS_WIRED_LCD -#define SDSS SD_SS_PIN -#define SD_DETECT_PIN PB11 + #define SPI_DEVICE 2 + #define SD_SS_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN -#define BEEPER_PIN PC14 + #define SDSS SD_SS_PIN + #define SD_DETECT_PIN EXP2_04_PIN -#define LCD_PINS_RS PB8 -#define LCD_PINS_ENABLE PB9 -#define LCD_PINS_D4 PB7 -#define LCD_PINS_D5 PB6 -#define LCD_PINS_D6 PB5 -#define LCD_PINS_D7 PB4 + #define BEEPER_PIN EXP1_10_PIN -#define BTN_EN1 PD2 -#define BTN_EN2 PB3 -#define BTN_ENC PC13 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN -#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder -#endif + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_08_PIN + #define BTN_ENC EXP1_09_PIN -// -// Filament runout -// + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif -// -// ST7920 Delays -// -#ifndef ST7920_DELAY_1 - #define ST7920_DELAY_1 DELAY_NS(96) -#endif -#ifndef ST7920_DELAY_2 - #define ST7920_DELAY_2 DELAY_NS(48) -#endif -#ifndef ST7920_DELAY_3 - #define ST7920_DELAY_3 DELAY_NS(715) -#endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #endif + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 4edd67a14d..797e13fd07 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -157,16 +157,11 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index f346c3a9fd..64b1c6c040 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -165,16 +165,11 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 2545642bae..992fc36f92 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -162,16 +162,11 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 865de809e2..d33ce461fe 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -167,16 +167,11 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 2cfb71380d..4db596a1bc 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -342,15 +342,9 @@ #endif - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 60d342c602..8c0ff76ae6 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -133,54 +133,82 @@ #endif /** - * ----- ----- ----- - * (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) 5V | 1 2 | GND - * (LCD_EN) PA4 | 3 4 | PA5 (LCD_RS) (BTN_EN1) PB11 | 3 4 | PA15 (SD_SS) (LCD_EN) PA4 | 3 4 | PA5 (LCD_RS) - * (LCD_D4) PA6 | 5 6 PA7 (LCD_D5) (BTN_EN2) PB0 | 5 6 PB15 (SD_MOSI) (LCD_D4) PA6 | 5 6 PB0 (BTN_EN2) - * (LCD_D6) PC4 | 7 8 | PC5 (LCD_D7) (SD_DETECT) PC10 | 7 8 | RESET RESET | 7 8 | PB11 (BTN_EN1) - * GND | 9 10| 5V GND | 9 10| NC (BTN_ENC) PC3 | 9 10| PC1 (BEEPER) - * ----- ----- ----- - * EXP1 EXP2 EXP3 + * ------ ------ ------ + * (BEEPER) PC1 |10 9 | PC3 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SD_SCK) (BEEPER) PC1 |10 9 | PC3 (BTN_ENC) + * (LCD_EN) PA4 | 8 7 | PA5 (LCD_RS) (BTN_EN1) PB11 | 8 7 | PA15 (SD_SS) (BTN_EN1) PB11 | 8 7 | RESET + * (LCD_D4) PA6 6 5 | PA7 (LCD_D5) (BTN_EN2) PB0 6 5 | PB15 (SD_MOSI) (BTN_EN2) PB0 6 5 | PA6 (LCD_D4) + * (LCD_D6) PC4 | 4 3 | PC5 (LCD_D7) (SD_DETECT) PC10 | 4 3 | RESET (LCD_RS) PA5 | 4 3 | PA4 (LCD_EN) + * GND | 2 1 | 5V GND | 2 1 | NC GND | 2 1 | 5V + * ------ ------ ------ + * EXP1 EXP2 "Ender-3 EXP1" */ +#define EXP1_03_PIN PC5 +#define EXP1_04_PIN PC4 +#define EXP1_05_PIN PA7 +#define EXP1_06_PIN PA6 +#define EXP1_07_PIN PA5 +#define EXP1_08_PIN PA4 +#define EXP1_09_PIN PC3 +#define EXP1_10_PIN PC1 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PC10 +#define EXP2_05_PIN PB15 +#define EXP2_06_PIN PB0 +#define EXP2_07_PIN PA15 +#define EXP2_08_PIN PB11 +#define EXP2_09_PIN PB13 +#define EXP2_10_PIN PB14 + +// "Ender-3 EXP1" +#define E3_EXP1_03_PIN PA4 +#define E3_EXP1_04_PIN PA5 +#define E3_EXP1_05_PIN PA6 +#define E3_EXP1_06_PIN PB0 +#define E3_EXP1_07_PIN -1 // RESET +#define E3_EXP1_08_PIN PB11 +#define E3_EXP1_09_PIN PC3 +#define E3_EXP1_10_PIN PC1 + #if HAS_WIRED_LCD - #define BEEPER_PIN PC1 - #define BTN_ENC PC3 - #define LCD_PINS_ENABLE PA4 - #define LCD_PINS_RS PA5 - #define BTN_EN1 PB11 - #define BTN_EN2 PB0 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PC4 - #define DOGLCD_CS PA7 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN #elif ENABLED(MKS_MINI_12864_V3) - #define DOGLCD_CS PA4 - #define DOGLCD_A0 PA5 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PA6 - #define NEOPIXEL_PIN PA7 - #define DOGLCD_MOSI PB15 - #define DOGLCD_SCK PB13 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN #define FORCE_SOFT_SPI #define SOFTWARE_SPI //#define LCD_SCREEN_ROT_180 #else - #define LCD_PINS_D4 PA6 + #define LCD_PINS_D4 EXP1_06_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 PA7 - #define LCD_PINS_D6 PC4 - #define LCD_PINS_D7 PC5 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if !defined(BTN_ENC_EN) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -192,30 +220,33 @@ #endif // HAS_WIRED_LCD +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #endif +#endif + // // SD Card // +#define SDCARD_CONNECTION ONBOARD #define SPI_DEVICE 2 #define ONBOARD_SPI_DEVICE 2 #define SDSS SD_SS_PIN -#define SDCARD_CONNECTION ONBOARD -#define SD_DETECT_PIN PC10 #define ONBOARD_SD_CS_PIN SD_SS_PIN +#define SD_DETECT_PIN PC10 // EXP2_04_PIN #define NO_SD_HOST_DRIVE // TODO: This is the only way to set SPI for SD on STM32 (for now) #define ENABLE_SPI2 -#define SD_SCK_PIN PB13 -#define SD_MISO_PIN PB14 -#define SD_MOSI_PIN PB15 -#define SD_SS_PIN PA15 - -#ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) -#endif -#ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) -#endif +#define SD_SCK_PIN EXP2_09_PIN +#define SD_MISO_PIN EXP2_10_PIN +#define SD_MOSI_PIN EXP2_05_PIN +#define SD_SS_PIN EXP2_07_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 73c77d092a..6373d70e38 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -112,16 +112,11 @@ #endif // !MKS_MINI_12864 - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif + // Alter timing for graphical display + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index e83bcb0a5c..204cd21c02 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -365,13 +365,9 @@ #endif - #ifndef BOARD_ST7920_DELAY_1 + #if ENABLED(U8GLIB_ST7920) #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 6e19b441c6..8f03a3678f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -299,16 +299,11 @@ #endif -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) - #endif +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) #endif #define HAS_SPI_FLASH 1 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index 3674f10ce7..a7a1dacd5b 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -331,7 +331,8 @@ #define ADC_KEYPAD_PIN PC0 // PIN6 of AUX1 #endif -#if HAS_MARLINUI_U8GLIB +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #define BOARD_ST7920_DELAY_2 DELAY_NS(250) #define BOARD_ST7920_DELAY_3 DELAY_NS(125) diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index 017195edee..ba6bf8aa7b 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -304,7 +304,8 @@ #define BTN_ENC EXP2_05_PIN // PE15 #endif -#if HAS_MARLINUI_U8GLIB +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 79a414d7d4..bb283201e4 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -182,7 +182,6 @@ * EXP2 EXP1 | * -------------------------------------------------------------------------------------- */ - #define EXP1_03_PIN PE13 #define EXP1_04_PIN PE12 #define EXP1_05_PIN PE11 @@ -286,16 +285,10 @@ #endif // Alter timing for graphical display - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index a768088c37..8d828f9e27 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -282,16 +282,10 @@ #endif // Alter timing for graphical display - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index fa49ff1495..5a1efc252b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -488,16 +488,10 @@ #endif // Alter timing for graphical display - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif + #if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index ec9ca32f7e..bb5800aee7 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -310,17 +310,15 @@ #define TMC_BAUD_RATE 19200 #endif -/** - * ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) - * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) - * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) - * ------ ----- - * EXP2 EXP1 +/** ------ ------ + * (BEEPER) PE8 |10 9 | PE7 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) + * (LCD_EN) PE9 | 8 7 | PE10 (LCD_RS) (BTN_EN1) PB2 | 8 7 | PA4 (SD_SS) + * (LCD_D4) PE12 6 5 | PE13 (LCD_D5) (BTN_EN2) PB1 6 5 | PA7 (MOSI) + * (LCD_D6) PE14 | 4 3 | PE15 (LCD_D7) (SD_DETECT) PC15 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - #define EXP1_03_PIN PE15 #define EXP1_04_PIN PE14 #define EXP1_05_PIN PE13 @@ -485,16 +483,10 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) - #endif +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 80) + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) #endif #if HAS_SPI_TFT diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 6daa34e059..8690f41ec9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -311,17 +311,15 @@ #define SDCARD_CONNECTION LCD #endif -/** - * ----- ----- - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PF12(SD_DETECT) (LCD_D7) PG7 | 3 4 | PG6 (LCD_D6) - * (MOSI)PB15 | 5 6 PF11(BTN_EN2) (LCD_D5) PG3 | 5 6 PG2 (LCD_D4) - * (SD_SS)PB12 | 7 8 | PG10(BTN_EN1) (LCD_RS) PD10 | 7 8 | PD11 (LCD_EN) - * (SCK)PB13 | 9 10| PB14(MISO) (BTN_ENC) PA8 | 9 10| PG4 (BEEPER) - * ----- ----- - * EXP2 EXP1 +/** ------ ------ + * (BEEPER) PG4 |10 9 | PA8 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SCK) + * (LCD_EN) PD11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PG10 | 8 7 | PB12 (SD_SS) + * (LCD_D4) PG2 6 5 | PG3 (LCD_D5) (BTN_EN2) PF11 6 5 | PB15 (MOSI) + * (LCD_D6) PG6 | 4 3 | PG7 (LCD_D7) (SD_DETECT) PF12 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ - #define EXP1_03_PIN PG7 #define EXP1_04_PIN PG6 #define EXP1_05_PIN PG3 @@ -506,12 +504,12 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB +#if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(90) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 90) #endif #ifndef BOARD_ST7920_DELAY_3 #define BOARD_ST7920_DELAY_3 DELAY_NS(600) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index e049f8fbd9..30163dc61d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -303,7 +303,6 @@ * ----- ----- * EXP2 EXP1 */ - #define EXP1_03_PIN PE13 #define EXP1_04_PIN PE12 #define EXP1_05_PIN PE11 @@ -489,12 +488,12 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB +#if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(120) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(80) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 80) #endif #ifndef BOARD_ST7920_DELAY_3 #define BOARD_ST7920_DELAY_3 DELAY_NS(580) diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 27ad7179df..cbed56d202 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -185,7 +185,6 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_03_PIN PE7 #define EXP1_04_PIN PE8 #define EXP1_05_PIN PE9 @@ -305,17 +304,9 @@ #define FIL_RUNOUT_PIN PA3 -// -// ST7920 Delays -// -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) - #endif +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index b50f1e4966..c922f13c60 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -250,16 +250,10 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif #if ENABLED(TOUCH_UI_FTDI_EVE) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 9ce8d33fa8..4bf8da564f 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -314,16 +314,10 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) - #endif +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) #endif #ifndef RGB_LED_R_PIN diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 5b5c24899f..4e0ff6f09d 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -276,7 +276,6 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_03_PIN PD10 #define EXP1_04_PIN PD11 #define EXP1_05_PIN PE15 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 03d8d19e94..af0f5fa17c 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -167,20 +167,13 @@ #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif - #endif - // Alter timing for graphical display - #if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) - #endif - #endif +#endif // HAS_WIRED_LCD +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) + #define BOARD_ST7920_DELAY_3 DELAY_NS(640) #endif diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 9d122c2642..280f98eae8 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -182,15 +182,9 @@ #define BTN_ENC PB12 #endif -// -// ST7920 Delays -// -#ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) -#endif -#ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) -#endif -#ifndef BOARD_ST7920_DELAY_3 +// Alter timing for graphical display +#if ENABLED(U8GLIB_ST7920) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) #define BOARD_ST7920_DELAY_3 DELAY_NS(715) #endif From d6501a93ec1c4e63e35f362b12ce332ce8f91336 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 29 Aug 2021 01:00:17 +0000 Subject: [PATCH 0591/2168] [cron] Bump distribution date (2021-08-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e1dd602e1e..a9ecab7bbf 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-28" +//#define STRING_DISTRIBUTION_DATE "2021-08-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2dff3aa92f..7a2510e014 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 "2021-08-28" + #define STRING_DISTRIBUTION_DATE "2021-08-29" #endif /** From 6d3dec8b6390bd1fb9ce24814249ab0e3cf8719e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 13:51:57 -0500 Subject: [PATCH 0592/2168] =?UTF-8?q?=F0=9F=8E=A8=20Update=20more=20EXP=20?= =?UTF-8?q?Headers?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 13 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 25 ++-- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 9 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 17 ++- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 4 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 12 +- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 72 ++++++----- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 2 +- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 122 ++++++++++-------- 11 files changed, 155 insertions(+), 125 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 9211a6a793..ff36796207 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -27,7 +27,7 @@ #include "env_validate.h" -#define BOARD_INFO_NAME "AZSMZ MINI" +#define BOARD_INFO_NAME "AZSMZ Mini" // // Servos @@ -76,6 +76,7 @@ // // Heaters / Fans // + // EFB #define HEATER_0_PIN P2_04 #define HEATER_BED_PIN P2_05 @@ -117,14 +118,14 @@ // // Ethernet pins // -#define ENET_MDIO P1_17 -#define ENET_RX_ER P1_14 -#define ENET_RXD1 P1_10 -#define ENET_MOC P1_16 #define REF_CLK P1_15 -#define ENET_RXD0 P1_09 +#define ENET_MDIO P1_17 +#define ENET_MOC P1_16 #define ENET_CRS P1_08 +#define ENET_RX_ER P1_14 #define ENET_TX_EN P1_04 +#define ENET_RXD0 P1_09 +#define ENET_RXD1 P1_10 #define ENET_TXD0 P1_00 #define ENET_TXD1 P1_01 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 b74870b30f..6404fbbf25 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -53,26 +53,25 @@ #define E0_ENABLE_PIN P2_12 -/** - * ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | 1.31 NC | 3 4 | NC - * 0.18 | 5 6 3.25 NC | 5 6 0.15 - * 1.23 | 7 8 | 3.26 0.16 | 7 8 | 0.18 - * 0.15 | 9 10 | 0.17 2.11 | 9 10 | 1.30 - * ------ ------ - * EXP2 EXP1 +/** ------ ------ + * 1.30 |10 9 | 2.11 0.17 |10 9 | 0.15 + * 0.18 | 8 7 | 0.16 3.26 | 8 7 | 1.23 + * 0.15 6 5 | NC 3.25 6 5 | 0.18 + * NC | 4 3 | NC 1.31 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ -#define EXP1_03_PIN -1 -#define EXP1_04_PIN -1 -#define EXP1_05_PIN -1 +#define EXP1_03_PIN -1 // NC +#define EXP1_04_PIN -1 // NC +#define EXP1_05_PIN -1 // NC #define EXP1_06_PIN P0_15 #define EXP1_07_PIN P0_16 #define EXP1_08_PIN P0_18 #define EXP1_09_PIN P2_11 #define EXP1_10_PIN P1_30 -#define EXP2_03_PIN -1 +#define EXP2_03_PIN -1 // RESET #define EXP2_04_PIN P1_31 #define EXP2_05_PIN P0_18 #define EXP2_06_PIN P3_25 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index d1d1eccc45..a9701bc8b5 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -215,6 +215,9 @@ * that the garbage/lines are erased immediately after the SD card accesses are completed. */ +// +// LCD / Controller +// #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -341,10 +344,8 @@ #endif // UNUSED -#define PIN_P0_27 P0_27 // EXP2/Onboard SD -#define PIN_P0_28 P0_28 // EXP2 -#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) -#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) /** * PWMs diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index a8a4d2de4e..124f0301b1 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -255,15 +255,14 @@ #define LED4_PIN P1_21 #endif -/** - * ----- ----- - * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) - * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 0.9 (SD_MOSI) - * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST - * GND | · · | 5V GND | · · | NC - * ----- ----- - * EXP1 EXP2 +/** ------ ------ + * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) + * (LCD_D4) 0.15 | 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 | 6 5 | 0.9 (SD_MOSI) + * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RST + * GND | 2 1 | 5V GND | 2 1 | NC + * ------ ------ + * EXP1 EXP2 */ #define EXP1_03_PIN P1_22 #define EXP1_04_PIN P1_00 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 5d23466071..6aa3372b3f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -96,7 +96,7 @@ /** ------ ------ * (BEEPER) PC10 |10 9 | PC11 (BTN_ENC) (MISO) PB4 |10 9 | PB3 (SCK) * (LCD_EN) PB6 | 8 7 | PC12 (LCD_RS) (BTN_EN1) PD2 | 8 7 | PA15 (SD_SS) - * (LCD_D4) PC13 | 6 5 | PB7 (LCD_D5) (BTN_EN2) PB8 | 6 5 | PB5 (MOSI) + * (LCD_D4) PC13 6 5 | PB7 (LCD_D5) (BTN_EN2) PB8 6 5 | PB5 (MOSI) * (LCD_D6) PC15 | 4 3 | PC14 (LCD_D7) (SD_DETECT) PB9 | 4 3 | RESET * GND | 2 1 | 5V GND | 2 1 | NC * ------ ------ diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 7694130a3e..6062755d3c 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -165,7 +165,7 @@ * ------ * PC6 |10 9 | PB2 * PB10 | 8 7 | PE8 - * PB14 | 6 5 | PB13 + * PB14 6 5 | PB13 * PB12 | 4 3 | PB15 * GND | 2 1 | 5V * ------ @@ -189,7 +189,7 @@ * ------ * ? |10 9 | PC5 * PB10 | 8 7 | ? - * PA6 | 6 5 | PA5 + * PA6 6 5 | PA5 * PA4 | 4 3 | PA7 * GND | 2 1 | 5V * ------ diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index f850b4a90b..6717455692 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -294,13 +294,14 @@ #define TFT_BACKLIGHT_PIN PD13 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #define TFT_CS_PIN TFT_CS_PIN - #define TFT_RS_PIN TFT_RS_PIN + #define FSMC_CS_PIN PD7 // NE4 + #define FSMC_RS_PIN PD11 // A0 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #ifdef TFT_CLASSIC_UI #define TFT_MARLINBG_COLOR 0x3186 // Grey @@ -309,11 +310,14 @@ #define TFT_BTOKMENU_COLOR 0x145F // Cyan #endif #define TFT_BUFFER_SIZE 14400 + #elif HAS_GRAPHICAL_TFT + #define TFT_RESET_PIN PC6 #define TFT_BACKLIGHT_PIN PD13 #define TFT_CS_PIN PD7 // NE4 #define TFT_RS_PIN PD11 // A0 + #endif #if NEED_TOUCH_PINS diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 2060ad86fe..0c2f2fc5db 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -130,29 +130,39 @@ #define RGB_LED_B_PIN PB6 #endif -/* -* EXP1 pinout for the LCD according to Fysetcs schematic for the Cheetah board -* ----- -* (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) -* (BTN_EN2) PC11 | 3 4 | PB14 (LCD_RS / MISO) -* (BTN_EN1) PC10 5 6 | PB13 (SCK) -* (LCD_EN) PB12 | 7 8 | PB15 (MOSI) -* GND | 9 10| 5V -* ----- -* EXP1 -* Note: The pin-numbers match the connector correctly and are not in reverse order like on the Ender-3 board. -* Note: Functionally the pins are assigned in the same order as on the Ender-3 board. -* Note: Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. -*/ +/** + * EXP1 pinout for the LCD according to FYSETC's Cheetah board schematic + * ------ + * (BEEPER) PC9 |10 9 | PC12 (BTN_ENC) + * (BTN_EN2) PC11 | 8 7 | PB14 (LCD_RS / MISO) + * (BTN_EN1) PC10 6 5 | PB13 (SCK) + * (LCD_EN) PB12 | 4 3 | PB15 (MOSI) + * GND | 2 1 | 5V + * ------ + * EXP1 + * + * Notes: + * - The pin-numbers match the connector correctly and are not in reverse order like on the Ender-3 board. + * - Functionally the pins are assigned in the same order as on the Ender-3 board. + * - Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. + */ +#define EXP1_03_PIN PB15 +#define EXP1_04_PIN PB12 +#define EXP1_05_PIN PB13 +#define EXP1_06_PIN PC10 +#define EXP1_07_PIN PB14 +#define EXP1_08_PIN PC11 +#define EXP1_09_PIN PC12 +#define EXP1_10_PIN PC9 #if HAS_WIRED_LCD - #define BEEPER_PIN PC9 + #define BEEPER_PIN EXP1_10_PIN #if HAS_MARLINUI_U8GLIB - #define DOGLCD_A0 PB14 - #define DOGLCD_CS PB12 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_SCK EXP1_05_PIN + #define DOGLCD_MOSI EXP1_03_PIN //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 @@ -162,30 +172,30 @@ #endif #endif - #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 PB13 // SCLK - #define LCD_PINS_ENABLE PB15 // DATA MOSI + #define LCD_PINS_RS EXP1_04_PIN // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 EXP1_05_PIN // SCLK + #define LCD_PINS_ENABLE EXP1_03_PIN // DATA MOSI //#define LCD_CONTRAST_INIT 190 #if IS_NEWPANEL - #define BTN_EN1 PC10 - #define BTN_EN2 PC11 - #define BTN_ENC PC12 + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_09_PIN #endif #endif #if ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN PC9 - #define CLCD_MOD_RESET PC11 - #define CLCD_SPI_CS PB12 + #define BEEPER_PIN EXP1_10_PIN + #define CLCD_MOD_RESET EXP1_08_PIN + #define CLCD_SPI_CS EXP1_04_PIN //#define CLCD_USE_SOFT_SPI // the Cheetah can use hardware-SPI so we do not really need this #if ENABLED(CLCD_USE_SOFT_SPI) - #define CLCD_SOFT_SPI_MOSI PB15 - #define CLCD_SOFT_SPI_MISO PB14 - #define CLCD_SOFT_SPI_SCLK PB13 + #define CLCD_SOFT_SPI_MOSI EXP1_03_PIN + #define CLCD_SOFT_SPI_MISO EXP1_07_PIN + #define CLCD_SOFT_SPI_SCLK EXP1_05_PIN #else #define CLCD_SPI_BUS 2 #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 4bf8da564f..da83ade4e0 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -195,7 +195,7 @@ * ------ ------ * PC9 |10 9 | PA8 PA6 |10 9 | PA5 * PC11 | 8 7 | PD2 PC6 | 8 7 | PA4 - * PC10 | 6 5 PC12 PC7 | 6 5 PA7 + * PC10 6 5 | PC12 PC7 6 5 | PA7 * PD0 | 4 3 | PD1 PB10 | 4 3 | RESET * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 38714d7da9..3b6a3f74f6 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -237,7 +237,7 @@ * ------ ------ * (BEEPER) PB2 |10 9 | PE10 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) * (LCD_EN) PE11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PE9 | 8 7 | PA4 (SPI1 CS) - * (LCD_D4) PD9 | 6 5 PD8 (LCD_D5) (BTN_EN2) PE8 | 6 5 PA7 (SPI1 MOSI) + * (LCD_D4) PD9 6 5 | PD8 (LCD_D5) (BTN_EN2) PE8 6 5 | PA7 (SPI1 MOSI) * (LCD_D6) PE15 | 4 3 | PE7 (LCD_D7) (SPI1_RS) PB11 | 4 3 | RESET * GND | 2 1 | 5V GND | 2 1 | 3.3V * ------ ------ diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 88e2d1804e..c28da71347 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -215,8 +215,8 @@ // Onboard SD card // NOT compatible with LCD // -// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled -#if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD +// Detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled +#if SD_CONNECTION_IS(ONBOARD) #if USE_NEW_SPI_API #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) #else @@ -230,17 +230,44 @@ #define SD_DETECT_PIN PD12 #endif -/* +/** ------ ------ + * (BEEPER) PC5 |10 9 | PE13 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) + * (LCD_EN) PD13 | 8 7 | PC6 (LCD_RS) (BTN_EN1) PE8 | 8 7 | PE10 (SPI1 CS) + * (LCD_D4) PE14 6 5 | PE15 (LCD_D5) (BTN_EN2) PE11 6 5 | PA7 (SPI1 MOSI) + * (LCD_D6) PD11 | 4 3 | PD10 (LCD_D7) (SPI DET) PE12 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_03_PIN PD10 +#define EXP1_04_PIN PD11 +#define EXP1_05_PIN PE15 +#define EXP1_06_PIN PE14 +#define EXP1_07_PIN PC6 +#define EXP1_08_PIN PD13 +#define EXP1_09_PIN PE13 +#define EXP1_10_PIN PC5 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PE12 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PE11 +#define EXP2_07_PIN PE10 +#define EXP2_08_PIN PE8 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + // // LCD SD // -#if SDCARD_CONNECTION == LCD +/* +#if SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 + #define SDSS EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN #endif */ @@ -257,17 +284,6 @@ #define SPI_FLASH_SCK_PIN PB13 #endif -/** - * ----- ----- - * (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK) - * (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS) - * (LCD_D4)PE14 | · · | PE15(LCD_D5) (BTN_EN2) PE11 | · · | PA7 (SPI1 MOSI) - * (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI DET) PE12 | · · | RESET - * GND | · · | 5V GND | · · | 3.3V - * ----- ----- - * EXP1 EXP2 - */ - #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 @@ -285,21 +301,21 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif - #define TFT_CS_PIN PD11 - #define TFT_SCK_PIN PA5 - #define TFT_MISO_PIN PA6 - #define TFT_MOSI_PIN PA7 - #define TFT_DC_PIN PD10 - #define TFT_RST_PIN PC6 + #define TFT_CS_PIN EXP1_04_PIN + #define TFT_SCK_PIN EXP2_09_PIN + #define TFT_MISO_PIN EXP2_10_PIN + #define TFT_MOSI_PIN EXP2_05_PIN + #define TFT_DC_PIN EXP1_03_PIN + #define TFT_RST_PIN EXP1_07_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN PC6 - #define TFT_BACKLIGHT_PIN PD13 + #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_BACKLIGHT_PIN EXP1_08_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN EXP1_08_PIN #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif @@ -307,15 +323,15 @@ #define TFT_HEIGHT 320 #endif - #define TOUCH_CS_PIN PE14 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI @@ -325,22 +341,22 @@ #elif HAS_WIRED_LCD - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 PD11 - #define DOGLCD_CS PE15 - //#define DOGLCD_SCK PA5 - //#define DOGLCD_MOSI PA7 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + //#define DOGLCD_SCK EXP2_09_PIN + //#define DOGLCD_MOSI EXP2_05_PIN // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B @@ -348,15 +364,15 @@ #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PE14 + #define LCD_PINS_D4 EXP1_06_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 PE15 - #define LCD_PINS_D6 PD11 - #define LCD_PINS_D7 PD10 + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) + #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) #define BOARD_ST7920_DELAY_3 DELAY_NS(600) #endif // !MKS_MINI_12864 From 09a83d565e0db2157baa3662020500476b931ec6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 28 Aug 2021 17:46:22 -0500 Subject: [PATCH 0593/2168] =?UTF-8?q?=F0=9F=A9=B9=20Sensorless=20homing=20?= =?UTF-8?q?tweak?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 20243ae0ea..fd49aada6b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2005,7 +2005,7 @@ #define HAS_TMC_SW_SERIAL 1 #endif -#if !USE_SENSORLESS +#if DISABLED(SENSORLESS_HOMING) #undef SENSORLESS_BACKOFF_MM #endif From 4b4de71304a426e0d9b2696dae4e82eb55ba7079 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 13:57:47 -0500 Subject: [PATCH 0594/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Improve=20G2/G3?= =?UTF-8?q?=20arc=20handling=20(#22599)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 25 ++-- Marlin/src/core/macros.h | 2 + Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/G2_G3.cpp | 235 ++++++++++++++++++------------ Marlin/src/inc/SanityCheck.h | 14 +- 6 files changed, 174 insertions(+), 106 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 80606df733..9e232f95bb 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2052,20 +2052,23 @@ // // G2/G3 Arc Support // -#define ARC_SUPPORT // Disable this feature to save ~3226 bytes +#define ARC_SUPPORT // Requires ~3226 bytes #if ENABLED(ARC_SUPPORT) - #define MM_PER_ARC_SEGMENT 1 // (mm) Length (or minimum length) of each arc segment - //#define ARC_SEGMENTS_PER_R 1 // Max segment length, MM_PER = Min - #define MIN_ARC_SEGMENTS 24 // Minimum number of segments in a complete circle - //#define ARC_SEGMENTS_PER_SEC 50 // Use feedrate to choose segment length (with MM_PER_ARC_SEGMENT as the minimum) - #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections - //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles - //#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes - //#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure + #define MIN_ARC_SEGMENT_MM 0.1 // (mm) Minimum length of each arc segment + #define MAX_ARC_SEGMENT_MM 1.0 // (mm) Maximum length of each arc segment + #define MIN_CIRCLE_SEGMENTS 72 // Minimum number of segments in a complete circle + //#define ARC_SEGMENTS_PER_SEC 50 // Use the feedrate to choose the segment length + #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections + //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles + //#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure #endif -// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. -//#define BEZIER_CURVE_SUPPORT +// G5 Bézier Curve Support with XYZE destination and IJPQ offsets +//#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes + +#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) + //#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes +#endif /** * Direct Stepping diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 86368bf5e7..0174e21add 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -260,6 +260,7 @@ #define CODE_3( A,B,C,...) A; B; C #define CODE_2( A,B,...) A; B #define CODE_1( A,...) A +#define CODE_0(...) #define _CODE_N(N,V...) CODE_##N(V) #define CODE_N(N,V...) _CODE_N(N,V) @@ -279,6 +280,7 @@ #define GANG_3( A,B,C,...) A B C #define GANG_2( A,B,...) A B #define GANG_1( A,...) A +#define GANG_0(...) #define _GANG_N(N,V...) GANG_##N(V) #define GANG_N(N,V...) _GANG_N(N,V) #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 7933c3141a..94496f2b25 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -136,7 +136,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { } /** - * Set XYZE destination and feedrate from the current GCode command + * Set XYZIJKE destination and feedrate from the current GCode command * * - Set destination from included axis codes * - Set to current for missing axis codes diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index eb79180c69..cc6979b74c 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -71,7 +71,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { #endif #endif - get_destination_from_command(); // Get X Y Z E F (and set cutter power) + get_destination_from_command(); // Get X Y [Z[I[J[K]]]] [E] F (and set cutter power) #ifdef G0_FEEDRATE if (fast_move) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 094afdb70e..f9f9c2b3da 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -39,14 +39,21 @@ #undef N_ARC_CORRECTION #define N_ARC_CORRECTION 1 #endif +#ifndef MIN_CIRCLE_SEGMENTS + #define MIN_CIRCLE_SEGMENTS 72 // 5° per segment +#endif +#if !defined(MAX_ARC_SEGMENT_MM) && defined(MIN_ARC_SEGMENT_MM) + #define MAX_ARC_SEGMENT_MM MIN_ARC_SEGMENT_MM +#elif !defined(MIN_ARC_SEGMENT_MM) && defined(MAX_ARC_SEGMENT_MM) + #define MIN_ARC_SEGMENT_MM MAX_ARC_SEGMENT_MM +#endif + +#define ARC_LIJK_CODE(L,I,J,K) CODE_N(SUB2(LINEAR_AXES),L,I,J,K) +#define ARC_LIJKE_CODE(L,I,J,K,E) ARC_LIJK_CODE(L,I,J,K); CODE_ITEM_E(E) /** - * Plan an arc in 2 dimensions, with optional linear motion in a 3rd dimension - * - * The arc is traced by generating many small linear segments, as configured by - * MM_PER_ARC_SEGMENT (Default 1mm). In the future we hope more slicers will include - * an option to generate G2/G3 arcs for curved surfaces, as this will allow faster - * boards to produce much smoother curved surfaces. + * Plan an arc in 2 dimensions, with linear motion in the other axes. + * The arc is traced with many small linear segments according to the configuration. */ void plan_arc( const xyze_pos_t &cart, // Destination position @@ -55,41 +62,45 @@ void plan_arc( const uint8_t circles // Take the scenic route ) { #if ENABLED(CNC_WORKSPACE_PLANES) - AxisEnum p_axis, q_axis, l_axis; + AxisEnum axis_p, axis_q, axis_l; switch (gcode.workspace_plane) { default: - case GcodeSuite::PLANE_XY: p_axis = X_AXIS; q_axis = Y_AXIS; l_axis = Z_AXIS; break; - case GcodeSuite::PLANE_YZ: p_axis = Y_AXIS; q_axis = Z_AXIS; l_axis = X_AXIS; break; - case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break; + case GcodeSuite::PLANE_XY: axis_p = X_AXIS; axis_q = Y_AXIS; axis_l = Z_AXIS; break; + case GcodeSuite::PLANE_YZ: axis_p = Y_AXIS; axis_q = Z_AXIS; axis_l = X_AXIS; break; + case GcodeSuite::PLANE_ZX: axis_p = Z_AXIS; axis_q = X_AXIS; axis_l = Y_AXIS; break; } #else - constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS); + constexpr AxisEnum axis_p = X_AXIS, axis_q = Y_AXIS OPTARG(HAS_Z_AXIS, axis_l = Z_AXIS); #endif // Radius vector from center to current location ab_float_t rvec = -offset; const float radius = HYPOT(rvec.a, rvec.b), - center_P = current_position[p_axis] - rvec.a, - center_Q = current_position[q_axis] - rvec.b, - rt_X = cart[p_axis] - center_P, - rt_Y = cart[q_axis] - center_Q - OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]); + center_P = current_position[axis_p] - rvec.a, + center_Q = current_position[axis_q] - rvec.b, + rt_X = cart[axis_p] - center_P, + rt_Y = cart[axis_q] - center_Q; - #ifdef MIN_ARC_SEGMENTS - uint16_t min_segments = MIN_ARC_SEGMENTS; - #else - constexpr uint16_t min_segments = 1; - #endif + ARC_LIJK_CODE( + const float start_L = current_position[axis_l], + const float start_I = current_position.i, + const float start_J = current_position.j, + const float start_K = current_position.k + ); // Angle of rotation between position and target from the circle center. float angular_travel, abs_angular_travel; + // Minimum number of segments in an arc move + uint16_t min_segments = 1; + // Do a full circle if starting and ending positions are "identical" - if (NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { + if (NEAR(current_position[axis_p], cart[axis_p]) && NEAR(current_position[axis_q], cart[axis_q])) { // Preserve direction for circles angular_travel = clockwise ? -RADIANS(360) : RADIANS(360); abs_angular_travel = RADIANS(360); + min_segments = MIN_CIRCLE_SEGMENTS; } else { // Calculate the angle @@ -106,61 +117,90 @@ void plan_arc( abs_angular_travel = ABS(angular_travel); - #ifdef MIN_ARC_SEGMENTS - min_segments = CEIL(min_segments * abs_angular_travel / RADIANS(360)); - NOLESS(min_segments, 1U); - #endif + // Apply minimum segments to the arc + const float portion_of_circle = abs_angular_travel / RADIANS(360); // Portion of a complete circle (0 < N < 1) + min_segments = CEIL((MIN_CIRCLE_SEGMENTS) * portion_of_circle); // Minimum segments for the arc } - #if HAS_Z_AXIS - float linear_travel = cart[l_axis] - start_L; - #endif - #if HAS_EXTRUDERS - float extruder_travel = cart.e - current_position.e; - #endif + ARC_LIJKE_CODE( + float travel_L = cart[axis_l] - start_L, + float travel_I = cart.i - start_I, + float travel_J = cart.j - start_J, + float travel_K = cart.k - start_K, + float travel_E = cart.e - current_position.e + ); - // If circling around... + // If "P" specified circles, call plan_arc recursively then continue with the rest of the arc if (TERN0(ARC_P_CIRCLES, circles)) { - const float total_angular = abs_angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder - part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total + const float total_angular = abs_angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder + part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total - #if HAS_Z_AXIS - const float l_per_circle = linear_travel * part_per_circle; // L movement per circle - #endif - #if HAS_EXTRUDERS - const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle - #endif + ARC_LIJKE_CODE( + const float per_circle_L = travel_L * part_per_circle, // L movement per circle + const float per_circle_I = travel_I * part_per_circle, + const float per_circle_J = travel_J * part_per_circle, + const float per_circle_K = travel_K * part_per_circle, + const float per_circle_E = travel_E * part_per_circle // E movement per circle + ); - xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position + xyze_pos_t temp_position = current_position; for (uint16_t n = circles; n--;) { - TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis - TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle); // Destination L axis - plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle + ARC_LIJKE_CODE( // Destination Linear Axes + temp_position[axis_l] += per_circle_L, + temp_position.i += per_circle_I, + temp_position.j += per_circle_J, + temp_position.k += per_circle_K, + temp_position.e += per_circle_E // Destination E axis + ); + plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle } - TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]); - TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e); + ARC_LIJKE_CODE( + travel_L = cart[axis_l] - current_position[axis_l], + travel_I = cart.i - current_position.i, + travel_J = cart.j - current_position.j, + travel_K = cart.k - current_position.k, + travel_E = cart.e - current_position.e + ); } - const float flat_mm = radius * abs_angular_travel, - mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) flat_mm; - if (mm_of_travel < 0.001f) return; + // Millimeters in the arc, assuming it's flat + const float flat_mm = radius * abs_angular_travel; + // Return if the move is near zero + if (flat_mm < 0.0001f + GANG_N(SUB2(LINEAR_AXES), + && travel_L < 0.0001f, + && travel_I < 0.0001f, + && travel_J < 0.0001f, + && travel_K < 0.0001f + ) + ) return; + + // Feedrate for the move, scaled by the feedrate multiplier const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); - // Start with a nominal segment length - float seg_length = ( - #ifdef ARC_SEGMENTS_PER_R - constrain(MM_PER_ARC_SEGMENT * radius, MM_PER_ARC_SEGMENT, ARC_SEGMENTS_PER_R) - #elif ARC_SEGMENTS_PER_SEC - _MAX(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MM_PER_ARC_SEGMENT) + // Get the nominal segment length based on settings + const float nominal_segment_mm = ( + #if ARC_SEGMENTS_PER_SEC // Length based on segments per second and feedrate + constrain(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM) #else - MM_PER_ARC_SEGMENT + MAX_ARC_SEGMENT_MM // Length using the maximum segment size #endif ); - // Divide total travel by nominal segment length - uint16_t segments = FLOOR(mm_of_travel / seg_length); - NOLESS(segments, min_segments); // At least some segments - seg_length = mm_of_travel / segments; + + // Number of whole segments based on the nominal segment length + const float nominal_segments = _MAX(FLOOR(flat_mm / nominal_segment_mm), min_segments); + + // A new segment length based on the required minimum + const float segment_mm = constrain(flat_mm / nominal_segments, MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM); + + // The number of whole segments in the arc, ignoring the remainder + uint16_t segments = FLOOR(flat_mm / segment_mm); + + // Are the segments now too few to reach the destination? + const float segmented_length = segment_mm * segments; + const bool tooshort = segmented_length < flat_mm - 0.0001f; + const float proportion = tooshort ? segmented_length / flat_mm : 1.0f; /** * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, @@ -190,26 +230,36 @@ void plan_arc( */ // Vector rotation matrix values xyze_pos_t raw; - const float theta_per_segment = angular_travel / segments, + const float theta_per_segment = proportion * angular_travel / segments, sq_theta_per_segment = sq(theta_per_segment), sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6, cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation - #if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL) - const float linear_per_segment = linear_travel / segments; - #endif - #if HAS_EXTRUDERS - const float extruder_per_segment = extruder_travel / segments; + #if DISABLED(AUTO_BED_LEVELING_UBL) + ARC_LIJK_CODE( + const float per_segment_L = proportion * travel_L / segments, + const float per_segment_I = proportion * travel_I / segments, + const float per_segment_J = proportion * travel_J / segments, + const float per_segment_K = proportion * travel_K / segments + ); #endif - // Initialize the linear axis - TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]); + CODE_ITEM_E(const float extruder_per_segment = proportion * travel_E / segments); - // Initialize the extruder axis - TERN_(HAS_EXTRUDERS, raw.e = current_position.e); + // For shortened segments, run all but the remainder in the loop + if (tooshort) segments++; + + // Initialize all linear axes and E + ARC_LIJKE_CODE( + raw[axis_l] = current_position[axis_l], + raw.i = current_position.i, + raw.j = current_position.j, + raw.k = current_position.k, + raw.e = current_position.e + ); #if ENABLED(SCARA_FEEDRATE_SCALING) - const float inv_duration = scaled_fr_mm_s / seg_length; + const float inv_duration = scaled_fr_mm_s / segment_mm; #endif millis_t next_idle_ms = millis() + 200UL; @@ -221,8 +271,9 @@ void plan_arc( for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times thermalManager.manage_heater(); - if (ELAPSED(millis(), next_idle_ms)) { - next_idle_ms = millis() + 200UL; + const millis_t ms = millis(); + if (ELAPSED(ms, next_idle_ms)) { + next_idle_ms = ms + 200UL; idle(); } @@ -250,13 +301,16 @@ void plan_arc( } // Update raw location - raw[p_axis] = center_P + rvec.a; - raw[q_axis] = center_Q + rvec.b; - #if HAS_Z_AXIS - raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment); - #endif - - TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment); + raw[axis_p] = center_P + rvec.a; + raw[axis_q] = center_Q + rvec.b; + ARC_LIJKE_CODE( + #if ENABLED(AUTO_BED_LEVELING_UBL) + raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K + #else + raw[axis_l] += per_segment_L, raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K + #endif + , raw.e += extruder_per_segment + ); apply_motion_limits(raw); @@ -264,14 +318,15 @@ void plan_arc( planner.apply_leveling(raw); #endif - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - )) break; + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) + break; } // Ensure last segment arrives at target location. raw = cart; - TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); + #if ENABLED(AUTO_BED_LEVELING_UBL) + ARC_LIJK_CODE(raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K); + #endif apply_motion_limits(raw); @@ -279,11 +334,11 @@ void plan_arc( planner.apply_leveling(raw); #endif - planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) - ); + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); - TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); + #if ENABLED(AUTO_BED_LEVELING_UBL) + ARC_LIJK_CODE(raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K); + #endif current_position = raw; } // plan_arc @@ -325,7 +380,7 @@ void GcodeSuite::G2_G3(const bool clockwise) { relative_mode = true; #endif - get_destination_from_command(); // Get X Y Z E F (and set cutter power) + get_destination_from_command(); // Get X Y [Z[I[J[K]]]] [E] F (and set cutter power) TERN_(SF_ARC_FIX, relative_mode = relative_mode_backup); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index e02e903551..a146b95ba6 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -585,12 +585,20 @@ #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." #elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" -#elif MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) +#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) + #error "LCD_ALEPHOBJECTS_CLCD_UI is now LCD_LULZBOT_CLCD_UI." +#elif defined(MIN_ARC_SEGMENTS) + #error "MIN_ARC_SEGMENTS is now MIN_CIRCLE_SEGMENTS." +#elif defined(ARC_SEGMENTS_PER_R) + #error "ARC_SUPPORT no longer uses ARC_SEGMENTS_PER_R." +#elif ENABLED(ARC_SUPPORT) && (!defined(MIN_ARC_SEGMENT_MM) || !defined(MAX_ARC_SEGMENT_MM)) + #error "ARC_SUPPORT now requires MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM." +#endif + +#if MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) #warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." #elif MOTHERBOARD == BOARD_BTT_SKR_E3_TURBO && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) #warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." -#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) - #warning "LCD_ALEPHOBJECTS_CLCD_UI is now LCD_LULZBOT_CLCD_UI." #endif constexpr float arm[] = AXIS_RELATIVE_MODES; From f721c44c225c084785b296dac43df7b272702b7d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 15:15:53 -0500 Subject: [PATCH 0595/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20SDSUPPORT=20for?= =?UTF-8?q?=20SKR=20CR-6=20(#22668)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Sebastiaan Dammann --- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index c614a2dbb9..f58f13dc2f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -165,6 +165,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card + #define SDSS ONBOARD_SD_CS_PIN #endif // From ab03c9a56063c4ae0e27f46a5622ffe1564b0c1b Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sun, 29 Aug 2021 16:03:10 -0600 Subject: [PATCH 0596/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Enhance=20and=20?= =?UTF-8?q?fix=20FTDI=20Eve=20Touch=20UI=20file=20select=20(#22651)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/arrows.cpp | 52 +++++ .../ftdi_eve_lib/extended/arrows.h | 28 +++ .../ftdi_eve_lib/extended/ftdi_extended.h | 1 + .../ftdi_eve_lib/extended/grid_layout.h | 36 ++-- .../generic/bed_mesh_view_screen.cpp | 6 - .../generic/bed_mesh_view_screen.h | 1 - .../generic/files_screen.cpp | 181 ++++++++++-------- .../ftdi_eve_touch_ui/generic/files_screen.h | 12 +- .../generic/leveling_menu.cpp | 5 +- 9 files changed, 209 insertions(+), 113 deletions(-) create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.cpp create mode 100644 Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.cpp new file mode 100644 index 0000000000..0a45c0d339 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.cpp @@ -0,0 +1,52 @@ +/************** + * arrows.cpp * + **************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - SynDaver 3D * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "ftdi_extended.h" + +#if ENABLED(FTDI_EXTENDED) + +#define COORD(X,Y) cx + s*(swapXY ? Y : (flipX ? -X : X)), cy + s*(swapXY ? (flipX ? -X : X) : Y) + +namespace FTDI { + + void drawArrow(int x, int y, int w, int h, Direction direction) { + const bool swapXY = direction == UP || direction == DOWN; + const bool flipX = direction == UP || direction == LEFT; + const int s = min(w,h); + const int cx = (x + w/2)*16; + const int cy = (y + h/2)*16; + + CommandProcessor cmd; + cmd.cmd(SAVE_CONTEXT()) + .cmd(LINE_WIDTH(s/2)) + .cmd(BEGIN(LINES)) + .cmd(VERTEX2F(COORD( 5, 0))) + .cmd(VERTEX2F(COORD( 2,-2))) + .cmd(VERTEX2F(COORD( 5, 0))) + .cmd(VERTEX2F(COORD( 2, 2))) + .cmd(VERTEX2F(COORD( 5, 0))) + .cmd(VERTEX2F(COORD(-5, 0))) + .cmd(RESTORE_CONTEXT()); + } + +} // namespace FTDI + +#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.h new file mode 100644 index 0000000000..e9592d47a0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/arrows.h @@ -0,0 +1,28 @@ +/************ + * arrows.h * + ************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2021 - SynDaver 3D * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +namespace FTDI { + enum Direction {UP, DOWN, LEFT, RIGHT}; + + void drawArrow(int x, int y, int w, int h, Direction direction); +} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h index bf9858f6eb..e99c798eea 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h @@ -48,6 +48,7 @@ #include "sound_list.h" #include "polygon.h" #include "poly_ui.h" + #include "arrows.h" #include "text_box.h" #include "text_ellipsis.h" #include "adjuster_widget.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h index dd94685c98..813f4f0484 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h @@ -54,23 +54,33 @@ #define EDGE_L 0 #define EDGE_R 0 -// GRID_X and GRID_Y computes the positions of the divisions on +// _GRID_X and _GRID_Y computes the positions of the divisions on // the layout grid. -#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R-EDGE_L)/GRID_COLS+EDGE_L) -#define GRID_Y(y) ((y)*(FTDI::display_height-EDGE_B-EDGE_T)/GRID_ROWS+EDGE_T) +#define _GRID_X(x) ((x)*(FTDI::display_width-EDGE_R-EDGE_L)/GRID_COLS+EDGE_L) +#define _GRID_Y(y) ((y)*(FTDI::display_height-EDGE_B-EDGE_T)/GRID_ROWS+EDGE_T) + +// BOX_X, BOX_Y, BOX_W and BOX_X returns the top-left and width +// and height of position on the grid. + +#define BOX_X(x) (_GRID_X((x)-1)) +#define BOX_Y(y) (_GRID_Y((y)-1)) +#define BOX_W(w) (_GRID_X(w) - _GRID_X(0)) +#define BOX_H(h) (_GRID_Y(h) - _GRID_Y(0)) // BTN_X, BTN_Y, BTN_W and BTN_X returns the top-left and width // and height of a button, taking into account the button margins. -#define BTN_X(x) (GRID_X((x)-1) + MARGIN_L) -#define BTN_Y(y) (GRID_Y((y)-1) + MARGIN_T) -#define BTN_W(w) (GRID_X(w) - GRID_X(0) - MARGIN_L - MARGIN_R) -#define BTN_H(h) (GRID_Y(h) - GRID_Y(0) - MARGIN_T - MARGIN_B) +#define BTN_X(x) (BOX_X(x) + MARGIN_L) +#define BTN_Y(y) (BOX_Y(y) + MARGIN_T) +#define BTN_W(w) (BOX_W(w) - MARGIN_L - MARGIN_R) +#define BTN_H(h) (BOX_H(h) - MARGIN_T - MARGIN_B) -// Abbreviations for common phrases, to allow a button to be -// defined in one line of source. +// Abbreviations for common phrases, to allow a box or button +// to be defined in one line of source. #define BTN_POS(x,y) BTN_X(x), BTN_Y(y) #define BTN_SIZE(w,h) BTN_W(w), BTN_H(h) +#define BOX_POS(x,y) BOX_X(x), BOX_Y(y) +#define BOX_SIZE(w,h) BOX_W(w), BOX_H(h) // Draw a reference grid for ease of spacing out widgets. #define DRAW_LAYOUT_GRID \ @@ -78,13 +88,13 @@ cmd.cmd(LINE_WIDTH(4)); \ for (int i = 1; i <= GRID_COLS; i++) { \ cmd.cmd(BEGIN(LINES)); \ - cmd.cmd(VERTEX2F(GRID_X(i) *16, 0 *16)); \ - cmd.cmd(VERTEX2F(GRID_X(i) *16, FTDI::display_height *16)); \ + cmd.cmd(VERTEX2F(_GRID_X(i) *16, 0 *16)); \ + cmd.cmd(VERTEX2F(_GRID_X(i) *16, FTDI::display_height *16)); \ } \ for (int i = 1; i < GRID_ROWS; i++) { \ cmd.cmd(BEGIN(LINES)); \ - cmd.cmd(VERTEX2F(0 *16, GRID_Y(i) *16)); \ - cmd.cmd(VERTEX2F(FTDI::display_width *16, GRID_Y(i) *16)); \ + cmd.cmd(VERTEX2F(0 *16, _GRID_Y(i) *16)); \ + cmd.cmd(VERTEX2F(FTDI::display_width *16, _GRID_Y(i) *16)); \ } \ cmd.cmd(LINE_WIDTH(16)); \ } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 552cd831ea..8db2d2ef70 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -157,12 +157,6 @@ void BedMeshViewScreen::doProbe() { injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); } -void BedMeshViewScreen::doMeshValidation() { - mydata.count = 0; - GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("G28\nM117 Heating...\nG26 R X0 Y0\nG27")); -} - void BedMeshViewScreen::show() { injectCommands_P(PSTR("G29 L1")); GOTO_SCREEN(BedMeshViewScreen); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h index 0bb88f7f96..90a90c233e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h @@ -43,6 +43,5 @@ class BedMeshViewScreen : public BedMeshBase, public CachedScreen "), OPT_CENTERY | OPT_RIGHTX); - } + draw_text_with_ellipsis(cmd, bx,by, bw - (is_dir ? 20 : 0), bh, filename, OPT_CENTERY, font_medium); + if (is_dir && !is_highlighted) cmd.text(bx, by, bw, bh, F("> "), OPT_CENTERY | OPT_RIGHTX); #if ENABLED(SCROLL_LONG_FILENAMES) - if (is_highlighted) { - cmd.cmd(RESTORE_CONTEXT()); - } + if (is_highlighted) cmd.cmd(RESTORE_CONTEXT()); #endif } void FilesScreen::drawFileList() { FileList files; - mydata.num_page = max(1,ceil(float(files.count()) / files_per_page)); + mydata.num_page = max(1,ceil(float(files.count()) / FILES_PER_PAGE)); mydata.cur_page = min(mydata.cur_page, mydata.num_page-1); mydata.flags.is_root = files.isAtRootDir(); - #undef MARGIN_T - #undef MARGIN_B - #define MARGIN_T 0 - #define MARGIN_B 0 - uint16_t fileIndex = mydata.cur_page * files_per_page; - for (uint8_t i = 0; i < files_per_page; i++, fileIndex++) { - if (files.seek(fileIndex)) { + uint16_t fileIndex = mydata.cur_page * FILES_PER_PAGE; + for (uint8_t i = 0; i < FILES_PER_PAGE; i++, fileIndex++) { + if (files.seek(fileIndex)) drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); - } - else { + else break; - } } } void FilesScreen::drawHeader() { - const bool prev_enabled = mydata.cur_page > 0; - const bool next_enabled = mydata.cur_page < (mydata.num_page - 1); - - #undef MARGIN_T - #undef MARGIN_B - #define MARGIN_T 0 - #define MARGIN_B 2 - char str[16]; - sprintf_P(str, PSTR("Page %d of %d"), - mydata.cur_page + 1, mydata.num_page); + sprintf_P(str, PSTR("Page %d of %d"), mydata.cur_page + 1, mydata.num_page); CommandProcessor cmd; cmd.colors(normal_btn) .font(font_small) - .tag(0).button(BTN_POS(2,1), BTN_SIZE(4,header_h), str, OPT_CENTER | OPT_FLAT) - .font(font_medium) - .colors(action_btn) - .tag(241).enabled(prev_enabled).button(BTN_POS(1,1), BTN_SIZE(1,header_h), F("<")) - .tag(242).enabled(next_enabled).button(BTN_POS(6,1), BTN_SIZE(1,header_h), F(">")); + .tag(0).button(HEAD_POS, str, OPT_CENTER | OPT_FLAT); +} + +void FilesScreen::drawArrows() { + const bool prev_enabled = mydata.cur_page > 0; + const bool next_enabled = mydata.cur_page < (mydata.num_page - 1); + + CommandProcessor cmd; + cmd.colors(normal_btn); + cmd.tag(242).enabled(prev_enabled).button(PREV_POS, F("")); if (prev_enabled) drawArrow(PREV_POS, PREV_DIR); + cmd.tag(243).enabled(next_enabled).button(NEXT_POS, F("")); if (next_enabled) drawArrow(NEXT_POS, NEXT_DIR); } void FilesScreen::drawFooter() { - #undef MARGIN_T - #undef MARGIN_B - #if ENABLED(TOUCH_UI_PORTRAIT) - #define MARGIN_T 15 - #define MARGIN_B 5 - #else - #define MARGIN_T 5 - #define MARGIN_B 5 - #endif - const bool has_selection = mydata.selected_tag != 0xFF; - const uint8_t back_tag = mydata.flags.is_root ? 240 : 245; - const uint8_t y = GRID_ROWS - footer_h + 1; - const uint8_t h = footer_h; + const bool has_selection = mydata.selected_tag != 0xFF; CommandProcessor cmd; cmd.colors(normal_btn) .font(font_medium) - .colors(has_selection ? normal_btn : action_btn) - .tag(back_tag).button(BTN_POS(4,y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_DONE)) - .enabled(has_selection) + .colors(has_selection ? normal_btn : action_btn); + + if (mydata.flags.is_root) + cmd.tag(240).button(BTN2_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + else + cmd.tag(245).button(BTN2_POS, F("Up Dir")); + + cmd.enabled(has_selection) .colors(has_selection ? action_btn : normal_btn); if (mydata.flags.is_dir) - cmd.tag(244).button(BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_OPEN)); + cmd.tag(244).button(BTN1_POS, GET_TEXT_F(MSG_BUTTON_OPEN)); else - cmd.tag(243).button(BTN_POS(1, y), BTN_SIZE(3,h), GET_TEXT_F(MSG_BUTTON_PRINT)); + cmd.tag(241).button(BTN1_POS, GET_TEXT_F(MSG_BUTTON_PRINT)); +} + +void FilesScreen::drawFileButton(const char *filename, uint8_t tag, bool is_dir, bool is_highlighted) { + #undef MARGIN_L + #undef MARGIN_R + #define MARGIN_L 0 + #define MARGIN_R 0 + drawFileButton(LIST_POS, filename, tag, is_dir, is_highlighted); } void FilesScreen::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { drawHeader(); + drawArrows(); drawSelectedFile(); drawFooter(); } @@ -200,48 +215,50 @@ void FilesScreen::gotoPage(uint8_t page) { bool FilesScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 240: GOTO_PREVIOUS(); return true; - case 241: + case 240: // Done button + GOTO_PREVIOUS(); + return true; + case 241: // Print highlighted file + ConfirmStartPrintDialogBox::show(getSelectedFileIndex()); + return true; + case 242: // Previous page if (mydata.cur_page > 0) { gotoPage(mydata.cur_page-1); } break; - case 242: + case 243: // Next page if (mydata.cur_page < (mydata.num_page-1)) { gotoPage(mydata.cur_page+1); } break; - case 243: - ConfirmStartPrintDialogBox::show(getSelectedFileIndex()); - return true; - case 244: + case 244: // Select directory { FileList files; files.changeDir(getSelectedShortFilename()); gotoPage(0); } break; - case 245: + case 245: // Up directory { FileList files; files.upDir(); gotoPage(0); } break; - default: + default: // File selected if (tag < 240) { mydata.selected_tag = tag; #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) + mydata.scroll_pos = 0; + mydata.scroll_max = 0; if (FTDI::ftdi_chip >= 810) { const char *longFilename = getSelectedLongFilename(); if (longFilename[0]) { CommandProcessor cmd; - uint16_t text_width = cmd.font(font_medium).text_width(longFilename); - mydata.scroll_pos = 0; - if (text_width > display_width) - mydata.scroll_max = text_width - display_width + MARGIN_L + MARGIN_R; - else - mydata.scroll_max = 0; + constexpr int dim[4] = {LIST_POS}; + const uint16_t text_width = cmd.font(font_medium).text_width(longFilename); + if (text_width > dim[2]) + mydata.scroll_max = text_width - dim[2] + MARGIN_L + MARGIN_R + 10; } } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h index be75684ceb..bf2b415364 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h @@ -41,16 +41,6 @@ struct FilesScreenData { class FilesScreen : public BaseScreen, public CachedScreen { private: - #if ENABLED(TOUCH_UI_PORTRAIT) - static constexpr uint8_t header_h = 2; - static constexpr uint8_t footer_h = 2; - static constexpr uint8_t files_per_page = 11; - #else - static constexpr uint8_t header_h = 1; - static constexpr uint8_t footer_h = 1; - static constexpr uint8_t files_per_page = 6; - #endif - static uint8_t getTagForLine(uint8_t line) {return line + 2;} static uint8_t getLineForTag(uint8_t tag) {return tag - 2;} static uint16_t getFileForTag(uint8_t tag); @@ -60,9 +50,11 @@ class FilesScreen : public BaseScreen, public CachedScreen Date: Sun, 29 Aug 2021 16:05:30 -0600 Subject: [PATCH 0597/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Fix,=20enhance?= =?UTF-8?q?=20FTDI=20Eve=20Touch=20UI=20(#22619)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/extended/text_box.cpp | 12 ++++++--- .../extui/ftdi_eve_touch_ui/theme/bitmaps.h | 26 +++++++++++++++++++ 2 files changed, 34 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 544c5fed05..342b1e4d2b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -23,6 +23,10 @@ #if ENABLED(FTDI_EXTENDED) +#define IS_LINE_SEPARATOR(c) c == '\n' || c == '\t' +#define IS_WORD_SEPARATOR(c) c == ' ' +#define IS_SEPARATOR(c) IS_LINE_SEPARATOR(c) || IS_WORD_SEPARATOR(c) + namespace FTDI { /** * Given a str, end will be set to the position at which a line needs to @@ -37,11 +41,11 @@ namespace FTDI { const char *next = p; const utf8_char_t c = get_utf8_char_and_inc(next); // Decide whether to break the string at this location - if (c == '\n' || c == '\0' || c == ' ') { + if (IS_SEPARATOR(c) || c == '\0' ) { end = p; result = lw; } - if (c == '\n' || c == '\0') break; + if (IS_LINE_SEPARATOR(c) || c == '\0') break; // Measure the next character const uint16_t cw = use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c]; // Stop processing once string exceeds the display width @@ -69,7 +73,7 @@ namespace FTDI { const uint16_t line_width = find_line_break(utf8_fm, clcd_fm, wrap_width, line_start, line_end, use_utf8); width = max(width, line_width); height += utf8_fm.get_height(); - if (*line_end == '\n' || *line_end == ' ') line_end++; + if (IS_SEPARATOR(*line_end)) line_end++; if (*line_end == '\0') break; if (line_end == line_start) break; line_start = line_end; @@ -124,7 +128,7 @@ namespace FTDI { } y += utf8_fm.get_height(); - if (*line_end == '\n' || *line_end == ' ') line_end++; + if (IS_SEPARATOR(*line_end)) line_end++; if (*line_end == '\0') break; if (line_end == line_start) break; line_start = line_end; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h index f7cb63125f..c689f23905 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -229,5 +229,31 @@ namespace Theme { 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00 }; + constexpr PROGMEM bitmap_info_t Light_Bulb_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8685, + .width = 31, + .height = 32, + }; + + const unsigned char Light_Bulb[128] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x40, + 0x02, 0x00, 0x00, 0x80, 0x01, 0x00, 0x01, 0x00, 0x00, 0x80, 0x02, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x18, 0x30, 0x00, 0x00, 0x36, 0x18, 0x00, + 0x00, 0x2C, 0x08, 0x00, 0x00, 0x58, 0x04, 0x00, 0x00, 0x50, 0x04, 0x00, + 0x7C, 0x50, 0x04, 0x7C, 0x00, 0x40, 0x04, 0x00, 0x00, 0x40, 0x04, 0x00, + 0x00, 0x60, 0x0C, 0x00, 0x00, 0x20, 0x08, 0x00, 0x00, 0x10, 0x10, 0x00, + 0x00, 0x10, 0x10, 0x00, 0x00, 0x88, 0x22, 0x00, 0x01, 0x08, 0x21, 0x00, + 0x02, 0x08, 0x20, 0x80, 0x04, 0x0F, 0xE0, 0x40, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00 + }; + constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; + constexpr PROGMEM uint32_t BACKGROUND_OFFSET = 40000; }; // namespace Theme From 4d5f6b2a7817609f58f20aa8e1d2a40f139fa2ae Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 30 Aug 2021 00:57:24 +0000 Subject: [PATCH 0598/2168] [cron] Bump distribution date (2021-08-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a9ecab7bbf..ae244b1f51 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-29" +//#define STRING_DISTRIBUTION_DATE "2021-08-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7a2510e014..198dc15fb4 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 "2021-08-29" + #define STRING_DISTRIBUTION_DATE "2021-08-30" #endif /** From 8f57a21176d217c1c55c03be18876bf187ca786f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 20:04:14 -0500 Subject: [PATCH 0599/2168] =?UTF-8?q?=F0=9F=94=A8=20Three=20columns=20in?= =?UTF-8?q?=20mftest=20menu?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/mftest | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index e0c1d8f38d..17605e3174 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -206,13 +206,26 @@ fi if [[ $TESTENV == '-' ]]; then IND=0 NAMES=() + MENU=() + BIGLEN=0 for FILE in $( ls -1 $TESTPATH/* ) do let IND++ TNAME=${FILE/$TESTPATH\//} NAMES+=($TNAME) - (( IND < 10 )) && echo -n " " - echo " $IND) $TNAME" + IFS="" + ITEM=$( printf "%2i) %s" $IND $TNAME ) + MENU+=($ITEM) + [[ ${#ITEM} -gt $BIGLEN ]] && BIGLEN=${#ITEM} + done + + (( BIGLEN += 2 )) + THIRD=$(( (${#MENU[@]} + 2) / 3 )) + for ((i = 0; i < $THIRD; i++)) + do + COL1=$i ; COL2=$(( $i + $THIRD )) ; COL3=$(( $i + 2 * $THIRD )) + FMT="%-${BIGLEN}s" + printf "${FMT}${FMT}${FMT}\n" ${MENU[$COL1]} ${MENU[$COL2]} ${MENU[$COL3]} done echo From d95d452b29b80e66d534b36c78262454664ce5a1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 23:02:53 -0500 Subject: [PATCH 0600/2168] =?UTF-8?q?=F0=9F=8C=90=20MSG=5FPROBING=5FMESH?= =?UTF-8?q?=20=3D>=20MSG=5FPROBING=5FPOINT?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 ++-- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/lcd/language/language_cz.h | 2 +- Marlin/src/lcd/language/language_de.h | 2 +- Marlin/src/lcd/language/language_en.h | 2 +- Marlin/src/lcd/language/language_es.h | 2 +- Marlin/src/lcd/language/language_fr.h | 2 +- Marlin/src/lcd/language/language_gl.h | 2 +- Marlin/src/lcd/language/language_hu.h | 2 +- Marlin/src/lcd/language/language_it.h | 2 +- Marlin/src/lcd/language/language_pl.h | 2 +- Marlin/src/lcd/language/language_pt_br.h | 2 +- Marlin/src/lcd/language/language_ro.h | 2 +- Marlin/src/lcd/language/language_ru.h | 2 +- Marlin/src/lcd/language/language_sk.h | 2 +- Marlin/src/lcd/language/language_sv.h | 2 +- Marlin/src/lcd/language/language_tr.h | 2 +- Marlin/src/lcd/language/language_uk.h | 2 +- Marlin/src/lcd/language/language_zh_CN.h | 2 +- Marlin/src/lcd/language/language_zh_TW.h | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- 22 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index f8e446cf81..84bb7f9c4c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -736,7 +736,7 @@ void unified_bed_leveling::shift_mesh_height() { const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); #if HAS_LCD_MENU if (ui.button_pressed()) { diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index c3c8d3c92b..ca36f6d46e 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -637,7 +637,7 @@ G29_TYPE GcodeSuite::G29() { if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue; if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", pt_index, "/", abl.abl_points, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl.abl_points))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); @@ -682,7 +682,7 @@ G29_TYPE GcodeSuite::G29() { LOOP_L_N(i, 3) { if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing point ", i + 1, "/3."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); // Retain the last probe position abl.probePos = xy_pos_t(points[i]); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 984e008d27..b8ca8bdee5 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -211,7 +211,7 @@ void GcodeSuite::G29() { if (state == MeshNext) { SERIAL_ECHOLNPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); - if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); + if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); } report_current_position(); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index a6e97ea40c..b58fb05a1d 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -114,7 +114,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sítě"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upravit síť bodů"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Konec úprav sítě"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Měření bodu"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Měření bodu"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 0fa895638b..318f00315b 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -107,7 +107,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Netz Editor"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Netzbearb. angeh."); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Messpunkt"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Messpunkt"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index ede6904627..3f1f744b55 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -147,7 +147,7 @@ namespace Language_en { 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_PROBING_MESH = _UxGT("Probing Point"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Probing Point"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Value"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 46e4e262e7..f08cecf1e1 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -110,7 +110,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado parada"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Sondear Punto"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sondear Punto"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index e0f13356ba..c0ee6b82cd 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -117,7 +117,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Modif. maille"); // 13 car. max PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifier grille"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Modification arrêtée"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Mesure point"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Mesure point"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valeur Z"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index f657d5e34d..e29a2772ff 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -108,7 +108,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado Detida"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punto de Proba"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punto de Proba"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 444c29560b..04b266500f 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -141,7 +141,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló szerkesztö"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló szerkesztése"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Háló szerk. állj"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Próbapont"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Próbapont"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z érték"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 4ae85e7bbe..ab05d5b64f 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -145,7 +145,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifica Mesh"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punto sondato"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punto sondato"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Indice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valore di Z"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index b55777717d..c1620a8fa6 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -139,7 +139,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Edycja siatki zatrzymana"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punkt pomiarowy"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punkt pomiarowy"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Indeks X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indeks Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Wartość Z"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 4b52ee97b8..21be3a2931 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -99,7 +99,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor de Malha"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Malha"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Fim da Edição"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Sondando ponto"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sondando ponto"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index aedc8c4173..b1208eac25 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -107,7 +107,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editeaza Mesh"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Editarea Meshului Oprita"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punctul de Probare"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punctul de Probare"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valoare Z"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index e7eab72f6c..5f5afb049c 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -178,7 +178,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка окончена"); #endif PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Редактировать сетку"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Точка сетки"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Точка сетки"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Индекс X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Индекс Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значение Z"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 079bcf55c8..2fda9b8794 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -141,7 +141,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Koniec úprav siete"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Skúšam bod"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Skúšam bod"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index cb33db5dfd..af80c41a82 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -130,7 +130,7 @@ namespace Language_sv { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Nät Redigerare"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Redigera Nät"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Nätredigering Stoppad"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Sonderingspunkt"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sonderingspunkt"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Värde"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 66c7c1c1a2..f31eb5b13f 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -110,7 +110,7 @@ namespace Language_tr { 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_PROBING_POINT = _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"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index e0ee2e3929..1e6b49da76 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -179,7 +179,7 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Редагувати сітку"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Редагув. зупинено"); - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Точка сітки"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Точка сітки"); PROGMEM Language_Str MSG_MESH_X = _UxGT("Індекс X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Індекс Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значення Z"); diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index d3883ac88d..35642460fc 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -105,7 +105,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("网格编辑器"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("编辑网格"); // "Edit Mesh" PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("网格编辑已停止"); // "Mesh Editing Stopped" - PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("探测点"); + PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("探测点"); PROGMEM Language_Str MSG_MESH_X = _UxGT("索引X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("索引Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z 值"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 2c7d1bf69f..467a2467f5 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -103,7 +103,7 @@ namespace Language_zh_TW { 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_PROBING_MESH = _UxGT("探測點"); // "Probing Point" + PROGMEM Language_Str MSG_PROBING_POINT = _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" diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 82f25ea6f3..ea9ef75aa1 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -172,7 +172,7 @@ static void _lcd_level_bed_corners_get_next_position() { TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); // Set up the font for extra info - MenuItem_static::draw(0, GET_TEXT(MSG_PROBING_MESH), SS_INVERT); // "Probing Mesh" heading + MenuItem_static::draw(0, GET_TEXT(MSG_PROBING_POINT), SS_INVERT); // "Probing Mesh" heading uint8_t cy = TERN(TFT_COLOR_UI, 3, LCD_HEIGHT - 1), y = LCD_ROW_Y(cy); From 90cd1ca68d3f4f5ede56cbea4913f06ca4782a94 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 23:06:24 -0500 Subject: [PATCH 0601/2168] =?UTF-8?q?=F0=9F=8E=A8=20screws=5Ftilt=5Fadjust?= =?UTF-8?q?=5Fpos=20=3D>=20tramming=5Fpoints?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/tramming.h | 6 +++--- Marlin/src/gcode/bedlevel/G35.cpp | 6 +++--- Marlin/src/lcd/menu/menu_tramming.cpp | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/feature/tramming.h b/Marlin/src/feature/tramming.h index eb27fe82fe..925659e29d 100644 --- a/Marlin/src/feature/tramming.h +++ b/Marlin/src/feature/tramming.h @@ -28,12 +28,12 @@ #error "TRAMMING_SCREW_THREAD must be equal to 30, 31, 40, 41, 50, or 51." #endif -constexpr xy_pos_t screws_tilt_adjust_pos[] = TRAMMING_POINT_XY; +constexpr xy_pos_t tramming_points[] = TRAMMING_POINT_XY; -#define G35_PROBE_COUNT COUNT(screws_tilt_adjust_pos) +#define G35_PROBE_COUNT COUNT(tramming_points) static_assert(WITHIN(G35_PROBE_COUNT, 3, 6), "TRAMMING_POINT_XY requires between 3 and 6 XY positions."); -#define VALIDATE_TRAMMING_POINT(N) static_assert(N >= G35_PROBE_COUNT || Probe::build_time::can_reach(screws_tilt_adjust_pos[N]), \ +#define VALIDATE_TRAMMING_POINT(N) static_assert(N >= G35_PROBE_COUNT || Probe::build_time::can_reach(tramming_points[N]), \ "TRAMMING_POINT_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN.") VALIDATE_TRAMMING_POINT(0); VALIDATE_TRAMMING_POINT(1); VALIDATE_TRAMMING_POINT(2); VALIDATE_TRAMMING_POINT(3); VALIDATE_TRAMMING_POINT(4); VALIDATE_TRAMMING_POINT(5); diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 3d75a76915..3a4e1bdd5a 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -103,13 +103,13 @@ void GcodeSuite::G35() { // Users of G35 might have a badly misaligned bed, so raise Z by the // length of the deployed pin (BLTOUCH stroke < 7mm) do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, Z_CLEARANCE_BETWEEN_PROBES, 7)); - const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true); + const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { SERIAL_ECHOPAIR("G35 failed at point ", i + 1, " ("); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); SERIAL_CHAR(')'); - SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y); + SERIAL_ECHOLNPAIR_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y); err_break = true; break; } @@ -118,7 +118,7 @@ void GcodeSuite::G35() { DEBUG_ECHOPAIR("Probing point ", i + 1, " ("); DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); DEBUG_CHAR(')'); - DEBUG_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height); + DEBUG_ECHOLNPAIR_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height); } z_measured[i] = z_probed_height; diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index b5868f4056..d230ca6397 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -49,7 +49,7 @@ static uint8_t tram_index = 0; static bool probe_single_point() { do_blocking_move_to_z(TERN(BLTOUCH, Z_CLEARANCE_DEPLOY_PROBE, Z_CLEARANCE_BETWEEN_PROBES)); // Stow after each point with BLTouch "HIGH SPEED" mode for push-pin safety - const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); + const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); DEBUG_ECHOLNPAIR("probe_single_point: ", z_probed_height, "mm"); z_measured[tram_index] = z_probed_height; move_to_tramming_wait_pos(); From efb9ea92b85ec469e9436969129bcee33aadd3bc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 30 Aug 2021 17:02:12 -0500 Subject: [PATCH 0602/2168] =?UTF-8?q?=F0=9F=94=A8=20Fix=20HAL/STM32=20F103?= =?UTF-8?q?Zx=20builds=20(#22610)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h | 3 + .../MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h | 2 +- .../MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h | 2 +- .../hal_conf_extra.h | 2 +- .../hal_conf_extra.h | 2 +- .../MARLIN_F103VE_LONGER/hal_conf_custom.h | 41 +++-------- .../variants/MARLIN_F103Zx/PinNamesVar.h | 3 +- .../variants/MARLIN_F103Zx/hal_conf_custom.h | 71 ++++++++++--------- ini/stm32f1.ini | 12 +++- 10 files changed, 66 insertions(+), 74 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index f9f9c2b3da..33167d9dff 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -217,7 +217,7 @@ void plan_arc( * tool precision in some cases. Therefore, arc path correction is implemented. * * Small angle approximation may be used to reduce computation overhead further. This approximation - * holds for everything, but very small circles and large MM_PER_ARC_SEGMENT values. In other words, + * holds for everything, but very small circles and large MAX_ARC_SEGMENT_MM values. In other words, * theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large * to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for * numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 5b59a157f1..bf38955127 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -147,6 +147,9 @@ #define FSMC_CS_PIN PD7 // NE4 #define FSMC_RS_PIN PD11 // A0 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h index 6c4a991f33..2c1557cbbb 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h @@ -8,7 +8,7 @@ #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it? #define HAL_SPI_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED #define HAL_USART_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h index e6d558b3e1..40b340c205 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h @@ -8,7 +8,7 @@ #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it? #define HAL_SPI_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED #define HAL_USART_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h index da974b1ba7..42c76a4bbf 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h @@ -8,7 +8,7 @@ #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it? #define HAL_SPI_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED #define HAL_USART_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h index e6d558b3e1..40b340c205 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h @@ -8,7 +8,7 @@ #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +//#define HAL_RTC_MODULE_ENABLED // Real Time Clock...do we use it? #define HAL_SPI_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED #define HAL_USART_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h index e2247addb9..fd20d8fe6f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h @@ -20,25 +20,18 @@ extern "C" { */ #include "stm32yyxx_hal_conf.h" -#ifdef HAL_PWR_MODULE_ENABLED - #undef HAL_PWR_MODULE_ENABLED // only way to disable it -#endif +#undef HAL_PWR_MODULE_ENABLED +#define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) -#if defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) - #define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) -#endif - -#ifndef HAL_IWDG_MODULE_ENABLED - #define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG -#endif +#define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG #ifdef HAL_PCD_MODULE_ENABLED - #warning No direct STM32 USB pins on Longer3D board + #warning "No direct STM32 USB pins on Longer3D board" #undef HAL_PCD_MODULE_ENABLED // USB Device #endif #ifdef HAL_HCD_MODULE_ENABLED - #warning No direct STM32 USB pins on Longer3D board + #warning "No direct STM32 USB pins on Longer3D board" #undef HAL_HCD_MODULE_ENABLED // USB Host #endif @@ -46,25 +39,12 @@ extern "C" { //#define HAL_USART_MODULE_ENABLED // Useless.... UART_MODULE do it #endif -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #undef HAL_CAN_LEGACY_MODULE_ENABLED -#endif +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_RTC_MODULE_ENABLED -#ifdef HAL_CAN_MODULE_ENABLED - #undef HAL_CAN_MODULE_ENABLED -#endif - -#ifdef HAL_DAC_MODULE_ENABLED - #undef HAL_DAC_MODULE_ENABLED -#endif - -#ifdef HAL_RTC_MODULE_ENABLED - #undef HAL_RTC_MODULE_ENABLED -#endif - -#ifndef HAL_EXTI_MODULE_ENABLED - #define HAL_EXTI_MODULE_ENABLED // for ENDSTOP_INTERRUPTS_FEATURE -#endif +#define HAL_EXTI_MODULE_ENABLED // for ENDSTOP_INTERRUPTS_FEATURE /** * @brief List of modules in the framework (first ones enabled by default) @@ -345,4 +325,3 @@ extern "C" { #ifdef __cplusplus } #endif - diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PinNamesVar.h index d9076b4dfb..b0259ab335 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/PinNamesVar.h @@ -1,5 +1,6 @@ /* SYS_WKUP */ -#ifdef PWR_WAKEUP_PIN1 +#if defined(PWR_WAKEUP_PIN1) && defined(HAL_PWR_MODULE_ENABLED) && !defined(HAL_PWR_MODULE_ONLY) + #error "PA0 is used by thermal sensor. Disable low power wake with -DHAL_PWR_MODULE_ONLY." SYS_WKUP1 = PA_0, #endif #ifdef PWR_WAKEUP_PIN2 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h index 4e55fe1240..7d19d532a5 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h @@ -37,40 +37,43 @@ extern "C" { /** * @brief This is the list of modules to be used in the HAL driver */ -//#define HAL_MODULE_ENABLED -//#define HAL_ADC_MODULE_ENABLED -//#define HAL_CAN_MODULE_ENABLED -//#define HAL_CAN_LEGACY_MODULE_ENABLED -//#define HAL_CEC_MODULE_ENABLED -//#define HAL_CORTEX_MODULE_ENABLED -//#define HAL_CRC_MODULE_ENABLED -//#define HAL_DAC_MODULE_ENABLED -//#define HAL_DMA_MODULE_ENABLED -//#define HAL_ETH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED -//#define HAL_FLASH_MODULE_ENABLED -//#define HAL_GPIO_MODULE_ENABLED -//#define HAL_HCD_MODULE_ENABLED -//#define HAL_I2C_MODULE_ENABLED -//#define HAL_I2S_MODULE_ENABLED -//#define HAL_IRDA_MODULE_ENABLED -//#define HAL_IWDG_MODULE_ENABLED -//#define HAL_NAND_MODULE_ENABLED -//#define HAL_NOR_MODULE_ENABLED -//#define HAL_PCCARD_MODULE_ENABLED -//#define HAL_PCD_MODULE_ENABLED -//#define HAL_PWR_MODULE_ENABLED -//#define HAL_RCC_MODULE_ENABLED -//#define HAL_RTC_MODULE_ENABLED -//#define HAL_SD_MODULE_ENABLED -//#define HAL_SMARTCARD_MODULE_ENABLED -//#define HAL_SPI_MODULE_ENABLED -//#define HAL_SRAM_MODULE_ENABLED -//#define HAL_TIM_MODULE_ENABLED -//#define HAL_UART_MODULE_ENABLED -//#define HAL_USART_MODULE_ENABLED -//#define HAL_WWDG_MODULE_ENABLED -//#define HAL_MMC_MODULE_ENABLED +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_IWDG_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) +#define HAL_SD_MODULE_ENABLED + +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_HCD_MODULE_ENABLED // USB Host +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_PWR_MODULE_ENABLED +#undef HAL_RTC_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED + +#define HAL_PWR_MODULE_ONLY /* ########################## Oscillator Values adaptation ####################*/ /** diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index f1cb078fd8..a27d275fc1 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -348,9 +348,15 @@ debug_tool = stlink # TRIGORILLA PRO (STM32F103ZET6) # [env:trigorilla_pro] -platform = ${common_stm32.platform} -extends = env:mks_robin -extra_scripts = ${common_stm32.extra_scripts} +platform = ${stm32_variant.platform} +extends = stm32_variant +board = genericSTM32F103ZE +board_build.variant = MARLIN_F103Zx +board_build.offset = 0x7000 +build_flags = ${stm32_variant.build_flags} + -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC # # Chitu boards like Tronxy X5s (STM32F103ZET6) From 6ff2be329e0ac81ea56066353f2bb1469ae02eda Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Tue, 31 Aug 2021 00:05:11 +0200 Subject: [PATCH 0603/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Italian=20lan?= =?UTF-8?q?guage=20(#22645)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_it.h | 33 ++++++++++++++++----------- 1 file changed, 20 insertions(+), 13 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index ab05d5b64f..388498fe8f 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -62,7 +62,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principale"); PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configurazione"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu di debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); @@ -137,7 +137,7 @@ namespace Language_it { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Livella piano"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Livella piano"); PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Tramming piano"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finche' la sonda non rileva il piano."); + PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finché la sonda non rileva il piano."); PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Punti buoni: "); PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Ultimo Z: "); @@ -244,7 +244,7 @@ namespace Language_it { PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Controllo LED"); PROGMEM Language_Str MSG_LEDS = _UxGT("Luci"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Preset luce"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Presets luce"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rosso"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Arancione"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Giallo"); @@ -256,7 +256,7 @@ namespace Language_it { PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Predefinito"); PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Canale ="); PROGMEM Language_Str MSG_LEDS2 = _UxGT("Luci #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Luce #2 Presets"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Presets luce #2"); PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Luminosità"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luci personalizzate"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensità rosso"); @@ -318,6 +318,7 @@ namespace Language_it { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Off"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Calibrazione PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Calibraz. PID *"); + PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("Ciclo PID"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); @@ -502,8 +503,8 @@ namespace Language_it { PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Finecorsa annullati"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 caratteri + PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Interrompi se FC"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 characters PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP RIDONDANTE"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEMP FUORI CONTROLLO"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEMP PIAT.FUORI CTRL"); @@ -514,9 +515,9 @@ namespace Language_it { PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); PROGMEM Language_Str MSG_HALTED = _UxGT("STAMPANTE FERMATA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Riavviare prego"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("g"); // Un solo carattere - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // Un solo carattere - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // Un solo carattere + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("g"); // One character + PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // One character + PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character PROGMEM Language_Str MSG_HEATING = _UxGT("Riscaldamento..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Raffreddamento.."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Risc. piatto..."); @@ -538,7 +539,7 @@ namespace Language_it { PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonale"); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altezza"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Raggio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Riguardo stampante"); + PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Info su stampante"); PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info. stampante"); PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Livel. a 3 punti"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Livel. Lineare"); @@ -660,8 +661,9 @@ namespace Language_it { PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Password eliminata"); // - // Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe - // ...o fino a 2 linee su un display a 3 righe. + // 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_3_LINE("Premi per", "riprendere", "la stampa")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcheggiando...")); @@ -709,9 +711,14 @@ namespace Language_it { PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout inattività, temperatura diminuita. Premere OK per riscaldare e riprendere di nuovo."); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); + #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Riscalda"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Riscaldando..."); + PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Riscaldato"); PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Wizard Z offset"); PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Altezza di riferimento sonda"); From fff1ed3369200306b313186643ca14ffa7fc36b1 Mon Sep 17 00:00:00 2001 From: "Zs.Antal" <45710979+AntoszHUN@users.noreply.github.com> Date: Tue, 31 Aug 2021 02:30:14 +0200 Subject: [PATCH 0604/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Hungarian=20l?= =?UTF-8?q?anguage=20(#22678)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_hu.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 04b266500f..2b879a7d6f 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -26,11 +26,11 @@ * * LCD Menu Messages. See also https://marlinfw.org/docs/development/lcd_language.html * Hungarian translation by AntoszHUN. I am constantly improving and updating the translation. - * Translation last updated: 07/07/2021 - 11:20 + * Translation last updated: 08/30/2021 - 22:20 * * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html * A Magyar fordítást készítette: AntoszHUN. A fordítást folyamatosan javítom és frissítem. - * A Fordítás utolsó frissítése: 2021.07.07. - 11:20 + * A Fordítás utolsó frissítése: 2021.08.30. - 22:20 */ namespace Language_hu { @@ -312,6 +312,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID hangolás"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID hangolás *"); + PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("PID ciklus"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); @@ -493,7 +494,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI használ"); PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Szonda telepítés"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Szonda elhelyezés"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elsö %s%s%s kell"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elöször %s%s%s kell"); PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Szonda eltolások"); PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X szonda eltolás"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y szonda eltolás"); From 7378e7c2db379f57e99a3b3b7ea1700e5031460a Mon Sep 17 00:00:00 2001 From: Christian Schuster Date: Tue, 31 Aug 2021 02:32:02 +0200 Subject: [PATCH 0605/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20LPC176x=20M43=20?= =?UTF-8?q?formatting=20(#22680)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/pinsDebug.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h index c622a2622e..466bf170b4 100644 --- a/Marlin/src/HAL/LPC1768/pinsDebug.h +++ b/Marlin/src/HAL/LPC1768/pinsDebug.h @@ -35,7 +35,7 @@ #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0) -#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin +#define MULTI_NAME_PAD 17 // space needed to be pretty if not first name assigned to a pin // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities #ifndef M43_NEVER_TOUCH From ef2d0b8d5353460ba8b6698281c8d4987217eb07 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 31 Aug 2021 00:59:16 +0000 Subject: [PATCH 0606/2168] [cron] Bump distribution date (2021-08-31) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ae244b1f51..df5f54a550 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-30" +//#define STRING_DISTRIBUTION_DATE "2021-08-31" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 198dc15fb4..c5fc257800 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 "2021-08-30" + #define STRING_DISTRIBUTION_DATE "2021-08-31" #endif /** From 66ded801b734fbb597ab1c1497d347544b3aa05c Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 31 Aug 2021 15:40:49 +1200 Subject: [PATCH 0607/2168] =?UTF-8?q?=E2=8F=AA=EF=B8=8F=20Revert=20MAX3186?= =?UTF-8?q?5=20recent=20changes=20(#22660)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 6 ++--- Marlin/src/libs/MAX31865.cpp | 38 ++++++++++++++++++------------ Marlin/src/libs/MAX31865.h | 1 - Marlin/src/module/temperature.cpp | 6 ++--- 4 files changed, 29 insertions(+), 22 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index fd49aada6b..a43e57d158 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -755,13 +755,13 @@ // to select a USER library for MAX6675, MAX31855, MAX31865 // #if BOTH(HAS_MAX6675, LIB_MAX6675) - #define LIB_USR_MAX6675 1 + #define USE_LIB_MAX6675 1 #endif #if BOTH(HAS_MAX31855, LIB_MAX31855) - #define LIB_USR_MAX31855 1 + #define USE_ADAFRUIT_MAX31855 1 #endif #if BOTH(HAS_MAX31865, LIB_MAX31865) - #define LIB_USR_MAX31865 1 + #define USE_ADAFRUIT_MAX31865 1 #elif HAS_MAX31865 #define LIB_INTERNAL_MAX31865 1 #endif diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 86c31edee9..1264c6fbe8 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -44,12 +44,11 @@ //#define MAX31865_DEBUG //#define MAX31865_DEBUG_SPI -#include - #include "../inc/MarlinConfig.h" -#if HAS_MAX31865 && !LIB_USR_MAX31865 +#if HAS_MAX31865 && !USE_ADAFRUIT_MAX31865 +//#include // TODO: switch to SPIclass/SoftSPI #include "MAX31865.h" // The maximum speed the MAX31865 can do is 5 MHz @@ -62,7 +61,7 @@ SPISettings MAX31865::spiConfig = SPISettings( 500000 #endif , MSBFIRST - , SPI_MODE1 // CPOL0 CPHA1 + , SPI_MODE_1 // CPOL0 CPHA1 ); #ifndef LARGE_PINMAP @@ -153,15 +152,17 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { OUT_WRITE(_cs, HIGH); if (_sclk != TERN(LARGE_PINMAP, -1UL, -1)) { - // define pin modes for Software SPI + // Define pin modes for Software SPI #ifdef MAX31865_DEBUG SERIAL_ECHOLN("Initializing MAX31865 Software SPI"); #endif - - swSpiBegin(_sclk, _miso, _mosi); - - } else { - // start and configure hardware SPI + + OUT_WRITE(_sclk, LOW); + SET_OUTPUT(_mosi); + SET_INPUT(_miso); + } + else { + // Start and configure hardware SPI #ifdef MAX31865_DEBUG SERIAL_ECHOLN("Initializing MAX31865 Hardware SPI"); #endif @@ -169,9 +170,6 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { SPI.begin(); } - // SPI Begin must be called first, then init - _spi_speed = swSpiInit(SPI_QUARTER_SPEED, _sclk, _mosi); - setWires(wires); enableBias(false); autoConvert(false); @@ -486,7 +484,17 @@ uint8_t MAX31865::spixfer(uint8_t x) { if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) return SPI.transfer(x); - return swSpiTransfer(x, _spi_speed, _sclk, _miso, _mosi); + uint8_t reply = 0; + for (int i = 7; i >= 0; i--) { + reply <<= 1; + WRITE(_sclk, HIGH); + WRITE(_mosi, x & (1 << i)); + WRITE(_sclk, LOW); + if (READ(_miso)) + reply |= 1; + } + + return reply; } -#endif // HAS_MAX31865 && !LIB_USR_MAX31865 +#endif // HAS_MAX31865 && !USE_ADAFRUIT_MAX31865 diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 13a117447d..5d50e870ec 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -90,7 +90,6 @@ private: static SPISettings spiConfig; TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; - uint8_t _spi_speed; float Rzero, Rref; void setConfig(uint8_t config, bool enable); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 0475db486c..935de772f4 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -63,21 +63,21 @@ // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library // If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. -#if HAS_MAX6675 && LIB_USR_MAX6675 +#if HAS_MAX6675 && USE_LIB_MAX6675 #include #define HAS_MAX6675_LIBRARY 1 #endif // LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library. // If LIB_MAX31855 is not on the build_flags then raw SPI reads will be used. -#if HAS_MAX31855 && LIB_USR_MAX31855 +#if HAS_MAX31855 && USE_ADAFRUIT_MAX31855 #include #define HAS_MAX31855_LIBRARY 1 typedef Adafruit_MAX31855 MAX31855; #endif #if HAS_MAX31865 - #if LIB_USR_MAX31865 + #if USE_ADAFRUIT_MAX31865 #include typedef Adafruit_MAX31865 MAX31865; #else From 485a1864673d14177622e30d4f77de799e6d910a Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Tue, 31 Aug 2021 00:00:59 -0700 Subject: [PATCH 0608/2168] =?UTF-8?q?=F0=9F=9A=B8=20Improve=20Tramming=20W?= =?UTF-8?q?izard=20usability=20(#22672)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/example/example.cpp | 1 + Marlin/src/lcd/menu/menu_tramming.cpp | 28 ++++++++++++++---------- buildroot/tests/DUE | 2 +- buildroot/tests/LPC1768 | 1 + 4 files changed, 19 insertions(+), 13 deletions(-) diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 0e7d71ff4d..f74cbee91c 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -120,6 +120,7 @@ namespace ExtUI { void onPidTuning(const result_t rst) { // Called for temperature PID tuning result switch (rst) { + case PID_STARTED: break; case PID_BAD_EXTRUDER_NUM: break; case PID_TEMP_TOO_HIGH: break; case PID_TUNING_TIMEOUT: break; diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index d230ca6397..c3090bcc5b 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -39,8 +39,10 @@ //#define DEBUG_OUT 1 #include "../../core/debug_out.h" -float z_measured[G35_PROBE_COUNT] = { 0 }; +static float z_measured[G35_PROBE_COUNT]; +static bool z_isvalid[G35_PROBE_COUNT]; static uint8_t tram_index = 0; +static int8_t reference_index; // = 0 #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" @@ -50,32 +52,31 @@ static bool probe_single_point() { do_blocking_move_to_z(TERN(BLTOUCH, Z_CLEARANCE_DEPLOY_PROBE, Z_CLEARANCE_BETWEEN_PROBES)); // Stow after each point with BLTouch "HIGH SPEED" mode for push-pin safety const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); - DEBUG_ECHOLNPAIR("probe_single_point: ", z_probed_height, "mm"); z_measured[tram_index] = z_probed_height; + if (reference_index < 0) reference_index = tram_index; move_to_tramming_wait_pos(); - return !isnan(z_probed_height); + DEBUG_ECHOLNPAIR("probe_single_point(", tram_index, ") = ", z_probed_height, "mm"); + return (z_isvalid[tram_index] = !isnan(z_probed_height)); } -static void _menu_single_probe(const uint8_t point) { - tram_index = point; - DEBUG_ECHOLNPAIR("Screen: single probe screen Arg:", point); +static void _menu_single_probe() { + DEBUG_ECHOLNPAIR("Screen: single probe screen Arg:", tram_index); START_MENU(); STATIC_ITEM(MSG_BED_TRAMMING, SS_LEFT); - STATIC_ITEM(MSG_LAST_VALUE_SP, SS_LEFT, ftostr42_52(z_measured[0] - z_measured[point])); // Print diff + STATIC_ITEM(MSG_LAST_VALUE_SP, SS_LEFT, z_isvalid[tram_index] ? ftostr42_52(z_measured[reference_index] - z_measured[tram_index]) : "---"); ACTION_ITEM(MSG_UBL_BC_INSERT2, []{ if (probe_single_point()) ui.refresh(); }); - ACTION_ITEM(MSG_BUTTON_DONE, []{ ui.goto_previous_screen(); }); // Back + ACTION_ITEM(MSG_BUTTON_DONE, []{ ui.goto_previous_screen(); }); END_MENU(); } static void tramming_wizard_menu() { - DEBUG_ECHOLNPAIR("Screen: tramming_wizard_menu"); START_MENU(); STATIC_ITEM(MSG_SELECT_ORIGIN); // Draw a menu item for each tramming point - LOOP_L_N(i, G35_PROBE_COUNT) - SUBMENU_N_P(i, (char*)pgm_read_ptr(&tramming_point_name[i]), []{ _menu_single_probe(MenuItemBase::itemIndex); }); + for (tram_index = 0; tram_index < G35_PROBE_COUNT; tram_index++) + SUBMENU_P((char*)pgm_read_ptr(&tramming_point_name[tram_index]), _menu_single_probe); ACTION_ITEM(MSG_BUTTON_DONE, []{ probe.stow(); // Stow before exiting Tramming Wizard @@ -87,9 +88,12 @@ static void tramming_wizard_menu() { // Init the wizard and enter the submenu void goto_tramming_wizard() { DEBUG_ECHOLNPAIR("Screen: goto_tramming_wizard", 1); - tram_index = 0; ui.defer_status_screen(); + // Initialize measured point flags + ZERO(z_isvalid); + reference_index = -1; + // Inject G28, wait for homing to complete, set_all_unhomed(); queue.inject_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index 9eb2157428..37678501e4 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -15,7 +15,7 @@ opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB \ TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 6 HEATER_CHAMBER_PIN 45 opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING \ - ASSISTED_TRAMMING ASSISTED_TRAMMING_WIZARD REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ + ASSISTED_TRAMMING REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index b4e489d310..26e3710890 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -42,6 +42,7 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EEB \ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ FILAMENT_WIDTH_SENSOR FILAMENT_LCD_DISPLAY PID_EXTRUSION_SCALING SOUND_MENU_ITEM \ NOZZLE_AS_PROBE AUTO_BED_LEVELING_BILINEAR PREHEAT_BEFORE_LEVELING G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + ASSISTED_TRAMMING ASSISTED_TRAMMING_WIZARD REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ From 2c5daa07228e153a14b6df5a784b1c1ef0e35e46 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Aug 2021 02:23:49 -0500 Subject: [PATCH 0609/2168] =?UTF-8?q?=F0=9F=A9=B9=20Clean=20up=20BTT=5FSKR?= =?UTF-8?q?=5FCR6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22665 --- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index f58f13dc2f..8bae916a46 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -49,25 +49,21 @@ #define I2C_EEPROM #endif -/* I2C */ #if ENABLED(I2C_EEPROM) #define IIC_EEPROM_SDA PB7 #define IIC_EEPROM_SCL PB6 - #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #elif ENABLED(SDCARD_EEPROM_EMULATION) #define MARLIN_EEPROM_SIZE 0x1000 // 4KB #endif -#define E2END (MARLIN_EEPROM_SIZE - 1) // 2KB - // // Limit Switches // #define X_STOP_PIN PC0 #define Y_STOP_PIN PC1 -#define Z_STOP_PIN PC14 // Endtop or Probe +#define Z_STOP_PIN PC14 // Endstop or Probe #define FIL_RUNOUT_PIN PC15 @@ -165,7 +161,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card - #define SDSS ONBOARD_SD_CS_PIN + #define SDSS ONBOARD_SD_CS_PIN #endif // From 1f5eacac09d694c2b69c223aba7bf8c422d16241 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 31 Aug 2021 19:26:12 +1200 Subject: [PATCH 0610/2168] =?UTF-8?q?=F0=9F=94=A7=20Set=20Z=5FPROBE=5FOFFS?= =?UTF-8?q?ET=5FRANGE=5FMIN/MAX=20for=20MBL=20(#22663)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index a43e57d158..d82b651650 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2862,16 +2862,18 @@ /** * Bed Probe dependencies */ -#if HAS_BED_PROBE - #if BOTH(ENDSTOPPULLUPS, HAS_Z_MIN_PROBE_PIN) - #define ENDSTOPPULLUP_ZMIN_PROBE - #endif +#if EITHER(MESH_BED_LEVELING, HAS_BED_PROBE) #ifndef Z_PROBE_OFFSET_RANGE_MIN #define Z_PROBE_OFFSET_RANGE_MIN -20 #endif #ifndef Z_PROBE_OFFSET_RANGE_MAX #define Z_PROBE_OFFSET_RANGE_MAX 20 #endif +#endif +#if HAS_BED_PROBE + #if BOTH(ENDSTOPPULLUPS, HAS_Z_MIN_PROBE_PIN) + #define ENDSTOPPULLUP_ZMIN_PROBE + #endif #ifndef XY_PROBE_FEEDRATE #define XY_PROBE_FEEDRATE ((homing_feedrate_mm_m.x + homing_feedrate_mm_m.y) / 2) #endif From eccd82b7c1049b098546334fab7ac152e1fa1ce7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Dec 2020 18:15:36 -0600 Subject: [PATCH 0611/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Add=20PROBE=5FPT?= =?UTF-8?q?=5FLAST=5FSTOW?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/module/probe.cpp | 4 ++-- Marlin/src/module/probe.h | 1 + 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 84bb7f9c4c..ceedd316e3 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1479,7 +1479,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); - measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, param.V_verbosity); + measured_z = probe.probe_at_point(points[2], PROBE_PT_LAST_STOW, param.V_verbosity); #ifdef VALIDATE_MESH_TILT z3 = measured_z; #endif diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index ded5d43893..cbadda2eef 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -751,7 +751,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR( "...(", LOGICAL_X_POSITION(rx), ", ", LOGICAL_Y_POSITION(ry), - ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none", + ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_LAST_STOW ? "stow (last)" : raise_after == PROBE_PT_STOW ? "stow" : "none", ", ", verbose_level, ", ", probe_relative ? "probe" : "nozzle", "_relative)" ); @@ -782,7 +782,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai const bool big_raise = raise_after == PROBE_PT_BIG_RAISE; if (big_raise || raise_after == PROBE_PT_RAISE) do_blocking_move_to_z(current_position.z + (big_raise ? 25 : Z_CLEARANCE_BETWEEN_PROBES), z_probe_fast_mm_s); - else if (raise_after == PROBE_PT_STOW) + else if (raise_after == PROBE_PT_STOW || raise_after == PROBE_PT_LAST_STOW) if (stow()) measured_z = NAN; // Error on stow? if (verbose_level > 2) diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index ce690593f2..5da5ea3a22 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -33,6 +33,7 @@ enum ProbePtRaise : uint8_t { PROBE_PT_NONE, // No raise or stow after run_z_probe PROBE_PT_STOW, // Do a complete stow after run_z_probe + PROBE_PT_LAST_STOW, // Stow for sure, even in BLTouch HS mode PROBE_PT_RAISE, // Raise to "between" clearance after run_z_probe PROBE_PT_BIG_RAISE // Raise to big clearance after run_z_probe }; From f55a28b01599692ca7a149571c6ae94e3b6b017d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 20:52:48 -0500 Subject: [PATCH 0612/2168] =?UTF-8?q?=F0=9F=8C=90=20Tweak=20language=20sel?= =?UTF-8?q?ection?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/multi_language.h | 13 ++++++------- Marlin/src/lcd/language/language_en.h | 22 ++++++++++++---------- 2 files changed, 18 insertions(+), 17 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 1eaef69305..5063faf60c 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -36,9 +36,8 @@ typedef const char Language_Str[]; #define NUM_LANGUAGES 1 #endif -// Setting the unused languages equal to each other allows -// the compiler to optimize away the conditionals - +// Set unused languages equal to each other so the +// compiler can optimize away the conditionals. #ifndef LCD_LANGUAGE_2 #define LCD_LANGUAGE_2 LCD_LANGUAGE #endif @@ -58,11 +57,11 @@ typedef const char Language_Str[]; #if NUM_LANGUAGES > 1 #define HAS_MULTI_LANGUAGE 1 #define GET_TEXT(MSG) ( \ - ui.language == 0 ? GET_LANG(LCD_LANGUAGE )::MSG : \ - ui.language == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \ - ui.language == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \ + ui.language == 4 ? GET_LANG(LCD_LANGUAGE_5)::MSG : \ ui.language == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \ - GET_LANG(LCD_LANGUAGE_5)::MSG ) + ui.language == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \ + ui.language == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \ + GET_LANG(LCD_LANGUAGE )::MSG ) #define MAX_LANG_CHARSIZE _MAX(GET_LANG(LCD_LANGUAGE )::CHARSIZE, \ GET_LANG(LCD_LANGUAGE_2)::CHARSIZE, \ GET_LANG(LCD_LANGUAGE_3)::CHARSIZE, \ diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 3f1f744b55..85bf685e31 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -41,6 +41,8 @@ #endif #undef en +#define MEDIA_TYPE_EN "Media" + namespace Language_en { constexpr uint8_t CHARSIZE = 2; PROGMEM Language_Str LANGUAGE = _UxGT("English"); @@ -51,11 +53,11 @@ namespace Language_en { 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("Media Inserted"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media Removed"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Waiting for media"); + PROGMEM Language_Str MSG_MEDIA_INSERTED = MEDIA_TYPE_EN _UxGT(" Inserted"); + PROGMEM Language_Str MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Waiting for card"); PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD Init Fail"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Media read error"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); @@ -399,7 +401,7 @@ namespace Language_en { PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Update"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = MEDIA_TYPE_EN _UxGT(" Update"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset Printer"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Refresh"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info Screen"); @@ -431,8 +433,8 @@ namespace Language_en { 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("Power Outage"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Print from Media"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No Media"); + PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Print from ") MEDIA_TYPE_EN; + PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No ") MEDIA_TYPE_EN; 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"); @@ -475,9 +477,9 @@ namespace Language_en { PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Unload Filament"); PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Unload *"); PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Unload All"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Attach Media"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Change Media"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Release Media"); + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Attach ") MEDIA_TYPE_EN; + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Change ") MEDIA_TYPE_EN; + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Release ") MEDIA_TYPE_EN; PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Probe Past Bed"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Skew Factor"); PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); From ba10816c51804433446a5221759a794aaac5bac2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 20:54:17 -0500 Subject: [PATCH 0613/2168] =?UTF-8?q?=F0=9F=92=84=20Extended=20Info=20Menu?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_info.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index cecccd115d..bcdea7f92d 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -273,6 +273,14 @@ void menu_info_board() { void menu_info() { START_MENU(); BACK_ITEM(MSG_MAIN); + STATIC_ITEM(MSG_MARLIN); + STATIC_ITEM_P(PSTR(SHORT_BUILD_VERSION)); + STATIC_ITEM_P(PSTR(STRING_DISTRIBUTION_DATE)); + STATIC_ITEM_P(PSTR(MACHINE_NAME)); + STATIC_ITEM_P(PSTR(WEBSITE_URL)); + STATIC_ITEM_P(PSTR(BOARD_INFO_NAME), SS_CENTER); + VALUE_ITEM_P(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); + VALUE_ITEM_P(MSG_INFO_BAUDRATE, STRINGIFY(BAUDRATE), SS_CENTER); #if ENABLED(LCD_PRINTER_INFO_IS_BOOTSCREEN) SUBMENU(MSG_INFO_PRINTER_MENU, TERN(SHOW_CUSTOM_BOOTSCREEN, menu_show_custom_bootscreen, menu_show_marlin_bootscreen)); #else From e33e101850797f4d3edecd4eb18e9ae63c89ef13 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 20:54:51 -0500 Subject: [PATCH 0614/2168] =?UTF-8?q?=F0=9F=8E=A8=20Tweak=20pins,=20commen?= =?UTF-8?q?t=20formatting?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 12 +++--- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 50 +++++++++++----------- 2 files changed, 33 insertions(+), 29 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index fca33c98c2..632f95558d 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2397,13 +2397,15 @@ void MarlinSettings::postprocess() { UNUSED(s); } - const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; // 128 (+1 because of the change to capacity rather than last valid address) - // is a placeholder for the size of the MAT; the MAT will always - // live at the very end of the eeprom + // 128 (+1 because of the change to capacity rather than last valid address) + // is a placeholder for the size of the MAT; the MAT will always + // live at the very end of the eeprom + const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; uint16_t MarlinSettings::meshes_start_index() { - return (datasize() + EEPROM_OFFSET + 32) & 0xFFF8; // Pad the end of configuration data so it can float up - // or down a little bit without disrupting the mesh data + // Pad the end of configuration data so it can float up + // or down a little bit without disrupting the mesh data + return (datasize() + EEPROM_OFFSET + 32) & 0xFFF8; } #define MESH_STORE_SIZE sizeof(TERN(OPTIMIZED_MESH_STORAGE, mesh_store_t, ubl.z_values)) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 056fdf4c29..65d3fe731d 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -154,36 +154,38 @@ #define SDIO_SUPPORT #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer -#if ENABLED(CR10_STOCKDISPLAY) && NONE(RET6_12864_LCD, VET6_12864_LCD) - #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." -#endif +#if ENABLED(CR10_STOCKDISPLAY) -#if ENABLED(RET6_12864_LCD) + #if ENABLED(RET6_12864_LCD) - // RET6 12864 LCD - #define LCD_PINS_RS PB12 - #define LCD_PINS_ENABLE PB15 - #define LCD_PINS_D4 PB13 + // RET6 12864 LCD + #define LCD_PINS_RS PB12 + #define LCD_PINS_ENABLE PB15 + #define LCD_PINS_D4 PB13 - #define BTN_ENC PB2 - #define BTN_EN1 PB10 - #define BTN_EN2 PB14 + #define BTN_ENC PB2 + #define BTN_EN1 PB10 + #define BTN_EN2 PB14 - #ifndef HAS_PIN_27_BOARD - #define BEEPER_PIN PC6 + #ifndef HAS_PIN_27_BOARD + #define BEEPER_PIN PC6 + #endif + + #elif ENABLED(VET6_12864_LCD) + + // VET6 12864 LCD + #define LCD_PINS_RS PA4 + #define LCD_PINS_ENABLE PA7 + #define LCD_PINS_D4 PA5 + + #define BTN_ENC PC5 + #define BTN_EN1 PB10 + #define BTN_EN2 PA6 + + #else + #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." #endif -#elif ENABLED(VET6_12864_LCD) - - // VET6 12864 LCD - #define LCD_PINS_RS PA4 - #define LCD_PINS_ENABLE PA7 - #define LCD_PINS_D4 PA5 - - #define BTN_ENC PC5 - #define BTN_EN1 PB10 - #define BTN_EN2 PA6 - #elif EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD From fb29135c74a258eaa0ba824c9c1f00762ed59183 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Aug 2021 20:44:55 -0500 Subject: [PATCH 0615/2168] =?UTF-8?q?=E2=9C=A8=20Creality3D=20CR-30=20Prin?= =?UTF-8?q?tMill?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 3 +++ Marlin/src/feature/pause.cpp | 4 +++- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 7 +++++++ 4 files changed, 14 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index ac98b1b322..c9a900062c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -758,6 +758,9 @@ //#define COREZY //#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 +// Enable for a belt style printer with endless "Z" motion +//#define BELTPRINTER + //=========================================================================== //============================== Endstop Settings =========================== //=========================================================================== diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 79a8af66e2..9a402141e6 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -213,6 +213,8 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load set_duplication_enabled(false, DXC_ext); #endif + TERN_(BELTPRINTER, do_blocking_move_to_xy(0.00, 50.00)); + // Slow Load filament if (slow_load_length) unscaled_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); @@ -606,7 +608,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ ui.pause_show_message(PAUSE_MESSAGE_RESUME); // Check Temperature before moving hotend - ensure_safe_temperature(); + ensure_safe_temperature(DISABLED(BELTPRINTER)); // Retract to prevent oozing unscaled_e_move(-(PAUSE_PARK_RETRACT_LENGTH), feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index a512022320..3409e6714d 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -386,7 +386,7 @@ void PrintJobRecovery::resume() { ), dtostrf(z_now, 1, 3, str_1)); gcode.process_subcommands_now(cmd); - #else + #elif DISABLED(BELTPRINTER) #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) #define HOMING_Z_DOWN 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a146b95ba6..d6f911cd4c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1469,6 +1469,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "CLASSIC_JERK is required for DELTA and SCARA." #endif +/** + * Some things should not be used on Belt Printers + */ +#if BOTH(BELTPRINTER, HAS_LEVELING) + #error "Bed Leveling is not compatible with BELTPRINTER." +#endif + /** * Probes */ From bad46796495403fddfb65e793f4ca4d0e47b9843 Mon Sep 17 00:00:00 2001 From: Vert <45634861+Vertabreak@users.noreply.github.com> Date: Tue, 31 Aug 2021 03:36:00 -0400 Subject: [PATCH 0616/2168] =?UTF-8?q?=E2=9C=A8=20GT2560=20V4.x=20A20=20(#2?= =?UTF-8?q?2664)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 7 ++-- Marlin/src/pins/mega/pins_GT2560_V4_A20.h | 43 +++++++++++++++++++++++ Marlin/src/pins/pins.h | 2 ++ 3 files changed, 49 insertions(+), 3 deletions(-) create mode 100644 Marlin/src/pins/mega/pins_GT2560_V4_A20.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 6eeed447f7..d37fa0cdbc 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -149,10 +149,10 @@ #define BOARD_GT2560_REV_A 1314 // Geeetech GT2560 Rev A #define BOARD_GT2560_REV_A_PLUS 1315 // Geeetech GT2560 Rev A+ (with auto level probe) #define BOARD_GT2560_REV_B 1316 // Geeetech GT2560 Rev B -#define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/D) -#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/D) +#define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/T/D) +#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/T/D) #define BOARD_GT2560_V3_MC2 1319 // Geeetech GT2560 Rev B for Mecreator2 -#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/D) +#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/T/D) #define BOARD_EINSTART_S 1321 // Einstart retrofit #define BOARD_WANHAO_ONEPLUS 1322 // Wanhao 0ne+ i3 Mini #define BOARD_LEAPFROG_XEED2015 1323 // Leapfrog Xeed 2015 @@ -160,6 +160,7 @@ #define BOARD_PICA 1325 // PICA Shield (rev C or later) #define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) #define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) +#define BOARD_GT2560_V4_A20 1328 // Geeetech GT2560 Rev B for A20(M/T/D) // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/mega/pins_GT2560_V4_A20.h b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h new file mode 100644 index 0000000000..83a612e67c --- /dev/null +++ b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Geeetech A20 GT2560 V4.x board pin assignments + */ + +#define BOARD_INFO_NAME "GT2560 4.x" + +#define LCD_PINS_RS 5 +#define LCD_PINS_ENABLE 36 +#define LCD_PINS_D4 21 +#define LCD_PINS_D7 6 + +#define SPEAKER // The speaker can produce tones + +#if IS_NEWPANEL + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 19 +#endif + +#include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 86283dae24..064a4bb99e 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -243,6 +243,8 @@ #include "mega/pins_GT2560_REV_B.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V4) #include "mega/pins_GT2560_V4.h" // ATmega2560 env:mega2560 + #elif MB(GT2560_V4_A20) + #include "mega/pins_GT2560_V4_A20.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_MC2) #include "mega/pins_GT2560_V3_MC2.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_A20) From fc22f1f84337b5d8f93fa3fe9c06ab7911d43dc4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 1 Sep 2021 01:03:17 +0000 Subject: [PATCH 0617/2168] [cron] Bump distribution date (2021-09-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index df5f54a550..eca04a9631 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-08-31" +//#define STRING_DISTRIBUTION_DATE "2021-09-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c5fc257800..74e68f0911 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 "2021-08-31" + #define STRING_DISTRIBUTION_DATE "2021-09-01" #endif /** From 01d1192a441f5afb753185eb103be64baa81bd43 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 1 Sep 2021 22:33:24 +1200 Subject: [PATCH 0618/2168] =?UTF-8?q?=F0=9F=90=9B=20BTT=20Octopus=20X=20MA?= =?UTF-8?q?X=20pin=20for=20IDEX=20(#22654)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index bb5800aee7..d133a45718 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -72,7 +72,7 @@ #else #define X_MIN_PIN E0_DIAG_PIN // E0DET #endif -#elif ENABLED(X_DUAL_ENDSTOPS) +#elif EITHER(X_DUAL_ENDSTOPS, DUAL_X_CARRIAGE) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // X-STOP #endif From 9a9d55ceb0183640147c997fefeef375fa105a2f Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 2 Sep 2021 01:45:17 +0200 Subject: [PATCH 0619/2168] =?UTF-8?q?=F0=9F=A9=B9=20Allow=20M42=20S0/1=20a?= =?UTF-8?q?nalogWrite=20on=20PWM=20pins=20(STM32)=20(#22631)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/control/M42.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 908260ed25..eead971a01 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -127,7 +127,7 @@ void GcodeSuite::M42() { #ifdef ARDUINO_ARCH_STM32 // A simple I/O will be set to 0 by analogWrite() - if (pin_status <= 1) return; + if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif analogWrite(pin, pin_status); } From 71a2a958858f47545bb9f02764af26fb68991b36 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 2 Sep 2021 01:55:36 +0200 Subject: [PATCH 0620/2168] =?UTF-8?q?=F0=9F=94=A8=20Enhance=20Lerdge=20pin?= =?UTF-8?q?s,=20TFTs,=20and=20variants=20(#22658)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/inc/Conditionals_LCD.h | 36 ++------- Marlin/src/lcd/tft_io/st7796s.h | 38 ++-------- Marlin/src/lcd/tft_io/tft_ids.h | 1 - Marlin/src/lcd/tft_io/tft_io.cpp | 4 - Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 74 +++++++++++-------- Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 73 ++++++++++-------- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 68 ++++++++++------- buildroot/share/PlatformIO/scripts/lerdge.py | 5 +- .../PlatformIO/scripts/offset_and_rename.py | 3 +- .../MARLIN_BIGTREE_BTT002/hal_conf_extra.h | 2 +- .../MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h | 2 +- .../MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h | 2 +- .../PeripheralPins.c | 2 - .../hal_conf_extra.h | 2 +- .../hal_conf_extra.h | 2 +- .../MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h | 2 +- .../MARLIN_F103VE_LONGER/hal_conf_custom.h | 23 ++---- .../variants/MARLIN_F103Zx/hal_conf_custom.h | 2 +- .../variants/MARLIN_F407VE/hal_conf_custom.h | 2 +- .../variants/MARLIN_F4x7Vx/hal_conf_extra.h | 2 +- .../hal_conf_custom.h | 2 +- .../variants/MARLIN_LERDGE/PeripheralPins.c | 18 +++++ .../variants/MARLIN_LERDGE/variant.h | 49 ++++++------ .../MARLIN_STEVAL_F401VE/hal_conf_custom.h | 2 +- .../hal_conf_extra.h | 25 ++++--- ini/stm32f4.ini | 9 +-- 28 files changed, 233 insertions(+), 222 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c9a900062c..418c25aef7 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2710,6 +2710,7 @@ //#define TFT_RES_320x240 //#define TFT_RES_480x272 //#define TFT_RES_480x320 + //#define TFT_RES_1024x600 #endif /** diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index bfbe5ba6cf..13af3c25f5 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1219,30 +1219,19 @@ */ #if ENABLED(MKS_TS35_V2_0) // ST7796 #define TFT_DEFAULT_DRIVER ST7796 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_SPI -#elif ENABLED(ANET_ET5_TFT35) // ST7796 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) +#elif EITHER(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 + #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC -#elif ENABLED(ANET_ET4_TFT28) // ST7789 +#elif ANY(ANET_ET4_TFT28, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT24) // ST7789 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT28) // ST7789 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT32) // ST7789 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT35) // ILI9488 +#elif ANY(MKS_ROBIN_TFT35, TFT_TRONXY_X5SA, ANYCUBIC_TFT35) // ILI9488 + #define TFT_DRIVER ILI9488 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC @@ -1251,21 +1240,12 @@ #define TFT_DEFAULT_ORIENTATION 0 #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT_V1_1R) // ILI9328 or R61505 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif EITHER(TFT_TRONXY_X5SA, ANYCUBIC_TFT35) // ILI9488 - #define TFT_DRIVER ILI9488 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) - #define TFT_RES_480x320 - #define TFT_INTERFACE_FSMC -#elif ENABLED(LONGER_LK_TFT28) +#elif ANY(MKS_ROBIN_TFT_V1_1R, LONGER_LK_TFT28) // ILI9328 or R61505 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC #elif ENABLED(BIQU_BX_TFT70) // RGB - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_1024x600 #define TFT_INTERFACE_LTDC #if ENABLED(TOUCH_SCREEN) diff --git a/Marlin/src/lcd/tft_io/st7796s.h b/Marlin/src/lcd/tft_io/st7796s.h index e1931ed551..6d79dd882a 100644 --- a/Marlin/src/lcd/tft_io/st7796s.h +++ b/Marlin/src/lcd/tft_io/st7796s.h @@ -144,39 +144,11 @@ static const uint16_t st7796s_init[] = { ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, - ESC_REG(ST7796S_NORON), - ESC_REG(ST7796S_WRCTRLD), 0x0024, - ESC_REG(ST7796S_CSCON), 0x003C, // disable command 2 part I - ESC_REG(ST7796S_CSCON), 0x0069, // disable command 2 part II - ESC_REG(ST7796S_DISPON), - ESC_END -}; - -static const uint16_t lerdge_st7796s_init[] = { - DATASIZE_8BIT, - ESC_REG(ST7796S_SWRESET), ESC_DELAY(100), - ESC_REG(ST7796S_SLPOUT), ESC_DELAY(20), - - ESC_REG(ST7796S_CSCON), 0x00C3, // enable command 2 part I - ESC_REG(ST7796S_CSCON), 0x0096, // enable command 2 part II - - ESC_REG(ST7796S_MADCTL), ST7796S_MADCTL_DATA, - ESC_REG(ST7796S_COLMOD), 0x0055, - - ESC_REG(ST7796S_DIC), 0x0001, // 1-dot inversion - ESC_REG(ST7796S_EM), 0x00C6, - - ESC_REG(ST7796S_PWR2), 0x0015, - ESC_REG(ST7796S_PWR3), 0x00AF, - ESC_REG(ST7796S_VCMPCTL), 0x0022, - ESC_REG(ST7796S_VCMOST), 0x0000, - ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, - - /* Gamma Correction. */ - ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, - ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, - - ESC_REG(ST7796S_INVON), // Display inversion ON + #if ENABLED(ST7796S_INVERTED) + ESC_REG(ST7796S_INVON), // Display inversion ON + #else + ESC_REG(ST7796S_NORON), + #endif ESC_REG(ST7796S_WRCTRLD), 0x0024, ESC_REG(ST7796S_CSCON), 0x003C, // disable command 2 part I ESC_REG(ST7796S_CSCON), 0x0069, // disable command 2 part II diff --git a/Marlin/src/lcd/tft_io/tft_ids.h b/Marlin/src/lcd/tft_io/tft_ids.h index c4f6127c68..2de111366c 100644 --- a/Marlin/src/lcd/tft_io/tft_ids.h +++ b/Marlin/src/lcd/tft_io/tft_ids.h @@ -31,5 +31,4 @@ #define ILI9341 0x9341 #define ILI9488 0x9488 #define ILI9488_ID1 0x8066 // Some ILI9488 have 0x8066 in the 0x04 -#define LERDGE_ST7796 0xFFFE #define AUTO 0xFFFF diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index ded711b577..707232b4bb 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -97,10 +97,6 @@ if (lcd_id != 0xFFFFFFFF) return; write_esc_sequence(ili9341_init); #elif TFT_DRIVER == ILI9488 write_esc_sequence(ili9488_init); - #elif TFT_DRIVER == LERDGE_ST7796 - lcd_id = ST7796; - write_esc_sequence(lerdge_st7796s_init); - #elif TFT_DRIVER == AUTO // autodetect lcd_id = io.GetID() & 0xFFFF; diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 1b3cf15e5a..04f9afaad2 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -427,10 +427,10 @@ #define TFT_DRIVER ST7796 #endif #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION 63934 + #define XPT2046_X_CALIBRATION 63934 #endif #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 63598 + #define XPT2046_Y_CALIBRATION 63598 #endif #ifndef XPT2046_X_OFFSET #define XPT2046_X_OFFSET -1 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 4adc2f65a2..3cfa3cd3e5 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -72,42 +72,43 @@ #define X_DIR_PIN PB10 #define X_ENABLE_PIN PG0 //#ifndef X_CS_PIN -// #define X_CS_PIN PE0 +// #define X_CS_PIN PB2 //#endif #define Y_STEP_PIN PF14 #define Y_DIR_PIN PF15 #define Y_ENABLE_PIN PF13 //#ifndef Y_CS_PIN -// #define Y_CS_PIN PE1 +// #define Y_CS_PIN PE2 //#endif #define Z_STEP_PIN PF11 #define Z_DIR_PIN PF12 #define Z_ENABLE_PIN PC5 //#ifndef Z_CS_PIN -// #define Z_CS_PIN PE2 +// #define Z_CS_PIN PE3 //#endif #define E0_STEP_PIN PC14 #define E0_DIR_PIN PC13 #define E0_ENABLE_PIN PC15 //#ifndef E0_CS_PIN -// #define E0_CS_PIN PE3 +// #define E0_CS_PIN PE4 //#endif #define E1_STEP_PIN PF1 #define E1_DIR_PIN PF0 #define E1_ENABLE_PIN PF2 //#ifndef E1_CS_PIN -// #define E1_CS_PIN PE4 +// #define E1_CS_PIN PE1 //#endif -//#define E2_STEP_PIN PF4 // best guess -//#define E2_DIR_PIN PF3 // best guess -//#define E2_ENABLE_PIN PF5 // best guess -//#ifndef E2_CS_PIN -// #define E2_CS_PIN PB2 // best guess +//#define Z2_STEP_PIN PF4 +//#define Z2_DIR_PIN PF3 +//#define Z2_ENABLE_PIN PF5 +//#define Z2_STOP_PIN PG2 +//#ifndef Z2_CS_PIN +// #define Z2_CS_PIN PE0 //#endif #if HAS_TMC_UART @@ -144,12 +145,17 @@ #ifndef E1_SERIAL_RX_PIN #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN #endif + // Ex-motor can be any... X2/Y2/Z2 or E2 #ifndef EX_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN PE0 + #define EX_SERIAL_TX_PIN PE0 #endif #ifndef EX_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN + #define EX_SERIAL_RX_PIN EX_SERIAL_TX_PIN #endif + //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN + //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif @@ -193,8 +199,8 @@ // // LED / Lighting // -//#define CASE_LIGHT_PIN_CI -1 -//#define CASE_LIGHT_PIN_DO -1 +#define LED_PIN PA15 // Status LED +//#define CASE_LIGHT_PIN PB6 // LED Ribbon Connector (PWM TIM4_CH1) //#define NEOPIXEL_PIN -1 #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB8 // swap R and G pin for compatibility with real wires @@ -211,44 +217,54 @@ // #define SDIO_SUPPORT #define SDIO_CLOCK 4800000 +#define SD_DETECT_PIN PA8 +#if DISABLED(SDIO_SUPPORT) + #define SOFTWARE_SPI + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN PC11 + #define SDSS PC11 +#endif // // Misc. Functions // -#define SDSS PC11 -#define LED_PIN PA15 // Alive #define PS_ON_PIN PA4 #define KILL_PIN -1 #define POWER_LOSS_PIN PA4 // Power-loss / nAC_FAULT -#define SD_SCK_PIN PC12 -#define SD_MISO_PIN PC8 -#define SD_MOSI_PIN PD2 -#define SD_SS_PIN PC11 - -#define SD_DETECT_PIN PA8 -#define BEEPER_PIN PC7 - // // TFT with FSMC interface // #if HAS_FSMC_TFT - //#define TFT_DRIVER LERDGE_ST7796 + #ifndef TFT_DRIVER + #define TFT_DRIVER ST7796 + #endif + #define ST7796S_INVERTED #define TFT_RESET_PIN PD6 #define TFT_BACKLIGHT_PIN PD3 - #define TFT_CS_PIN PD7 - #define TFT_RS_PIN PD11 + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define TOUCH_CS_PIN PG15 #define TOUCH_SCK_PIN PB3 #define TOUCH_MOSI_PIN PB5 #define TOUCH_MISO_PIN PB4 + #define TOUCH_INT_PIN PG12 #endif #if IS_NEWPANEL - #define BTN_EN1 PG10 - #define BTN_EN2 PG11 + #define BEEPER_PIN PC7 + #define BTN_EN1 PG11 + #define BTN_EN2 PG10 #define BTN_ENC PG9 + #ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM 2 + #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 4707a16e14..2d5a45eee0 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -31,8 +31,6 @@ #define STEP_TIMER 4 #define TEMP_TIMER 2 -//#define I2C_EEPROM - // USB Flash Drive support #define HAS_OTG_USB_HOST_SUPPORT @@ -150,7 +148,6 @@ // // Misc. Functions // -#define SDSS PC11 // SD is working using SDIO, not sure if this definition is needed? #define LED_PIN PC6 // Mainboard soldered green LED #define PS_ON_PIN PB2 // Board has a power module connector #define KILL_PIN -1 // There is no reset button on the LCD @@ -161,23 +158,25 @@ // #define SDIO_SUPPORT #define SDIO_CLOCK 4800000 - -#define SD_SCK_PIN PC12 -#define SD_MISO_PIN PC8 -#define SD_MOSI_PIN PD2 -#define SD_SS_PIN PC11 - #define SD_DETECT_PIN PG15 +#if DISABLED(SDIO_SUPPORT) + #define SOFTWARE_SPI + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN PC11 + #define SDSS PC11 +#endif // // Persistent Storage // If no option is selected below the SD Card will be used -// (this section modelled after pins_LONGER3D_LK.h) -// Warning: Not tested yet! Pins traced with multimeter, mistakes are possible -//#define SPI_EEPROM +// Prefer the I2C option (F-RAM) to store Marlin settings, SPI option is not working yet -#if ENABLED(SPI_EEPROM) - // Lerdge has an SPI EEPROM Winbond W25Q128 (128Mbits) https://www.pjrc.com/teensy/W25Q128FV.pdf +//#define SPI_EEPROM +//#define I2C_EEPROM + +#if ENABLED(SPI_EEPROM) // SPI EEPROM Winbond W25Q128 (128Mbits) https://www.pjrc.com/teensy/W25Q128FV.pdf #define SPI_CHAN_EEPROM1 1 #define SPI_EEPROM1_CS_PIN PB12 // datasheet: /CS pin, found with multimeter, not tested #define EEPROM_SCK_PIN PB13 // datasheet: CLK pin, found with multimeter, not tested @@ -185,29 +184,45 @@ #define EEPROM_MOSI_PIN PB15 // datasheet: DI pin, found with multimeter, not tested #define EEPROM_PAGE_SIZE 0x1000U // 4KB (from datasheet) #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64KB for now... +#elif ENABLED(I2C_EEPROM) // FM24CL64BG (CYP1813) 64Kbit F-RAM + #define SOFT_I2C_EEPROM // Force the use of Software I2C + #define I2C_SDA_PIN PG13 + #define I2C_SCL_PIN PG14 // To be confirmed on the Lerdge S, but probably same as the K + #define MARLIN_EEPROM_SIZE 0x10000 #else #define MARLIN_EEPROM_SIZE 0x800U // On SD, Limit to 2KB, require this amount of RAM #endif // -// LCD / Controller +// TFT with FSMC interface // +#if HAS_FSMC_TFT + #ifndef TFT_DRIVER + #define TFT_DRIVER ST7796 + #endif + #define ST7796S_INVERTED -// The LCD is initialized in FSMC mode -#define BEEPER_PIN PD13 + #define TFT_RESET_PIN PD6 + #define TFT_BACKLIGHT_PIN PD3 -#define BTN_EN1 PC14 -#define BTN_EN2 PC15 -#define BTN_ENC PC13 + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 -#define TFT_RESET_PIN PD6 -#define TFT_BACKLIGHT_PIN PD3 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN -#define TFT_CS_PIN PD7 // TFT works -#define TFT_RS_PIN PD11 // TFT works + #define TOUCH_CS_PIN PB6 + #define TOUCH_SCK_PIN PB3 + #define TOUCH_MOSI_PIN PB5 + #define TOUCH_MISO_PIN PB4 +#endif -// There is touch, but calibration is off -#define TOUCH_CS_PIN PB6 -#define TOUCH_SCK_PIN PB3 -#define TOUCH_MOSI_PIN PB5 -#define TOUCH_MISO_PIN PB4 +#if IS_NEWPANEL + #define BEEPER_PIN PD13 + #define BTN_EN1 PC15 + #define BTN_EN2 PC14 + #define BTN_ENC PC13 + #ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM 2 + #endif +#endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index 3a9c286e00..f65476c0b7 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -113,10 +113,24 @@ //#define CASE_LIGHT_PIN_DO -1 //#define NEOPIXEL_PIN -1 +// +// SD support (On board) +// +#define SDIO_SUPPORT +#define SD_DETECT_PIN PA8 +#define SDIO_CLOCK 4800000 +#if DISABLED(SDIO_SUPPORT) + #define SOFTWARE_SPI + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 + #define SD_SS_PIN PC11 + #define SDSS PC11 +#endif + // // Misc. Functions // -#define SDSS PC11 #define LED_PIN PC7 // Alive #define PS_ON_PIN -1 #define KILL_PIN -1 @@ -124,36 +138,36 @@ // Lerdge supports auto-power off and power loss sense through a single pin. #define POWER_LOSS_PIN PC14 // Power-loss / nAC_FAULT -#define SD_SCK_PIN PC12 -#define SD_MISO_PIN PC8 -#define SD_MOSI_PIN PD2 -#define SD_SS_PIN PC11 - // -// SD support +// TFT with FSMC interface // -#define SDIO_SUPPORT -#define SD_DETECT_PIN PA8 -#define SDIO_CLOCK 4800000 +#if HAS_FSMC_TFT + #ifndef TFT_DRIVER + #define TFT_DRIVER ST7796 + #endif + #define ST7796S_INVERTED -// -// LCD / Controller -// + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 -// The LCD is initialized in FSMC mode -#define BEEPER_PIN PD12 + #define TFT_RESET_PIN PD6 + #define TFT_BACKLIGHT_PIN PD3 -#define BTN_EN1 PE3 -#define BTN_EN2 PE4 -#define BTN_ENC PE2 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN -#define TFT_RESET_PIN PD6 -#define TFT_BACKLIGHT_PIN PD3 + #define TOUCH_CS_PIN PB6 + #define TOUCH_SCK_PIN PB3 + #define TOUCH_MOSI_PIN PB5 + #define TOUCH_MISO_PIN PB4 +#endif -#define TFT_CS_PIN PD7 -#define TFT_RS_PIN PD11 - -#define TOUCH_CS_PIN PB6 -#define TOUCH_SCK_PIN PB3 -#define TOUCH_MOSI_PIN PB5 -#define TOUCH_MISO_PIN PB4 +#if IS_NEWPANEL + #define BEEPER_PIN PD12 + #define BTN_EN1 PE4 + #define BTN_EN2 PE3 + #define BTN_ENC PE2 + #ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM 2 + #endif +#endif diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 5c35c19e7d..654f0ad4df 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -41,7 +41,8 @@ def encrypt(source, target, env): renamed.close() if 'encrypt' in board.get("build").keys(): - marlin.add_post_action(encrypt); + if board.get("build.encrypt") != "": + marlin.add_post_action(encrypt) else: print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") - exit(1); + exit(1) diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index b42b2f3531..9caed298e4 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -45,7 +45,8 @@ if 'encrypt' in board_keys: def encrypt(source, target, env): marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) - marlin.add_post_action(encrypt); + if board.get("build.encrypt") != "": + marlin.add_post_action(encrypt) # # For build.rename simply rename the firmware file. diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h index 40b340c205..ef621d57bf 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/hal_conf_extra.h @@ -4,6 +4,7 @@ #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -32,7 +33,6 @@ //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h index 2c1557cbbb..b4eb0f9b5f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/hal_conf_extra.h @@ -4,6 +4,7 @@ #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -32,7 +33,6 @@ #undef HAL_SRAM_MODULE_ENABLED #undef HAL_SDRAM_MODULE_ENABLED #undef HAL_HASH_MODULE_ENABLED -#undef HAL_EXTI_MODULE_ENABLED #undef HAL_SMBUS_MODULE_ENABLED #undef HAL_I2S_MODULE_ENABLED #undef HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h index 40b340c205..ef621d57bf 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/hal_conf_extra.h @@ -4,6 +4,7 @@ #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -32,7 +33,6 @@ //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c index a4f8f696ee..9df61baf9b 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c @@ -392,9 +392,7 @@ const PinMap PinMap_USB_OTG_FS[] = { {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP {NC, NP, 0} }; -#endif -#ifdef HAL_PCD_MODULE_ENABLED const PinMap PinMap_USB_OTG_HS[] = { //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h index 42c76a4bbf..d62c510095 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h @@ -4,6 +4,7 @@ #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -33,7 +34,6 @@ #undef HAL_SRAM_MODULE_ENABLED #undef HAL_SDRAM_MODULE_ENABLED #undef HAL_HASH_MODULE_ENABLED -#undef HAL_EXTI_MODULE_ENABLED #undef HAL_SMBUS_MODULE_ENABLED #undef HAL_I2S_MODULE_ENABLED #undef HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h index 40b340c205..ef621d57bf 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/hal_conf_extra.h @@ -4,6 +4,7 @@ #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -32,7 +33,6 @@ //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h index 4050fe810f..99f3a30443 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/hal_conf_extra.h @@ -51,7 +51,7 @@ extern "C" { #define HAL_DMA2D_MODULE_ENABLED #define HAL_DSI_MODULE_ENABLED #define HAL_ETH_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_FDCAN_MODULE_ENABLED #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h index fd20d8fe6f..3a6b7037ad 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103VE_LONGER/hal_conf_custom.h @@ -20,11 +20,6 @@ extern "C" { */ #include "stm32yyxx_hal_conf.h" -#undef HAL_PWR_MODULE_ENABLED -#define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) - -#define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG - #ifdef HAL_PCD_MODULE_ENABLED #warning "No direct STM32 USB pins on Longer3D board" #undef HAL_PCD_MODULE_ENABLED // USB Device @@ -35,20 +30,20 @@ extern "C" { #undef HAL_HCD_MODULE_ENABLED // USB Host #endif -#ifndef HAL_USART_MODULE_ENABLED - //#define HAL_USART_MODULE_ENABLED // Useless.... UART_MODULE do it -#endif +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts +#define HAL_IWDG_MODULE_ENABLED // USE_WATCHDOG + +#undef HAL_PWR_MODULE_ENABLED +#define HAL_PWR_MODULE_ONLY // disable low power & PA0 wakeup pin (its T°c pin) #undef HAL_CAN_LEGACY_MODULE_ENABLED #undef HAL_CAN_MODULE_ENABLED #undef HAL_DAC_MODULE_ENABLED #undef HAL_RTC_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED // for ENDSTOP_INTERRUPTS_FEATURE - /** - * @brief List of modules in the framework (first ones enabled by default) - */ + * @brief List of modules in the framework (first ones enabled by default) + */ //#define HAL_MODULE_ENABLED //#define HAL_ADC_MODULE_ENABLED //#define HAL_CORTEX_MODULE_ENABLED @@ -66,13 +61,11 @@ extern "C" { //#define HAL_SRAM_MODULE_ENABLED //#define HAL_TIM_MODULE_ENABLED //#define HAL_UART_MODULE_ENABLED - //#define HAL_CAN_MODULE_ENABLED //#define HAL_CAN_LEGACY_MODULE_ENABLED //#define HAL_CEC_MODULE_ENABLED //#define HAL_CRC_MODULE_ENABLED //#define HAL_ETH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_HCD_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IRDA_MODULE_ENABLED @@ -81,7 +74,7 @@ extern "C" { //#define HAL_NOR_MODULE_ENABLED //#define HAL_PCCARD_MODULE_ENABLED //#define HAL_SMARTCARD_MODULE_ENABLED -//#define HAL_USART_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED // Useless.... UART_MODULE does it //#define HAL_WWDG_MODULE_ENABLED //#define HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h index 7d19d532a5..a41247b9b1 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Zx/hal_conf_custom.h @@ -41,7 +41,7 @@ extern "C" { #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h index 1252bc7059..58e9646b57 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h @@ -36,6 +36,7 @@ extern "C" { #define HAL_CRC_MODULE_ENABLED #define HAL_DAC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED @@ -61,7 +62,6 @@ extern "C" { //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h index 0c44f08742..952fe3c5b8 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/hal_conf_extra.h @@ -40,6 +40,7 @@ #define HAL_CRC_MODULE_ENABLED #define HAL_DAC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED #define HAL_PWR_MODULE_ENABLED @@ -64,7 +65,6 @@ //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h index 395bfcd4b7..2ff2fd686e 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/hal_conf_custom.h @@ -35,6 +35,7 @@ extern "C" { #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED @@ -61,7 +62,6 @@ extern "C" { //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_LTDC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c index 044f555a41..7f6b32c228 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/PeripheralPins.c @@ -398,3 +398,21 @@ const PinMap PinMap_USB_OTG_HS[] = { {NC, NP, 0} }; #endif + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { +//{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 +//{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 +//{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 +//{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h index 87033a68e5..f4488356b7 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h @@ -163,32 +163,37 @@ extern "C" { // Below SPI and I2C definitions already done in the core // Could be redefined here if differs from the default one // SPI Definitions -#define PIN_SPI_SS PF11 -#define PIN_SPI_MOSI PB15 -#define PIN_SPI_MISO PB14 -#define PIN_SPI_SCK PB13 +// SPI1 (Winbond on the Lerdge-K) +//#define PIN_SPI_SS PC4 +//#define PIN_SPI_SCK PA5 +//#define PIN_SPI_MISO PA6 +//#define PIN_SPI_MOSI PA7 +// SPI2 (Winbond on the Lerdge-S) +//#define PIN_SPI_SS PB12 +//#define PIN_SPI_SCK PB13 +//#define PIN_SPI_MISO PB14 +//#define PIN_SPI_MOSI PB15 -//max6675 -//#define PIN_SPI_SS PA4 -//#define PIN_SPI_SCK PA5 -//#define PIN_SPI_MISO PA6 -//#define PIN_SPI_MOSI PA7 - - - - -// I2C Definitions -#define PIN_WIRE_SDA PB7 -#define PIN_WIRE_SCL PB6 +// I2C Definitions (Software I2C) +//#define PIN_WIRE_SDA PG13 +//#define PIN_WIRE_SCL PG14 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM6 - -// Do not use basic timer: OC is required -#define TIMER_SERVO TIM1 //TODO: advanced-control timers don't work +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// FANs may require PWM timers 3 10 11 13 +// The LED/RGB connectors timer 4 +// Beware: STEP_TIMER default is 6 and TEMP_TIMER 14 for the F407 +#ifndef TIMER_TONE + #define TIMER_TONE TIM8 // TIM3 or TIM8 for SPEAKER compat on the lerdge K (PC6) +#endif // TIM4 for that on the Lerdge S (PD11) +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM1 // Ideally TIM2 for Hardware PWM (PB11) +#endif // TIM4 on the S (PD12) +#ifndef TIMER_SERIAL + #define TIMER_SERIAL TIM7 // Default used in SoftwareSerial lib +#endif // UART Definitions // Define here Serial instance number to map on Serial generic name @@ -208,6 +213,8 @@ extern "C" { /* Extra HAL modules */ //#define HAL_DAC_MODULE_ENABLED #define HAL_SD_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #ifdef __cplusplus } // extern "C" diff --git a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h index aeaaf890f2..7d013d2b27 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_STEVAL_F401VE/hal_conf_custom.h @@ -35,6 +35,7 @@ extern "C" { #define HAL_ADC_MODULE_ENABLED #define HAL_CRC_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts #define HAL_FLASH_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED #define HAL_I2C_MODULE_ENABLED @@ -62,7 +63,6 @@ extern "C" { //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_LTDC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h index 8c46edb50e..2ad2905023 100755 --- a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_LITE_V2/hal_conf_extra.h @@ -36,6 +36,19 @@ */ #define HAL_MODULE_ENABLED #define HAL_ADC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +#define HAL_PCD_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default + //#define HAL_CAN_MODULE_ENABLED //#define HAL_CAN_LEGACY_MODULE_ENABLED //#define HAL_CRC_MODULE_ENABLED @@ -43,40 +56,28 @@ //#define HAL_CRYP_MODULE_ENABLED //#define HAL_DAC_MODULE_ENABLED //#define HAL_DCMI_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED //#define HAL_DMA2D_MODULE_ENABLED //#define HAL_ETH_MODULE_ENABLED -#define HAL_FLASH_MODULE_ENABLED //#define HAL_NAND_MODULE_ENABLED //#define HAL_NOR_MODULE_ENABLED //#define HAL_PCCARD_MODULE_ENABLED //#define HAL_SRAM_MODULE_ENABLED //#define HAL_SDRAM_MODULE_ENABLED //#define HAL_HASH_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -//#define HAL_EXTI_MODULE_ENABLED //#define HAL_I2C_MODULE_ENABLED //#define HAL_SMBUS_MODULE_ENABLED //#define HAL_I2S_MODULE_ENABLED //#define HAL_IWDG_MODULE_ENABLED //#define HAL_LTDC_MODULE_ENABLED //#define HAL_DSI_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED //#define HAL_QSPI_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED //#define HAL_RNG_MODULE_ENABLED //#define HAL_RTC_MODULE_ENABLED //#define HAL_SAI_MODULE_ENABLED //#define HAL_SD_MODULE_ENABLED -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -//#define HAL_UART_MODULE_ENABLED // by default -#define HAL_USART_MODULE_ENABLED //#define HAL_IRDA_MODULE_ENABLED //#define HAL_SMARTCARD_MODULE_ENABLED //#define HAL_WWDG_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -#define HAL_PCD_MODULE_ENABLED //#define HAL_HCD_MODULE_ENABLED //#define HAL_FMPI2C_MODULE_ENABLED //#define HAL_SPDIFRX_MODULE_ENABLED diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 29dd933078..6870345121 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -255,14 +255,13 @@ board_build.encrypt = firmware.bin board_build.offset = 0x10000 build_flags = ${stm32_variant.build_flags} -DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4 - -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DARDUINO_LERDGE - -DHAL_SRAM_MODULE_ENABLED + -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DLERDGE_TFT35 build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 extra_scripts = ${stm32_variant.extra_scripts} buildroot/share/PlatformIO/scripts/lerdge.py # -# Lerdge X +# Lerdge X (STM32F407VE) # [env:LERDGEX] platform = ${lerdge_common.platform} @@ -279,7 +278,7 @@ platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # -# Lerdge S +# Lerdge S (STM32F407ZG) # [env:LERDGES] platform = ${lerdge_common.platform} @@ -296,7 +295,7 @@ platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # -# Lerdge K +# Lerdge K (STM32F407ZG) # [env:LERDGEK] platform = ${lerdge_common.platform} From 3a2eb574e2027b966fb398959f8c8750ae3a3c73 Mon Sep 17 00:00:00 2001 From: DvoraNoob <62312359+DvoraNoob@users.noreply.github.com> Date: Wed, 1 Sep 2021 21:29:20 -0300 Subject: [PATCH 0621/2168] =?UTF-8?q?=F0=9F=9A=B8=20MKS=20UI=20extrusion?= =?UTF-8?q?=20speed/steps=20config=20(#22656)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/lcd/extui/mks_ui/draw_extrusion.cpp | 90 ++++++++----------- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 15 ++-- Marlin/src/lcd/extui/mks_ui/draw_ui.h | 10 ++- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 20 ++--- buildroot/bin/mftest | 2 +- buildroot/tests/mks_robin_nano35 | 32 +++---- 6 files changed, 75 insertions(+), 94 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index 2f9009bcdb..d1132a33d8 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -89,20 +89,18 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { disp_extru_amount(); break; case ID_E_STEP: - switch (ABS(uiCfg.extruStep)) { - case 1: uiCfg.extruStep = 5; break; - case 5: uiCfg.extruStep = 10; break; - case 10: uiCfg.extruStep = 1; break; - default: break; + switch (uiCfg.extruStep) { + case uiCfg.eStepMin: uiCfg.extruStep = uiCfg.eStepMed; break; + case uiCfg.eStepMed: uiCfg.extruStep = uiCfg.eStepMax; break; + case uiCfg.eStepMax: uiCfg.extruStep = uiCfg.eStepMin; break; } disp_ext_step(); break; case ID_E_SPEED: switch (uiCfg.extruSpeed) { - case 1: uiCfg.extruSpeed = 10; break; - case 10: uiCfg.extruSpeed = 20; break; - case 20: uiCfg.extruSpeed = 1; break; - default: break; + case uiCfg.eSpeedL: uiCfg.extruSpeed = uiCfg.eSpeedN; break; + case uiCfg.eSpeedN: uiCfg.extruSpeed = uiCfg.eSpeedH; break; + case uiCfg.eSpeedH: uiCfg.extruSpeed = uiCfg.eSpeedL; break; } disp_ext_speed(); break; @@ -155,41 +153,30 @@ void lv_draw_extrusion() { void disp_ext_type() { if (uiCfg.extruderIndex == 1) { lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); - if (gCfgItems.multiple_language) { - lv_label_set_text(labelType, extrude_menu.ext2); - lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } + if (gCfgItems.multiple_language) lv_label_set_text(labelType, extrude_menu.ext2); } else { lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); - if (gCfgItems.multiple_language) { - lv_label_set_text(labelType, extrude_menu.ext1); - lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } + if (gCfgItems.multiple_language) lv_label_set_text(labelType, extrude_menu.ext1); } + if (gCfgItems.multiple_language) + lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } void disp_ext_speed() { - if (uiCfg.extruSpeed == 20) - lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_high.bin"); - else if (uiCfg.extruSpeed == 1) - lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_slow.bin"); - else - lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_normal.bin"); + switch (uiCfg.extruSpeed) { + case uiCfg.eSpeedH: lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_high.bin"); break; + case uiCfg.eSpeedL: lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_slow.bin"); break; + case uiCfg.eSpeedN: lv_imgbtn_set_src_both(buttonSpeed, "F:/bmp_speed_normal.bin"); break; + } if (gCfgItems.multiple_language) { - if (uiCfg.extruSpeed == 20) { - lv_label_set_text(labelSpeed, extrude_menu.high); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruSpeed == 1) { - lv_label_set_text(labelSpeed, extrude_menu.low); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else { - lv_label_set_text(labelSpeed, extrude_menu.normal); - lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + switch (uiCfg.extruSpeed) { + case uiCfg.eSpeedH: lv_label_set_text(labelSpeed, extrude_menu.high); break; + case uiCfg.eSpeedL: lv_label_set_text(labelSpeed, extrude_menu.low); break; + case uiCfg.eSpeedN: lv_label_set_text(labelSpeed, extrude_menu.normal); break; } + lv_obj_align(labelSpeed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } @@ -221,33 +208,28 @@ void disp_extru_amount() { } void disp_ext_step() { - if (uiCfg.extruStep == 1) - lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step1_mm.bin"); - else if (uiCfg.extruStep == 5) - lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step5_mm.bin"); - else if (uiCfg.extruStep == 10) - lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step10_mm.bin"); + char buf3[12]; + sprintf_P(buf3, PSTR("%dmm"), uiCfg.extruStep); + + switch (uiCfg.extruStep) { + case uiCfg.eStepMin: lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step1_mm.bin"); break; + case uiCfg.eStepMed: lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step5_mm.bin"); break; + case uiCfg.eStepMax: lv_imgbtn_set_src_both(buttonStep, "F:/bmp_step10_mm.bin"); break; + } if (gCfgItems.multiple_language) { - if (uiCfg.extruStep == 1) { - lv_label_set_text(labelStep, extrude_menu.step_1mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruStep == 5) { - lv_label_set_text(labelStep, extrude_menu.step_5mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - else if (uiCfg.extruStep == 10) { - lv_label_set_text(labelStep, extrude_menu.step_10mm); - lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + switch (uiCfg.extruStep) { + case uiCfg.eStepMin: lv_label_set_text(labelStep, buf3); break; + case uiCfg.eStepMed: lv_label_set_text(labelStep, buf3); break; + case uiCfg.eStepMax: lv_label_set_text(labelStep, buf3); break; } + lv_obj_align(labelStep, buttonStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } void lv_clear_extrusion() { - #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); - #endif + if (TERN0(HAS_ROTARY_ENCODER, gCfgItems.encoder_enable)) + lv_group_remove_all_objs(g); lv_obj_del(scr); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 7dfbea5bae..e324c32def 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -186,10 +186,10 @@ void ui_cfg_init() { uiCfg.stepHeat = 10; uiCfg.leveling_first_time = false; uiCfg.para_ui_page = false; - uiCfg.extruStep = 5; - uiCfg.extruSpeed = 10; + uiCfg.extruStep = uiCfg.eStepMed; + uiCfg.extruSpeed = uiCfg.eSpeedN; uiCfg.move_dist = 1; - uiCfg.moveSpeed = 3000; + uiCfg.moveSpeed = 1000; uiCfg.stepPrintSpeed = 10; uiCfg.command_send = false; uiCfg.dialogType = 0; @@ -609,9 +609,9 @@ char *creat_title_text() { gPicturePreviewStart += (uintptr_t)p1 - (uintptr_t)((uint32_t *)(&public_buf[0])); break; } - else { + else gPicturePreviewStart += br; - } + if (br < 400) break; } } @@ -623,11 +623,8 @@ char *creat_title_text() { while (1) { card.read(public_buf, 400); - for (i = 0; i < 400;) { + for (i = 0; i < 400; i += 2, j++) bmp_public_buf[j] = ascii2dec_test((char*)&public_buf[i]) << 4 | ascii2dec_test((char*)&public_buf[i + 1]); - i += 2; - j++; - } if (j >= 400) break; } for (i = 0; i < 400; i += 2) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h index 37b19ebd46..b7e66a2727 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -208,7 +208,7 @@ typedef struct { uint32_t curFilesize; } CFG_ITMES; -typedef struct { +typedef struct UI_Config_Struct { uint8_t curTempType:1, extruderIndex:3, stepHeat:4, @@ -228,8 +228,16 @@ typedef struct { uint8_t wifi_name[32]; uint8_t wifi_key[64]; uint8_t cloud_hostUrl[96]; + // Extruder Steps distances (mm) uint8_t extruStep; + static constexpr uint8_t eStepMin = 1, + eStepMed = 5, + eStepMax = 10; + // Extruder speed (mm/s) uint8_t extruSpeed; + static constexpr uint8_t eSpeedH = 1, + eSpeedN = 10, + eSpeedL = 20; uint8_t print_state; uint8_t stepPrintSpeed; uint8_t waitEndMoves; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index b53586c756..998393ebd5 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -1445,16 +1445,12 @@ void utf8_2_unicode(uint8_t *source, uint8_t Len) { ZERO(FileName_unicode); - while (1) { + for (;;) { char_byte_num = source[i] & 0xF0; - if (source[i] < 0x80) { - //ASCII --1byte - FileName_unicode[char_i] = source[i]; - i += 1; - char_i += 1; + if (source[i] < 0x80) { // ASCII -- 1 byte + FileName_unicode[char_i++] = source[i++]; } - else if (char_byte_num == 0xC0 || char_byte_num == 0xD0) { - //--2byte + else if (char_byte_num == 0xC0 || char_byte_num == 0xD0) { // -- 2 byte u16_h = (((uint16_t)source[i] << 8) & 0x1F00) >> 2; u16_l = ((uint16_t)source[i + 1] & 0x003F); u16_value = (u16_h | u16_l); @@ -1463,8 +1459,7 @@ void utf8_2_unicode(uint8_t *source, uint8_t Len) { i += 2; char_i += 2; } - else if (char_byte_num == 0xE0) { - //--3byte + else if (char_byte_num == 0xE0) { // -- 3 byte u16_h = (((uint16_t)source[i] << 8) & 0x0F00) << 4; u16_m = (((uint16_t)source[i + 1] << 8) & 0x3F00) >> 2; u16_l = ((uint16_t)source[i + 2] & 0x003F); @@ -1474,8 +1469,7 @@ void utf8_2_unicode(uint8_t *source, uint8_t Len) { i += 3; char_i += 2; } - else if (char_byte_num == 0xF0) { - //--4byte + else if (char_byte_num == 0xF0) { // -- 4 byte i += 4; //char_i += 3; } @@ -1510,7 +1504,7 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { TERN_(SDSUPPORT, card.mount()); } else if (gCfgItems.fileSysType == FILE_SYS_USB) { - + // nothing } file_writer.write_index = 0; lastFragment = -1; diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index 17605e3174..7a55033e9e 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -133,7 +133,7 @@ lp9|lpc9) TESTENV='LPC1769' ;; t36) TESTENV='teensy35' ;; t40) TESTENV='teensy41' ;; t41) TESTENV='teensy41' ;; -[1-9][1-9]|[1-9]) TESTNUM=$TESTENV ; TESTENV=- ;; +[1-9]|[1-9][0-9]) TESTNUM=$TESTENV ; TESTENV=- ;; esac if ((AUTO_BUILD)); then diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 index bd16fe48e9..f892d42d9e 100755 --- a/buildroot/tests/mks_robin_nano35 +++ b/buildroot/tests/mks_robin_nano35 @@ -15,15 +15,15 @@ opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" # -# MKS Robin v2 nano Emulated DOGM SPI -# (Robin v2 nano has no FSMC interface) +# MKS Robin nano v2 Emulated DOGM SPI +# (Robin nano v2 has no FSMC interface) # use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC opt_enable TFT_INTERFACE_SPI MKS_WIFI_MODULE opt_add MKS_TEST -exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" +exec_test $1 $2 "MKS Robin nano v2 Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" # # MKS Robin nano v1.2 LVGL FSMC @@ -35,34 +35,34 @@ exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI, MKS_WIFI_MODULE" "$3" # exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" # -# MKS Robin v2 nano LVGL SPI -# (Robin v2 nano has no FSMC interface) +# MKS Robin nano v2 LVGL SPI +# (Robin nano v2 has no FSMC interface) # # use_example_configs Mks/Robin # opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 # opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 # opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" +# exec_test $1 $2 "MKS Robin nano v2 LVGL SPI" "$3" # -# MKS Robin v2 nano New Color UI 480x320 SPI -# (Robin v2 nano has no FSMC interface) +# MKS Robin nano v2 New Color UI 480x320 SPI +# (Robin nano v2 has no FSMC interface) # use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" +exec_test $1 $2 "MKS Robin nano v2 with New Color UI 480x320 SPI" "$3" # -# MKS Robin v2 nano LVGL SPI + TMC -# (Robin v2 nano has no FSMC interface) +# MKS Robin nano v2 LVGL SPI + TMC +# (Robin nano v2 has no FSMC interface) # -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 -# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin nano v2 LVGL SPI + TMC" "$3" # cleanup restore_configs From 682d6c99c7d9d0f89a260e1e72b9e776327bb82e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 2 Sep 2021 01:03:55 +0000 Subject: [PATCH 0622/2168] [cron] Bump distribution date (2021-09-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index eca04a9631..174752711a 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-01" +//#define STRING_DISTRIBUTION_DATE "2021-09-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 74e68f0911..c839ceb5bd 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 "2021-09-01" + #define STRING_DISTRIBUTION_DATE "2021-09-02" #endif /** From 43135114837b3dbe95bdf5b63ddcdec4a812813b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 3 Sep 2021 00:58:08 +0000 Subject: [PATCH 0623/2168] [cron] Bump distribution date (2021-09-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 174752711a..cdb1027194 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-02" +//#define STRING_DISTRIBUTION_DATE "2021-09-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c839ceb5bd..10b6a371a4 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 "2021-09-02" + #define STRING_DISTRIBUTION_DATE "2021-09-03" #endif /** From ff95a93ecc299dc8c811012e7e77e32427649cf8 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 3 Sep 2021 05:08:40 +0200 Subject: [PATCH 0624/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Mixing=20code=20?= =?UTF-8?q?typos=20(#22697)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 2 +- Marlin/src/module/stepper.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 00173e9ad1..04d32f9c18 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2131,7 +2131,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; - TERN_(MIXING_EXTRUDER, mixer.populate_block(block->b_color)) + TERN_(MIXING_EXTRUDER, mixer.populate_block(block->b_color)); TERN_(HAS_CUTTER, block->cutter_power = cutter.power); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 86e469827d..50d8ad4260 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2205,7 +2205,7 @@ uint32_t Stepper::block_phase_isr() { accelerate_until = current_block->accelerate_until << oversampling; decelerate_after = current_block->decelerate_after << oversampling; - TERN_(MIXING_EXTRUDER, mixer.stepper_setup(current_block->b_color)) + TERN_(MIXING_EXTRUDER, mixer.stepper_setup(current_block->b_color)); TERN_(HAS_MULTI_EXTRUDER, stepper_extruder = current_block->extruder); From e1056378f1bbba01fd846c5af2ba339739c271e3 Mon Sep 17 00:00:00 2001 From: Elliott Indiran Date: Thu, 2 Sep 2021 20:41:41 -0700 Subject: [PATCH 0625/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20PID=5FPARAMS?= =?UTF-8?q?=5FPER=5FHOTEND=20comment=20(#22694)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 418c25aef7..5a70d32671 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -595,8 +595,8 @@ // Set/get with gcode: M301 E[extruder number, 0-2] #if ENABLED(PID_PARAMS_PER_HOTEND) - // Specify between 1 and HOTENDS values per array. - // If fewer than EXTRUDER values are provided, the last element will be repeated. + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. #define DEFAULT_Kp_LIST { 22.20, 22.20 } #define DEFAULT_Ki_LIST { 1.08, 1.08 } #define DEFAULT_Kd_LIST { 114.00, 114.00 } From 18d82c1988624c48b459352fa02a352b34d2eff7 Mon Sep 17 00:00:00 2001 From: Thomas White Date: Fri, 3 Sep 2021 12:30:24 +0800 Subject: [PATCH 0626/2168] =?UTF-8?q?=E2=9C=A8=20Homing=20submenu=20option?= =?UTF-8?q?=20(#22692)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + .../extui/ftdi_eve_touch_ui/theme/bitmaps.h | 2 +- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_motion.cpp | 68 ++++++++++++++----- Marlin/src/pins/pins.h | 6 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 2 +- 9 files changed, 61 insertions(+), 25 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5a70d32671..bfc39298a2 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2159,6 +2159,7 @@ // Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. // //#define INDIVIDUAL_AXIS_HOMING_MENU +//#define INDIVIDUAL_AXIS_HOMING_SUBMENU // // SPEAKER/BUZZER diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h index c689f23905..59394b89a6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -239,7 +239,7 @@ namespace Theme { .width = 31, .height = 32, }; - + const unsigned char Light_Bulb[128] PROGMEM = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x40, diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 85bf685e31..bddddb75bf 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -70,6 +70,7 @@ namespace Language_en { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Progress Bar Test"); + PROGMEM Language_Str MSG_HOMING = _UxGT("Homing"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 3e7977bac6..948c8807b2 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -320,6 +320,36 @@ void menu_move() { END_MENU(); } +#if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + // + // "Motion" > "Homing" submenu + // + void menu_home() { + START_MENU(); + BACK_ITEM(MSG_MOTION); + + GCODES_ITEM(MSG_AUTO_HOME, G28_STR); + GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); + #if HAS_Y_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + #endif + #if HAS_Z_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #endif + #if LINEAR_AXES >= 4 + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); + #endif + #if LINEAR_AXES >= 5 + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); + #endif + #if LINEAR_AXES >= 6 + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + #endif + + END_MENU(); + } +#endif + #if ENABLED(AUTO_BED_LEVELING_UBL) void _lcd_ubl_level_bed(); #elif ENABLED(LCD_BED_LEVELING) @@ -347,23 +377,27 @@ void menu_motion() { // // Auto Home // - GCODES_ITEM(MSG_AUTO_HOME, G28_STR); - #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) - GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); - #if HAS_Y_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); - #endif - #if HAS_Z_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); - #endif - #if LINEAR_AXES >= 4 - GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); - #endif - #if LINEAR_AXES >= 5 - GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); - #endif - #if LINEAR_AXES >= 6 - GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + SUBMENU(MSG_HOMING, menu_home); + #else + GCODES_ITEM(MSG_AUTO_HOME, G28_STR); + #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) + GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); + #if HAS_Y_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + #endif + #if HAS_Z_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #endif + #if LINEAR_AXES >= 4 + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); + #endif + #if LINEAR_AXES >= 5 + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); + #endif + #if LINEAR_AXES >= 6 + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + #endif #endif #endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 064a4bb99e..af14f9ec1c 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -564,11 +564,11 @@ #elif MB(MINGDA_MPX_ARM_MINI) #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini #elif MB(ZONESTAR_ZM3E2) - #include "stm32f1/pins_ZM3E2_V1_0.h" // STM32F1 env:STM32F103RC_ZM3E2_USB env:STM32F103RC_ZM3E2_USB_maple + #include "stm32f1/pins_ZM3E2_V1_0.h" // STM32F1 env:STM32F103RC_ZM3E2_USB env:STM32F103RC_ZM3E2_USB_maple #elif MB(ZONESTAR_ZM3E4) - #include "stm32f1/pins_ZM3E4_V1_0.h" // STM32F1 env:STM32F103VC_ZM3E4_USB env:STM32F103VC_ZM3E4_USB_maple + #include "stm32f1/pins_ZM3E4_V1_0.h" // STM32F1 env:STM32F103VC_ZM3E4_USB env:STM32F103VC_ZM3E4_USB_maple #elif MB(ZONESTAR_ZM3E4V2) - #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple + #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple // // ARM Cortex-M4F diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 4db596a1bc..846a21eea5 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -326,7 +326,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 8c0ff76ae6..39920122d3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -200,7 +200,7 @@ #define DOGLCD_SCK EXP2_09_PIN #define FORCE_SOFT_SPI #define SOFTWARE_SPI - //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_180 #else diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 204cd21c02..ec1ec17d3f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -349,7 +349,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 4e0ff6f09d..d55b152a8b 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -389,7 +389,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_180 #else // !MKS_MINI_12864 From 5dbb15539502da2bbc4ece99a3f5fc123801cdbe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Sep 2021 17:26:36 -0500 Subject: [PATCH 0627/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20'ms'=20warning?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1472f5c32a..8911941ee0 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1444,7 +1444,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; UNUSED(persist); #endif - #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if BASIC_PROGRESS_BAR || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) const millis_t ms = millis(); #endif From a3557e63bf6669820d24a568030436979529f182 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sat, 4 Sep 2021 01:20:32 +0200 Subject: [PATCH 0628/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20"Homing"=20fo?= =?UTF-8?q?r=20some=20languages=20(#22706)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_an.h | 1 + Marlin/src/lcd/language/language_ca.h | 1 + Marlin/src/lcd/language/language_es.h | 1 + Marlin/src/lcd/language/language_fr.h | 1 + 4 files changed, 4 insertions(+) diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index e5fc965ed1..1bc6d75f3b 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -44,6 +44,7 @@ namespace Language_an { PROGMEM Language_Str MSG_MAIN = _UxGT("Menu prencipal"); PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inicio automatico"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Amortar motors"); + PROGMEM Language_Str MSG_HOMING = _UxGT("Orichen"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Levar a l'orichen"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Orichen X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Orichen Y"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 19ba9acab7..a554fafdfd 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -42,6 +42,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desactiva motors"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu de depuracio"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progres"); + PROGMEM Language_Str MSG_HOMING = _UxGT("Origen"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ves a l'origen"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X a origen"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y a origen"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index f08cecf1e1..1213d9e1fe 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -57,6 +57,7 @@ namespace Language_es { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Prob. barra progreso"); + PROGMEM Language_Str MSG_HOMING = _UxGT("Origen"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Llevar al origen"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origen X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origen Y"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index c0ee6b82cd..ef15d069dc 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -56,6 +56,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Arrêter moteurs"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); + PROGMEM Language_Str MSG_HOMING = _UxGT("Origine"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Origine auto"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origine X auto"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); From 88fc449c7bfef94782458c5b7ec3aeb0889f0bb5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 4 Sep 2021 00:58:22 +0000 Subject: [PATCH 0629/2168] [cron] Bump distribution date (2021-09-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index cdb1027194..3e8e7e47a2 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-03" +//#define STRING_DISTRIBUTION_DATE "2021-09-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 10b6a371a4..78683e6511 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 "2021-09-03" + #define STRING_DISTRIBUTION_DATE "2021-09-04" #endif /** From 73bc81739799cf50a70cb6dfd2045b57591f50d3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 5 Sep 2021 01:01:15 +0000 Subject: [PATCH 0630/2168] [cron] Bump distribution date (2021-09-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 3e8e7e47a2..436deb5e7a 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-04" +//#define STRING_DISTRIBUTION_DATE "2021-09-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 78683e6511..3f5497b719 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 "2021-09-04" + #define STRING_DISTRIBUTION_DATE "2021-09-05" #endif /** From 76fb131f14dfc4108c4f6491d84827b8813d3973 Mon Sep 17 00:00:00 2001 From: Justin Nesselrotte Date: Sun, 5 Sep 2021 14:21:45 -0600 Subject: [PATCH 0631/2168] =?UTF-8?q?=E2=9C=A8=20Index=20Pick-and-Place=20?= =?UTF-8?q?board=20Rev.3=20(#22647)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Gonçalo Pereira Co-authored-by: Scott Lahteine --- .github/workflows/test-builds.yml | 1 + Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f4/pins_INDEX_REV03.h | 157 ++++++++++++++++++ .../boards/marlin_index_mobo_rev03.json | 51 ++++++ buildroot/tests/Index_Mobo_Rev03 | 13 ++ ini/stm32f4.ini | 12 ++ 7 files changed, 237 insertions(+) create mode 100644 Marlin/src/pins/stm32f4/pins_INDEX_REV03.h create mode 100644 buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json create mode 100755 buildroot/tests/Index_Mobo_Rev03 diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index c6afaffebf..f5ce466d90 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -97,6 +97,7 @@ jobs: - REMRAM_V1 - BTT_SKR_SE_BX - chitu_f103 + - Index_Mobo_Rev03 # Put lengthy tests last diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index d37fa0cdbc..be78c96b22 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -395,6 +395,7 @@ #define BOARD_ANET_ET4P 4230 // ANET ET4P V1.x (STM32F407VGT6) #define BOARD_FYSETC_CHEETAH_V20 4231 // FYSETC Cheetah V2.0 #define BOARD_TH3D_EZBOARD_LITE_V2 4232 // TH3D EZBoard Lite v2.0 +#define BOARD_INDEX_REV03 4233 // Index PnP Controller REV03 (STM32F407VET6/VGT6) // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index af14f9ec1c..8c41a8a672 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -645,6 +645,8 @@ #include "stm32f4/pins_MKS_MONSTER8.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc #elif MB(TH3D_EZBOARD_LITE_V2) #include "stm32f4/pins_TH3D_EZBOARD_LITE_V2.h" // STM32F4 env:TH3D_EZBoard_Lite_V2 +#elif MB(INDEX_REV03) + #include "stm32f4/pins_INDEX_REV03.h" // STM32F4 env:Index_Mobo_Rev03 // // ARM Cortex M7 diff --git a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h new file mode 100644 index 0000000000..8761ca955a --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h @@ -0,0 +1,157 @@ +/** + * 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 + +/** + * STM32F407VET6 on Index PnP Mobo Rev03 + * Website - https://indexmachines.io/ + */ + +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#define BOARD_INFO_NAME "Index Mobo Rev03" +#define DEFAULT_MACHINE_NAME "Index Pick and Place" + +/** + * By default, the extra stepper motor configuration is: + * I = Left Head + * J = Right Head + * K = Auxiliary (Conveyor belt) + */ + +#define SRAM_EEPROM_EMULATION +#define MARLIN_EEPROM_SIZE 0x2000 // 8KB + +// +// Servos +// +#define SERVO0_PIN PB10 +#define SERVO1_PIN PB11 + +// +// Limit Switches +// +#define X_STOP_PIN PC6 +#define Y_STOP_PIN PD15 +#define Z_STOP_PIN PD14 + +// None of these require limit switches by default, so we leave these commented +// here for your reference. +// #define I_MIN_PIN PA8 +// #define I_MAX_PIN PA8 +// #define J_MIN_PIN PD13 +// #define J_MAX_PIN PD13 +// #define K_MIN_PIN PC9 +// #define K_MAX_PIN PC9 + +// +// Steppers +// +#define X_STEP_PIN PB15 +#define X_DIR_PIN PB14 +#define X_ENABLE_PIN PD9 +#define X_SERIAL_TX_PIN PD8 +#define X_SERIAL_RX_PIN PD8 + +#define Y_STEP_PIN PE15 +#define Y_DIR_PIN PE14 +#define Y_ENABLE_PIN PB13 +#define Y_SERIAL_TX_PIN PB12 +#define Y_SERIAL_RX_PIN PB12 + +#define Z_STEP_PIN PE7 +#define Z_DIR_PIN PB1 +#define Z_ENABLE_PIN PE9 +#define Z_SERIAL_TX_PIN PE8 +#define Z_SERIAL_RX_PIN PE8 + +#define I_STEP_PIN PC4 +#define I_DIR_PIN PA4 +#define I_ENABLE_PIN PB0 +#define I_SERIAL_TX_PIN PC5 +#define I_SERIAL_RX_PIN PC5 + +#define J_STEP_PIN PE11 +#define J_DIR_PIN PE10 +#define J_ENABLE_PIN PE13 +#define J_SERIAL_TX_PIN PE12 +#define J_SERIAL_RX_PIN PE12 +#define K_SERIAL_TX_PIN PA2 +#define K_SERIAL_RX_PIN PA2 + +#define K_STEP_PIN PD6 +#define K_DIR_PIN PD7 +#define K_ENABLE_PIN PA3 + +// Reduce baud rate to improve software serial reliability +#define TMC_BAUD_RATE 19200 + +// Not required for this board. Fails to compile otherwise. +// PD0 is not connected on this board. +#define TEMP_0_PIN PD0 + +// General use mosfets, useful for things like pumps and solenoids +#define FAN_PIN PE2 +#define FAN1_PIN PE3 +#define FAN2_PIN PE4 +#define FAN3_PIN PE5 + +// Neopixel Rings +#define NEOPIXEL_PIN PC7 +#define NEOPIXEL2_PIN PC8 + +// SPI +#define MISO_PIN PB4 +#define MOSI_PIN PB5 +#define SCK_PIN PB3 + +// I2C +#define I2C_SDA_PIN PB7 +#define I2C_SCL_PIN PB6 + +/** + * The index mobo rev03 has 3 aux ports. We define them here so they may be used + * in other places and to make sure someone doesn't have to go look up the pinout + * in the board files. Each 12 pin aux port has this pinout: + * + * VDC 1 2 GND + * 3.3V 3 4 SCL (I2C_SCL_PIN) + * PWM1 5 6 SDA (I2C_SDA_PIN) + * PWM2 7 8 CIPO (MISO_PIN) + * A1 9 10 COPI (MOSI_PIN) + * A2 11 12 SCK (SCK_PIN) + */ +#define INDEX_AUX1_PWM1 PA15 +#define INDEX_AUX1_PWM2 PA5 +#define INDEX_AUX1_A1 PC0 +#define INDEX_AUX1_A2 PC1 + +#define INDEX_AUX2_PWM1 PA6 +#define INDEX_AUX2_PWM2 PA7 +#define INDEX_AUX2_A1 PC2 +#define INDEX_AUX2_A2 PC3 + +#define INDEX_AUX3_PWM1 PB8 +#define INDEX_AUX3_PWM2 PB9 +#define INDEX_AUX3_A1 PA0 +#define INDEX_AUX3_A2 PA1 diff --git a/buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json b/buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json new file mode 100644 index 0000000000..c65f1dd703 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_index_mobo_rev03.json @@ -0,0 +1,51 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F407xx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ], + [ + "0x0483", + "0xdf11" + ] + ], + "mcu": "stm32f407vet6", + "variant": "MARLIN_F407VE" + }, + "debug": { + "jlink_device": "STM32F407VE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F407VE (192k RAM. 512k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink", + "blackmagic" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html", + "vendor": "Generic" +} diff --git a/buildroot/tests/Index_Mobo_Rev03 b/buildroot/tests/Index_Mobo_Rev03 new file mode 100755 index 0000000000..501386489d --- /dev/null +++ b/buildroot/tests/Index_Mobo_Rev03 @@ -0,0 +1,13 @@ +#!/usr/bin/env bash +# +# Build tests for Index_Mobo_Rev03 +# + +# exit on first failure +set -e + +use_example_configs Index/REV_03 +exec_test $1 $2 "Index REV03 Pick and Place" "$3" + +# cleanup +restore_configs diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 6870345121..84256d3be9 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -99,6 +99,18 @@ board = marlin_blackSTM32F407VET6 build_flags = ${stm32_variant.build_flags} -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS +# +# STM32F407VET6 Index Mobo Rev 03 +# +[env:Index_Mobo_Rev03] +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_index_mobo_rev03 +build_flags = ${stm32_variant.build_flags} + -DARDUINO_BLACK_F407VE + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS +extra_scripts = ${stm32_variant.extra_scripts} + # # Anet ET4-MB_V1.x/ET4P-MB_V1.x (STM32F407VGT6 ARM Cortex-M4) # For use with with davidtgbe's OpenBLT bootloader https://github.com/davidtgbe/openblt/releases From 51c66881c26e1db1d4eff925f0f0157ab65f83d0 Mon Sep 17 00:00:00 2001 From: Dan Date: Sun, 5 Sep 2021 13:32:09 -0700 Subject: [PATCH 0632/2168] =?UTF-8?q?=E2=9C=A8=20Protoneer=20CNC-Shield=20?= =?UTF-8?q?3.00=20(#22715)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 1 + .../pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h | 77 +++++++++++++++++++ Marlin/src/pins/pins.h | 2 + 3 files changed, 80 insertions(+) create mode 100644 Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index be78c96b22..dd181baed9 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -161,6 +161,7 @@ #define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) #define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) #define BOARD_GT2560_V4_A20 1328 // Geeetech GT2560 Rev B for A20(M/T/D) +#define BOARD_PROTONEER_CNC_SHIELD_V3 1329 // Mega controller & Protoneer CNC Shield V3.00 // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h new file mode 100644 index 0000000000..31bab5b2dc --- /dev/null +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Protoneer v3.00 pin assignments + * + * This CNC shield has an UNO pinout and fits all Arduino-compatibles. + * + * Referenced docs: + * - https://blog.protoneer.co.nz/arduino-cnc-shield-v3-00-assembly-guide/ + * - https://blog.protoneer.co.nz/arduino-cnc-shield/ + */ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Protoneer CNC Shield v3.00" + +// +// Limit Switches +// +#define X_STOP_PIN 9 +#define Y_STOP_PIN 10 +#define Z_STOP_PIN 11 + +// +// Steppers +// +#define X_STEP_PIN 2 +#define X_DIR_PIN 5 +#define X_ENABLE_PIN 8 // Shared enable pin + +#define Y_STEP_PIN 3 +#define Y_DIR_PIN 6 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 7 +#define Z_ENABLE_PIN X_ENABLE_PIN + +// Designated with letter "A" on BOARD +#define E0_STEP_PIN 12 +#define E0_DIR_PIN 13 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Temperature sensors - These could be any analog output not hidden by board +// +#define TEMP_0_PIN 8 // Analog Input +//#define TEMP_1_PIN 9 // Analog Input +//#define TEMP_BED_PIN 10 // Analog Input + +// +// Heaters / Fans - These could be any digital input not hidden by board +// +//#define HEATER_0_PIN 22 // EXTRUDER 1 +//#define HEATER_1_PIN 23 // EXTRUDER 2 +//#define HEATER_BED_PIN 24 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 8c41a8a672..7a0d932c61 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -269,6 +269,8 @@ #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 #elif MB(MALYAN_M180) #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 +#elif MB(PROTONEER_CNC_SHIELD_V3) + #include "mega/pins_PROTONEER_CNC_SHIELD_V3.h"// ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 From c881fab1280f338e32015e1556890d647ee967fb Mon Sep 17 00:00:00 2001 From: dotdash32 Date: Sun, 5 Sep 2021 17:21:25 -0700 Subject: [PATCH 0633/2168] =?UTF-8?q?=F0=9F=8E=A8=20Use=20largest=20defaul?= =?UTF-8?q?t=20ST9720=20delays=20(#22713)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/AVR/HAL.h | 12 ++--- Marlin/src/HAL/LINUX/HAL.h | 6 +-- Marlin/src/HAL/LPC1768/HAL.h | 6 +-- Marlin/src/HAL/NATIVE_SIM/HAL.h | 6 +-- Marlin/src/HAL/STM32/HAL.h | 6 +-- Marlin/src/HAL/STM32F1/HAL.h | 6 +-- Marlin/src/HAL/TEENSY31_32/HAL.h | 6 +-- Marlin/src/HAL/TEENSY35_36/HAL.h | 6 +-- Marlin/src/HAL/TEENSY40_41/HAL.h | 6 +-- Marlin/src/inc/Conditionals_LCD.h | 12 ++--- .../dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp | 50 +++++++++++++++++++ Marlin/src/pins/mega/pins_SILVER_GATE.h | 6 +-- Marlin/src/pins/pins_postprocess.h | 30 +---------- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 6 +-- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 6 +-- Marlin/src/pins/rambo/pins_MINIRAMBO.h | 6 +-- Marlin/src/pins/rambo/pins_RAMBO.h | 6 +-- Marlin/src/pins/ramps/pins_3DRAG.h | 6 +-- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 6 +-- Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 6 +-- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 6 +-- Marlin/src/pins/sanguino/pins_ANET_10.h | 12 ++--- Marlin/src/pins/sanguino/pins_MELZI.h | 6 +-- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 6 +-- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 6 +-- Marlin/src/pins/sanguino/pins_MELZI_V2.h | 6 +-- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 6 +-- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 6 +-- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 6 +-- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 6 +-- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 6 +-- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 6 +-- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 6 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 6 +-- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 6 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 6 +-- .../src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h | 6 +-- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 6 +-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 6 +-- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 6 +-- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 6 +-- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 6 +-- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 6 +-- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 11 ++-- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 11 ++-- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 11 ++-- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 11 ++-- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 11 ++-- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 6 +-- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 11 ++-- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 6 +-- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 6 +-- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 6 +-- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 6 +-- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 6 +-- .../pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h | 9 ++-- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 6 +-- Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h | 6 +-- .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 6 +-- 59 files changed, 231 insertions(+), 242 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index dc0a4f2074..a22daf9b5c 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -43,13 +43,13 @@ // Default graphical display delays // #if F_CPU >= 20000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(150) - #define CPU_ST7920_DELAY_2 DELAY_NS( 0) - #define CPU_ST7920_DELAY_3 DELAY_NS(150) + #define CPU_ST7920_DELAY_1 150 + #define CPU_ST7920_DELAY_2 0 + #define CPU_ST7920_DELAY_3 150 #elif F_CPU == 16000000 - #define CPU_ST7920_DELAY_1 DELAY_NS(125) - #define CPU_ST7920_DELAY_2 DELAY_NS( 0) - #define CPU_ST7920_DELAY_3 DELAY_NS(188) + #define CPU_ST7920_DELAY_1 125 + #define CPU_ST7920_DELAY_2 0 + #define CPU_ST7920_DELAY_3 188 #endif #ifndef pgm_read_ptr diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 07ab85a9a0..79639f4993 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -63,9 +63,9 @@ uint8_t _getc(); extern MSerialT usb_serial; #define MYSERIAL1 usb_serial -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 // // Interrupts diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f0a1185ff2..fc2fc57378 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -50,9 +50,9 @@ extern "C" volatile uint32_t _millis; // // Default graphical display delays // -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 400fafd711..235c24808c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -99,9 +99,9 @@ extern MSerialT serial_stream_3; #endif -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 // // Interrupts diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index d73f8b2d54..7a04c9ceeb 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -40,9 +40,9 @@ // // Default graphical display delays // -#define CPU_ST7920_DELAY_1 DELAY_NS(300) -#define CPU_ST7920_DELAY_2 DELAY_NS( 40) -#define CPU_ST7920_DELAY_3 DELAY_NS(340) +#define CPU_ST7920_DELAY_1 300 +#define CPU_ST7920_DELAY_2 40 +#define CPU_ST7920_DELAY_3 340 // // Serial Ports diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 7efb761c28..1d30f43c48 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -54,9 +54,9 @@ // // Default graphical display delays // -#define CPU_ST7920_DELAY_1 DELAY_NS(300) -#define CPU_ST7920_DELAY_2 DELAY_NS( 40) -#define CPU_ST7920_DELAY_3 DELAY_NS(340) +#define CPU_ST7920_DELAY_1 300 +#define CPU_ST7920_DELAY_2 40 +#define CPU_ST7920_DELAY_3 340 #ifndef STM32_FLASH_SIZE #if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE) diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index d4b3c0a772..aa195845fb 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,9 +36,9 @@ #include -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 //#undef MOTHERBOARD //#define MOTHERBOARD BOARD_TEENSY31_32 diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 0b82a569f9..0093294a2a 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,9 +37,9 @@ #include #include -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 // ------------------------ // Defines diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 14f14bf446..ea51f15ba1 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,9 +41,9 @@ #include "../../feature/ethernet.h" #endif -#define CPU_ST7920_DELAY_1 DELAY_NS(600) -#define CPU_ST7920_DELAY_2 DELAY_NS(750) -#define CPU_ST7920_DELAY_3 DELAY_NS(750) +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 // ------------------------ // Defines diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 13af3c25f5..b6f76564f9 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -237,16 +237,16 @@ #elif ENABLED(CR10_STOCKDISPLAY) #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 DELAY_NS(125) - #define LCD_ST7920_DELAY_2 DELAY_NS(125) - #define LCD_ST7920_DELAY_3 DELAY_NS(125) + #define LCD_ST7920_DELAY_1 125 + #define LCD_ST7920_DELAY_2 125 + #define LCD_ST7920_DELAY_3 125 #elif ENABLED(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 DELAY_NS(150) - #define LCD_ST7920_DELAY_2 DELAY_NS(150) - #define LCD_ST7920_DELAY_3 DELAY_NS(150) + #define LCD_ST7920_DELAY_1 150 + #define LCD_ST7920_DELAY_2 150 + #define LCD_ST7920_DELAY_3 150 #elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp index 20c8cec0cf..9367ed75a9 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -36,11 +36,61 @@ // Optimize this code with -O3 #pragma GCC optimize (3) +#ifndef ST7920_DELAY_1 + #ifndef LCD_ST7920_DELAY_1 + #define LCD_ST7920_DELAY_1 0 + #endif + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 0 + #endif + #ifndef CPU_ST7920_DELAY_1 + #define CPU_ST7920_DELAY_1 0 + #endif + #if LCD_ST7920_DELAY_1 || BOARD_ST7920_DELAY_1 || CPU_ST7920_DELAY_1 + #define ST7920_DELAY_1 DELAY_NS(_MAX(LCD_ST7920_DELAY_1, BOARD_ST7920_DELAY_1, CPU_ST7920_DELAY_1)) + #else + #define ST7920_DELAY_1 + #endif +#endif +#ifndef ST7920_DELAY_2 + #ifndef LCD_ST7920_DELAY_2 + #define LCD_ST7920_DELAY_2 0 + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 0 + #endif + #ifndef CPU_ST7920_DELAY_2 + #define CPU_ST7920_DELAY_2 0 + #endif + #if LCD_ST7920_DELAY_2 || BOARD_ST7920_DELAY_2 || CPU_ST7920_DELAY_2 + #define ST7920_DELAY_2 DELAY_NS(_MAX(LCD_ST7920_DELAY_2, BOARD_ST7920_DELAY_2, CPU_ST7920_DELAY_2)) + #else + #define ST7920_DELAY_2 + #endif +#endif +#ifndef ST7920_DELAY_3 + #ifndef LCD_ST7920_DELAY_3 + #define LCD_ST7920_DELAY_3 0 + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 0 + #endif + #ifndef CPU_ST7920_DELAY_3 + #define CPU_ST7920_DELAY_3 0 + #endif + #if LCD_ST7920_DELAY_3 || BOARD_ST7920_DELAY_3 || CPU_ST7920_DELAY_3 + #define ST7920_DELAY_3 DELAY_NS(_MAX(LCD_ST7920_DELAY_3, BOARD_ST7920_DELAY_3, CPU_ST7920_DELAY_3)) + #else + #define ST7920_DELAY_3 + #endif +#endif + #ifdef ARDUINO_ARCH_STM32F1 #define ST7920_DAT(V) !!((V) & 0x80) #else #define ST7920_DAT(V) ((V) & 0x80) #endif + #define ST7920_SND_BIT do{ \ WRITE(ST7920_CLK_PIN, LOW); ST7920_DELAY_1; \ WRITE(ST7920_DAT_PIN, ST7920_DAT(val)); ST7920_DELAY_2; \ diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 0828b32aa9..7b4f53a764 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -86,9 +86,9 @@ #define KILL_PIN 21 #define HOME_PIN 28 #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 0 #endif #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index aa2bc07908..6b5c695e85 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -1221,35 +1221,7 @@ // // Default DOGLCD SPI delays // -#if ENABLED(U8GLIB_ST7920) - #ifndef ST7920_DELAY_1 - #ifdef LCD_ST7920_DELAY_1 - #define ST7920_DELAY_1 LCD_ST7920_DELAY_1 - #elif defined(BOARD_ST7920_DELAY_1) - #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 - #elif defined(CPU_ST7920_DELAY_1) - #define ST7920_DELAY_1 CPU_ST7920_DELAY_1 - #endif - #endif - #ifndef ST7920_DELAY_2 - #ifdef LCD_ST7920_DELAY_2 - #define ST7920_DELAY_2 LCD_ST7920_DELAY_2 - #elif defined(BOARD_ST7920_DELAY_2) - #define ST7920_DELAY_2 BOARD_ST7920_DELAY_2 - #elif defined(CPU_ST7920_DELAY_2) - #define ST7920_DELAY_2 CPU_ST7920_DELAY_2 - #endif - #endif - #ifndef ST7920_DELAY_3 - #ifdef LCD_ST7920_DELAY_3 - #define ST7920_DELAY_3 LCD_ST7920_DELAY_3 - #elif defined(BOARD_ST7920_DELAY_3) - #define ST7920_DELAY_3 BOARD_ST7920_DELAY_3 - #elif defined(CPU_ST7920_DELAY_3) - #define ST7920_DELAY_3 CPU_ST7920_DELAY_3 - #endif - #endif -#else +#if DISABLED(U8GLIB_ST7920) #undef ST7920_DELAY_1 #undef ST7920_DELAY_2 #undef ST7920_DELAY_3 diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index dbb34f6585..25decbf035 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -206,9 +206,9 @@ #endif // HAS_WIRED_LCD #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 0 #endif #undef MK3_FAN_PINS diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 5d8ffc07aa..48c68d55f9 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -202,7 +202,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 0 #endif diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 6257550697..c496878908 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -194,7 +194,7 @@ #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 0 #endif diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index a77cb3d93f..8153103a38 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -271,7 +271,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(0) - #define BOARD_ST7920_DELAY_3 DELAY_NS(0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 0 + #define BOARD_ST7920_DELAY_3 0 #endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 3f38ecb211..316323ef9c 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -109,9 +109,9 @@ #endif // IS_ULTRA_LCD && IS_NEWPANEL #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 188 + #define BOARD_ST7920_DELAY_3 0 #endif /** diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 5b3ed4c6a5..14f54cdcf3 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -126,7 +126,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_3 DELAY_NS(189) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 0 + #define BOARD_ST7920_DELAY_3 189 #endif diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index 4f25110ca2..4bebd6ded6 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -41,9 +41,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS(250) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 250 #endif // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 0398d36f93..94c4551fc2 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -200,7 +200,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(200) - #define BOARD_ST7920_DELAY_2 DELAY_NS(200) - #define BOARD_ST7920_DELAY_3 DELAY_NS(200) + #define BOARD_ST7920_DELAY_1 200 + #define BOARD_ST7920_DELAY_2 200 + #define BOARD_ST7920_DELAY_3 200 #endif diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index e54209ed6a..bd69e167dc 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -195,9 +195,9 @@ #define BTN_EN1 28 #define BTN_EN2 10 #define BTN_ENC 17 - #define BOARD_ST7920_DELAY_1 DELAY_NS(250) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS(250) + #define BOARD_ST7920_DELAY_1 250 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 250 #else #define SERVO0_PIN 29 // free for BLTouch/3D-Touch #define BEEPER_PIN 17 @@ -207,9 +207,9 @@ #define BTN_EN1 11 #define BTN_EN2 10 #define BTN_ENC 16 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(63) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 63 + #define BOARD_ST7920_DELAY_3 125 #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index 8f2729f8f0..31583fd109 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -34,13 +34,13 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(188) + #define BOARD_ST7920_DELAY_2 188 #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_3 0 #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 81ccf5977e..3c6dd901c0 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -37,9 +37,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif #include "pins_MELZI.h" diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index e88a38561d..8abed5c30c 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -29,9 +29,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 0 #endif #include "pins_MELZI.h" diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index c1fb7fb6f7..badf53a641 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -26,9 +26,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 0) - #define BOARD_ST7920_DELAY_2 DELAY_NS(400) - #define BOARD_ST7920_DELAY_3 DELAY_NS( 0) + #define BOARD_ST7920_DELAY_1 0 + #define BOARD_ST7920_DELAY_2 400 + #define BOARD_ST7920_DELAY_3 0 #endif #include "pins_MELZI.h" diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 6aa3372b3f..650357ee9e 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -203,9 +203,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 2ce1d49bb8..77eb6aaf14 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -156,9 +156,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 7d0e15f57a..3f02d7082f 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -180,9 +180,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 797e13fd07..b3da8d884e 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -159,9 +159,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 64b1c6c040..3650ffde5c 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -167,9 +167,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 992fc36f92..56dda2b143 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -164,9 +164,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index d33ce461fe..c9a20fd66e 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -169,9 +169,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 846a21eea5..c5080b5227 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -342,9 +342,9 @@ #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 39920122d3..489da08393 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -223,13 +223,13 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #define BOARD_ST7920_DELAY_2 125 #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_3 125 #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 6373d70e38..6388e1723c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -114,9 +114,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index 73fefddf8f..416a061412 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -138,9 +138,9 @@ #endif // !MKS_MINI_12864 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index ec1ec17d3f..d19343386e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -366,9 +366,9 @@ #endif #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 8f03a3678f..fdee796692 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -301,9 +301,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(125) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 #endif #define HAS_SPI_FLASH 1 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index 0d413d3651..d4f77d5f84 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -201,9 +201,9 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_06_PIN #define BTN_ENC EXP1_04_PIN - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(200) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 200 + #define BOARD_ST7920_DELAY_3 125 #elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index a7a1dacd5b..daacd0c124 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -333,9 +333,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) - #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 250 + #define BOARD_ST7920_DELAY_3 125 #endif // Remap SERVO0 PIN for BLTouch diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index ba6bf8aa7b..e0b2f6adfc 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -306,9 +306,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(200) // Tclk_fall <200ns - #define BOARD_ST7920_DELAY_2 DELAY_NS(250) // Tdata_width >200ns - #define BOARD_ST7920_DELAY_3 DELAY_NS(200) // Tclk_rise <200ns + #define BOARD_ST7920_DELAY_1 200 // Tclk_fall <200ns + #define BOARD_ST7920_DELAY_2 250 // Tdata_width >200ns + #define BOARD_ST7920_DELAY_3 200 // Tclk_rise <200ns #endif // Remap SERVO0 PIN for BLTouch diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index bb283201e4..86851a7840 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -286,9 +286,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 8d828f9e27..eb0c3bdbb9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -207,11 +207,6 @@ #define LCD_PINS_ENABLE PE11 #define LCD_PINS_D4 PE10 - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." @@ -283,9 +278,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 5a1efc252b..68948f7de9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -425,11 +425,6 @@ #define LCD_PINS_ENABLE EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #elif ENABLED(MKS_MINI_12864) #define DOGLCD_A0 EXP1_04_PIN #define DOGLCD_CS EXP1_05_PIN @@ -489,9 +484,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index d133a45718..ab0a7dd962 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -433,11 +433,6 @@ #define LCD_PINS_ENABLE EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #else #define LCD_PINS_RS EXP1_07_PIN @@ -484,9 +479,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS(120) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 80) - #define BOARD_ST7920_DELAY_3 DELAY_NS(580) + #define BOARD_ST7920_DELAY_1 120 + #define BOARD_ST7920_DELAY_2 80 + #define BOARD_ST7920_DELAY_3 580 #endif #if HAS_SPI_TFT diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 8690f41ec9..72154be2ee 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -446,11 +446,6 @@ #define LCD_PINS_ENABLE EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #elif ENABLED(MKS_MINI_12864) #define DOGLCD_A0 EXP1_04_PIN @@ -506,13 +501,13 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #define BOARD_ST7920_DELAY_1 125 #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS( 90) + #define BOARD_ST7920_DELAY_2 90 #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 600 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 30163dc61d..a05f4fb5b9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -430,11 +430,6 @@ #define LCD_PINS_ENABLE EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #elif ENABLED(MKS_MINI_12864) #define DOGLCD_A0 EXP1_04_PIN @@ -490,13 +485,13 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(120) + #define BOARD_ST7920_DELAY_1 120 #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS( 80) + #define BOARD_ST7920_DELAY_2 80 #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(580) + #define BOARD_ST7920_DELAY_3 580 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index cbed56d202..8a9ac56e9e 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -306,7 +306,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index c922f13c60..3fe7449330 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -192,11 +192,6 @@ #define LCD_PINS_ENABLE EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #elif ENABLED(MKS_MINI_12864) #define DOGLCD_A0 EXP1_04_PIN @@ -251,9 +246,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif #if ENABLED(TOUCH_UI_FTDI_EVE) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index da83ade4e0..6b6f644159 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -315,9 +315,9 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 640 #endif #ifndef RGB_LED_R_PIN diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 3b6a3f74f6..8fa211dc95 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -369,9 +369,9 @@ #define LCD_PINS_D7 EXP1_03_PIN #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index d55b152a8b..e78807e1af 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -400,9 +400,9 @@ #define LCD_PINS_D7 EXP1_03_PIN #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index c28da71347..46dec71c11 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -371,9 +371,9 @@ #define LCD_PINS_D7 EXP1_03_PIN #endif - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif // !MKS_MINI_12864 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index af0f5fa17c..4c0e3515f6 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -173,7 +173,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(640) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 640 #endif diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h index c04341a243..bff3f5b6ee 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_LITE_V2.h @@ -225,12 +225,9 @@ #define LCD_PINS_D4 EXP1_05_PIN //#define KILL_PIN -1 - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_1 DELAY_NS(600) - #define BOARD_ST7920_DELAY_2 DELAY_NS(750) - #define BOARD_ST7920_DELAY_3 DELAY_NS(750) + #define BOARD_ST7920_DELAY_1 600 + #define BOARD_ST7920_DELAY_2 750 + #define BOARD_ST7920_DELAY_3 750 #elif ENABLED(MKS_MINI_12864) /** ______ diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 280f98eae8..f936df2c2c 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -184,7 +184,7 @@ // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) - #define BOARD_ST7920_DELAY_1 DELAY_NS( 96) - #define BOARD_ST7920_DELAY_2 DELAY_NS( 48) - #define BOARD_ST7920_DELAY_3 DELAY_NS(715) + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 715 #endif diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index 217664e5bc..c41b5ab1de 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -191,7 +191,7 @@ #define BTN_EN1 PF13 // BTN_EN1 #define BTN_EN2 PE9 // BTN_EN2 - #define BOARD_ST7920_DELAY_1 DELAY_NS(125) - #define BOARD_ST7920_DELAY_2 DELAY_NS(63) - #define BOARD_ST7920_DELAY_3 DELAY_NS(780) + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 63 + #define BOARD_ST7920_DELAY_3 780 #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index 539a3bb8f3..76b98ccbeb 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -245,9 +245,9 @@ //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 // Alter timing for graphical display - #define BOARD_ST7920_DELAY_1 DELAY_NS(313) - #define BOARD_ST7920_DELAY_2 DELAY_NS(313) - #define BOARD_ST7920_DELAY_3 DELAY_NS(313) + #define BOARD_ST7920_DELAY_1 313 + #define BOARD_ST7920_DELAY_2 313 + #define BOARD_ST7920_DELAY_3 313 #else From 6098150a857d15cd735f8c2309ca4b2d3f624974 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 6 Sep 2021 01:05:05 +0000 Subject: [PATCH 0634/2168] [cron] Bump distribution date (2021-09-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 436deb5e7a..45d4db7264 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-05" +//#define STRING_DISTRIBUTION_DATE "2021-09-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3f5497b719..2dbbd144e7 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 "2021-09-05" + #define STRING_DISTRIBUTION_DATE "2021-09-06" #endif /** From b0a91073b25f53e9e377f0ef4e01c9dd6fefd021 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 5 Sep 2021 20:32:29 -0500 Subject: [PATCH 0635/2168] =?UTF-8?q?=F0=9F=94=A7=20Sanity=20checks=20for?= =?UTF-8?q?=20Ender=203=20V2?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 25 +++++++++++++++++++++---- Marlin/src/lcd/e3v2/creality/dwin.cpp | 2 +- 2 files changed, 22 insertions(+), 5 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index d6f911cd4c..01fdaa3451 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1750,8 +1750,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * LCD_BED_LEVELING requirements */ #if ENABLED(LCD_BED_LEVELING) - #if !HAS_LCD_MENU - #error "LCD_BED_LEVELING requires a programmable LCD controller." + #if NONE(HAS_LCD_MENU, DWIN_CREALITY_LCD) + #error "LCD_BED_LEVELING is not supported by the selected LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." #elif ENABLED(MESH_EDIT_MENU) && !HAS_MESH @@ -2656,8 +2656,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ - + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY, DWIN_CREALITY_LCD) \ - + COUNT_ENABLED(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ @@ -2750,6 +2750,23 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." #endif +/** + * Ender 3 V2 controller has some limitations + */ +#if ENABLED(DWIN_CREALITY_LCD) + #if DISABLED(SDSUPPORT) + #error "DWIN_CREALITY_LCD requires SDSUPPORT to be enabled." + #elif ENABLED(PID_EDIT_MENU) + #error "DWIN_CREALITY_LCD does not support PID_EDIT_MENU." + #elif ENABLED(PID_AUTOTUNE_MENU) + #error "DWIN_CREALITY_LCD does not support PID_AUTOTUNE_MENU." + #elif ENABLED(LEVEL_BED_CORNERS) + #error "DWIN_CREALITY_LCD does not support LEVEL_BED_CORNERS." + #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." + #endif +#endif + /** * Some boards forbid the use of -1 Native USB */ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 5ddc231817..a6218609df 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -30,7 +30,7 @@ #include "dwin.h" -#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) +#if ENABLED(LCD_BED_LEVELING) && DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define HAS_ONESTEP_LEVELING 1 #endif From 521fda0235bc07c5e07889373a2a22c57fadf07f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 27 Aug 2021 16:12:08 -0500 Subject: [PATCH 0636/2168] =?UTF-8?q?=F0=9F=8E=A8=20MarlinUI=20for=20E3V2?= =?UTF-8?q?=20tweaks?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 10 ++-------- Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h | 1 - Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp | 10 +++++----- Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 20 +++++++++---------- .../src/lcd/e3v2/marlinui/lcdprint_dwin.cpp | 16 +++++++-------- 5 files changed, 24 insertions(+), 33 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index a6218609df..d14d6f10dd 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -579,14 +579,8 @@ void DWIN_Draw_Label(const uint8_t row, const __FlashStringHelper *title) { } void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - if (value < 0) { - DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, F("-")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); - } - else { - DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, F(" ")); - DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); - } + DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, value < 0 ? F("-") : F(" ")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value < 0 ? -value : value); } void Draw_Edit_Integer3(const uint8_t row, const uint16_t value, const bool active=false) { diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h index 09d7b5ddd2..4d8e670e1c 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h @@ -67,7 +67,6 @@ #define DWIN_FONT_MENU font10x20 #define DWIN_FONT_STAT font14x28 -#define DWIN_FONT_HEAD font10x20 #define DWIN_FONT_ALERT font14x28 // Color diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp index c7b37319c4..89e001b29c 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -47,7 +47,7 @@ uint8_t read_byte(uint8_t *byte) { return *byte; } * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) */ -void DWIN_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { +void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/*=nullptr*/) { wchar_t wchar; while (*string) { @@ -127,7 +127,7 @@ void DWIN_String::add(wchar_t character) { if (str[1]) add_character(str[1]); } -void DWIN_String::add_character(uint8_t character) { +void DWIN_String::add_character(const uint8_t character) { if (len < MAX_STRING_LENGTH) { data[len] = character; len++; @@ -135,7 +135,7 @@ void DWIN_String::add_character(uint8_t character) { } } -void DWIN_String::rtrim(uint8_t character) { +void DWIN_String::rtrim(const uint8_t character) { while (len) { if (data[len - 1] == 0x20 || data[len - 1] == character) { len--; @@ -147,7 +147,7 @@ void DWIN_String::rtrim(uint8_t character) { } } -void DWIN_String::ltrim(uint8_t character) { +void DWIN_String::ltrim(const uint8_t character) { uint16_t i, j; for (i = 0; (i < len) && (data[i] == 0x20 || data[i] == character); i++) { //span -= glyph(data[i])->DWidth; @@ -158,7 +158,7 @@ void DWIN_String::ltrim(uint8_t character) { eol(); } -void DWIN_String::trim(uint8_t character) { +void DWIN_String::trim(const uint8_t character) { rtrim(character); ltrim(character); } diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index d78d774095..08566407b7 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -46,7 +46,7 @@ class DWIN_String { static uint16_t span; // in pixels static uint8_t len; // in characters - static void add_character(uint8_t character); + static void add_character(const uint8_t character); static void eol() { data[len] = 0x00; } public: @@ -62,7 +62,7 @@ class DWIN_String { //static void add(uint8_t character) { add_character(character); eol(); } static void add(wchar_t character); static void add(uint8_t *string, uint8_t max_len=MAX_STRING_LENGTH); - static void add(uint8_t *string, int8_t index, uint8_t *itemString=nullptr); + static void add(uint8_t *string, const int8_t index, uint8_t *itemString=nullptr); static void set(uint8_t *string) { set(); add(string); } static void set(wchar_t character) { set(); add(character); } static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); } @@ -71,20 +71,20 @@ class DWIN_String { static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } static inline void add(const char *string) { add((uint8_t *)string); } - static void trim(uint8_t character=0x20); - static void rtrim(uint8_t character=0x20); - static void ltrim(uint8_t character=0x20); + static void trim(const uint8_t character=0x20); + static void rtrim(const uint8_t character=0x20); + static void ltrim(const uint8_t character=0x20); static void truncate(uint8_t maxlen) { if (len > maxlen) { len = maxlen; eol(); } } - static uint8_t length() { return len; } - static uint16_t width() { return span; } - static uint8_t *string() { return data; } + static inline uint8_t length() { return len; } + static inline uint16_t width() { return span; } + static inline uint8_t *string() { return data; } static uint16_t center(uint16_t width) { return span > width ? 0 : (width - span) / 2; } }; int dwin_charmap_compare(dwin_charmap_t *v1, dwin_charmap_t *v2); -int pf_bsearch_cb_comp_dwinmap_pgm(void *userdata, size_t idx, void * data_pin); +int pf_bsearch_cb_comp_dwinmap_pgm(void *userdata, size_t idx, void *data_pin); extern DWIN_String dwin_string; @@ -664,7 +664,7 @@ const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { #endif }; -// the plain ASCII replacement for various char +// ASCII replacement for various characters const dwin_charmap_t g_dwin_charmap_common[] PROGMEM = { {IV('¡'), 'i', 0}, // A1 {IV('¢'), 'c', 0}, // A2 diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp index 20b3727dbc..069272f6c1 100644 --- a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp @@ -46,11 +46,10 @@ extern dwin_font_t dwin_font; void lcd_moveto_xy(const lcd_uint_t x, const lcd_uint_t y) { cursor.x = x; cursor.y = y; } void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { - cursor.x = col * dwin_font.width; - cursor.y = (row * (dwin_font.height + EXTRA_ROW_HEIGHT)) + (EXTRA_ROW_HEIGHT / 2); + lcd_moveto_xy(col * dwin_font.width, row * (dwin_font.height + EXTRA_ROW_HEIGHT) + EXTRA_ROW_HEIGHT / 2); } -inline void lcd_advance_cursor() { cursor.x += dwin_font.width; } +inline void lcd_advance_cursor(const uint8_t len=1) { cursor.x += len * dwin_font.width; } void lcd_put_int(const int i) { // TODO: Draw an int at the cursor position, advance the cursor @@ -58,19 +57,18 @@ void lcd_put_int(const int i) { int lcd_put_dwin_string() { DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - cursor.x += dwin_string.length() * dwin_font.width; + lcd_advance_cursor(dwin_string.length()); return dwin_string.length(); } // return < 0 on error // return the advanced cols int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { - dwin_string.set(); - dwin_string.add(c); + dwin_string.set(c); dwin_string.truncate(max_length); // Draw the char(s) at the cursor and advance the cursor DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - cursor.x += dwin_string.length() * dwin_font.width; + lcd_advance_cursor(dwin_string.length()); return dwin_string.length(); } @@ -95,7 +93,7 @@ static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(u dwin_string.add(ch); } DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - cursor.x += dwin_string.length() * dwin_font.width; + lcd_advance_cursor(dwin_string.length()); return dwin_string.length(); } @@ -112,7 +110,7 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i dwin_string.add((uint8_t*)pstr, ind, (uint8_t*)inStr); dwin_string.truncate(maxlen); DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, (char*)dwin_string.string()); - cursor.x += dwin_string.length() * dwin_font.width; + lcd_advance_cursor(dwin_string.length()); return dwin_string.length(); } From ba62f24717f8ce7a452a07208f0b571d932c16c5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 5 Sep 2021 21:00:42 -0500 Subject: [PATCH 0637/2168] =?UTF-8?q?=E2=8F=AA=EF=B8=8F=20Clean=20up=20Inf?= =?UTF-8?q?o=20Menu?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_info.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index bcdea7f92d..9b7bf58fd7 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -250,7 +250,7 @@ void menu_info_board() { STATIC_ITEM(MSG_MARLIN, SS_DEFAULT|SS_INVERT); // Marlin STATIC_ITEM_P(PSTR(SHORT_BUILD_VERSION)); // x.x.x-Branch STATIC_ITEM_P(PSTR(STRING_DISTRIBUTION_DATE)); // YYYY-MM-DD HH:MM - STATIC_ITEM_P(PSTR(MACHINE_NAME)); // My3DPrinter + STATIC_ITEM_P(PSTR(MACHINE_NAME), SS_DEFAULT|SS_INVERT); // My3DPrinter STATIC_ITEM_P(PSTR(WEBSITE_URL)); // www.my3dprinter.com PSTRING_ITEM(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); // Extruders: 2 #if HAS_LEVELING @@ -273,14 +273,6 @@ void menu_info_board() { void menu_info() { START_MENU(); BACK_ITEM(MSG_MAIN); - STATIC_ITEM(MSG_MARLIN); - STATIC_ITEM_P(PSTR(SHORT_BUILD_VERSION)); - STATIC_ITEM_P(PSTR(STRING_DISTRIBUTION_DATE)); - STATIC_ITEM_P(PSTR(MACHINE_NAME)); - STATIC_ITEM_P(PSTR(WEBSITE_URL)); - STATIC_ITEM_P(PSTR(BOARD_INFO_NAME), SS_CENTER); - VALUE_ITEM_P(MSG_INFO_EXTRUDERS, STRINGIFY(EXTRUDERS), SS_CENTER); - VALUE_ITEM_P(MSG_INFO_BAUDRATE, STRINGIFY(BAUDRATE), SS_CENTER); #if ENABLED(LCD_PRINTER_INFO_IS_BOOTSCREEN) SUBMENU(MSG_INFO_PRINTER_MENU, TERN(SHOW_CUSTOM_BOOTSCREEN, menu_show_custom_bootscreen, menu_show_marlin_bootscreen)); #else From dc6b86065e53f82e309a13b710863617f9bdce82 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 5 Sep 2021 21:23:56 -0500 Subject: [PATCH 0638/2168] =?UTF-8?q?=F0=9F=9A=B8=20Per-hotend=20Watch=20i?= =?UTF-8?q?tems?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_info.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 9b7bf58fd7..388aebb744 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -106,6 +106,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E0 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_0_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_0_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_1 != 0 @@ -115,6 +116,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E1 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_1_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_1_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_2 != 0 @@ -124,6 +126,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E2 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_2_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_2_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_3 != 0 @@ -133,6 +136,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E3 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_3_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_3_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_4 != 0 @@ -142,6 +146,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E4 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_4_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_4_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_5 != 0 @@ -151,6 +156,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E5 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_5_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_5_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_6 != 0 @@ -160,6 +166,7 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E6 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_6_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_6_MAXTEMP), SS_LEFT); + STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif #if TEMP_SENSOR_7 != 0 @@ -169,9 +176,6 @@ void menu_info_thermistors() { STATIC_ITEM_P(PSTR(LCD_STR_E7 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_7_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); - #endif - - #if HAS_EXTRUDERS STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif From 845d42ef40e1adc04315779d31eb55dac2218689 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 6 Sep 2021 15:34:12 -0500 Subject: [PATCH 0639/2168] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20Spindle/Laser?= =?UTF-8?q?=20(etc.)=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/spindle_laser.cpp | 40 ++++++----- Marlin/src/feature/spindle_laser.h | 66 +++++++++++-------- Marlin/src/gcode/control/M3-M5.cpp | 2 +- Marlin/src/module/stepper.cpp | 16 ++--- .../pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h | 4 +- 5 files changed, 70 insertions(+), 58 deletions(-) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 539fafeb34..68a84e1aba 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -52,9 +52,9 @@ cutter_power_t SpindleLaser::menuPower, // Power s #endif #define SPINDLE_LASER_PWM_OFF TERN(SPINDLE_LASER_PWM_INVERT, 255, 0) -// -// Init the cutter to a safe OFF state -// +/** + * Init the cutter to a safe OFF state + */ void SpindleLaser::init() { #if ENABLED(SPINDLE_SERVO) MOVE_SERVO(SPINDLE_SERVO_NR, SPINDLE_SERVO_MIN); @@ -86,6 +86,8 @@ void SpindleLaser::init() { #if ENABLED(SPINDLE_LASER_PWM) /** * Set the cutter PWM directly to the given ocr value + * + * @param ocr Power value */ void SpindleLaser::_set_ocr(const uint8_t ocr) { #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY @@ -105,11 +107,15 @@ void SpindleLaser::init() { WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF _set_ocr(0); } -#endif +#endif // SPINDLE_LASER_PWM -// -// Set cutter ON/OFF state (and PWM) to the given cutter power value -// +/** + * Apply power for laser/spindle + * + * Apply cutter power value for PWM, Servo, and on/off pin. + * + * @param opwr Power value. Range 0 to MAX. When 0 disable spindle/laser. + */ void SpindleLaser::apply_power(const uint8_t opwr) { static uint8_t last_power_applied = 0; if (opwr == last_power_applied) return; @@ -137,10 +143,10 @@ void SpindleLaser::apply_power(const uint8_t opwr) { } #if ENABLED(SPINDLE_CHANGE_DIR) - // - // Set the spindle direction and apply immediately - // Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled - // + /** + * Set the spindle direction and apply immediately + * Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled + */ void SpindleLaser::set_reverse(const bool reverse) { const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted if (TERN0(SPINDLE_STOP_ON_DIR_CHANGE, enabled()) && READ(SPINDLE_DIR_PIN) != dir_state) disable(); @@ -149,25 +155,17 @@ void SpindleLaser::apply_power(const uint8_t opwr) { #endif #if ENABLED(AIR_EVACUATION) - // Enable / disable Cutter Vacuum or Laser Blower motor void SpindleLaser::air_evac_enable() { WRITE(AIR_EVACUATION_PIN, AIR_EVACUATION_ACTIVE); } // Turn ON - void SpindleLaser::air_evac_disable() { WRITE(AIR_EVACUATION_PIN, !AIR_EVACUATION_ACTIVE); } // Turn OFF - void SpindleLaser::air_evac_toggle() { TOGGLE(AIR_EVACUATION_PIN); } // Toggle state - -#endif // AIR_EVACUATION +#endif #if ENABLED(AIR_ASSIST) - // Enable / disable air assist void SpindleLaser::air_assist_enable() { WRITE(AIR_ASSIST_PIN, AIR_ASSIST_PIN); } // Turn ON - void SpindleLaser::air_assist_disable() { WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_PIN); } // Turn OFF - void SpindleLaser::air_assist_toggle() { TOGGLE(AIR_ASSIST_PIN); } // Toggle state - -#endif // AIR_ASSIST +#endif #endif // HAS_CUTTER diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index da228cf8a7..9a2d05c79d 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -132,54 +132,50 @@ public: public: static void set_ocr(const uint8_t ocr); - static inline void set_ocr_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } + static inline void ocr_set_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } static void ocr_off(); - // Used to update output for power->OCR translation + + /** + * Update output for power->OCR translation + */ static inline uint8_t upower_to_ocr(const cutter_power_t upwr) { - return ( + return uint8_t( #if CUTTER_UNIT_IS(PWM255) - uint8_t(upwr) + upwr #elif CUTTER_UNIT_IS(PERCENT) pct_to_ocr(upwr) #else - uint8_t(pct_to_ocr(cpwr_to_pct(upwr))) + pct_to_ocr(cpwr_to_pct(upwr)) #endif ); } - // Correct power to configured range + /** + * Correct power to configured range + */ static inline cutter_power_t power_to_range(const cutter_power_t pwr) { - return power_to_range(pwr, ( - #if CUTTER_UNIT_IS(PWM255) - 0 - #elif CUTTER_UNIT_IS(PERCENT) - 1 - #elif CUTTER_UNIT_IS(RPM) - 2 - #else - #error "CUTTER_UNIT_IS(unknown)" - #endif - )); + return power_to_range(pwr, _CUTTER_POWER(CUTTER_POWER_UNIT)); } + static inline cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) { if (pwr <= 0) return 0; cutter_power_t upwr; switch (pwrUnit) { - case 0: // PWM + case _CUTTER_POWER_PWM255: upwr = cutter_power_t( (pwr < pct_to_ocr(min_pct)) ? pct_to_ocr(min_pct) // Use minimum if set below : (pwr > pct_to_ocr(max_pct)) ? pct_to_ocr(max_pct) // Use maximum if set above : pwr ); break; - case 1: // PERCENT + case _CUTTER_POWER_PERCENT: upwr = cutter_power_t( (pwr < min_pct) ? min_pct // Use minimum if set below : (pwr > max_pct) ? max_pct // Use maximum if set above : pwr // PCT ); break; - case 2: // RPM + case _CUTTER_POWER_RPM: upwr = cutter_power_t( (pwr < SPEED_POWER_MIN) ? SPEED_POWER_MIN // Use minimum if set below : (pwr > SPEED_POWER_MAX) ? SPEED_POWER_MAX // Use maximum if set above @@ -190,14 +186,34 @@ public: } return upwr; } - #endif // SPINDLE_LASER_PWM + /** + * Enable/Disable spindle/laser + * @param enable true = enable; false = disable + */ static inline void set_enabled(const bool enable) { - set_power(enable ? TERN(SPINDLE_LASER_PWM, (power ?: (unitPower ? upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)) : 0)), 255) : 0); + uint8_t value = 0; + if (enable) { + #if ENABLED(SPINDLE_LASER_PWM) + if (power) + value = power; + else if (unitPower) + value = upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)); + #else + value = 255; + #endif + } + set_power(value); } - // Wait for spindle to spin up or spin down + static inline void disable() { isReady = false; set_enabled(false); } + + /** + * Wait for spindle to spin up or spin down + * + * @param on true = state to on; false = state to off. + */ static inline void power_delay(const bool on) { #if DISABLED(LASER_POWER_INLINE) safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); @@ -230,8 +246,6 @@ public: } #endif - static inline void disable() { isReady = false; set_enabled(false); } - #if HAS_LCD_MENU static inline void enable_with_dir(const bool reverse) { isReady = true; @@ -325,7 +339,7 @@ public: planner.laser_inline.power = ocrpwr; } #endif - #endif // LASER_POWER_INLINE + #endif // LASER_POWER_INLINE static inline void kill() { TERN_(LASER_POWER_INLINE, inline_disable()); diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 711bb7e5e4..ff5ab5086e 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -108,7 +108,7 @@ void GcodeSuite::M3_M4(const bool is_M4) { #if ENABLED(SPINDLE_LASER_PWM) if (parser.seenval('O')) { cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0); - cutter.set_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) + cutter.ocr_set_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) } else cutter.set_power(cutter.upower_to_ocr(get_s_power())); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 50d8ad4260..f9245336f3 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1914,7 +1914,7 @@ uint32_t Stepper::block_phase_isr() { laser_trap.acc_step_count += current_block->laser.entry_per; if (laser_trap.cur_power < current_block->laser.power) laser_trap.cur_power++; } - cutter.set_ocr_power(laser_trap.cur_power); + cutter.ocr_set_power(laser_trap.cur_power); } } #else @@ -1923,7 +1923,7 @@ uint32_t Stepper::block_phase_isr() { else { laser_trap.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; laser_trap.cur_power = (current_block->laser.power * acc_step_rate) / current_block->nominal_rate; - cutter.set_ocr_power(laser_trap.cur_power); // Cycle efficiency is irrelevant it the last line was many cycles + cutter.ocr_set_power(laser_trap.cur_power); // Cycle efficiency is irrelevant it the last line was many cycles } #endif } @@ -1991,7 +1991,7 @@ uint32_t Stepper::block_phase_isr() { laser_trap.acc_step_count += current_block->laser.exit_per; if (laser_trap.cur_power > current_block->laser.power_exit) laser_trap.cur_power--; } - cutter.set_ocr_power(laser_trap.cur_power); + cutter.ocr_set_power(laser_trap.cur_power); } } #else @@ -2000,7 +2000,7 @@ uint32_t Stepper::block_phase_isr() { else { laser_trap.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; laser_trap.cur_power = (current_block->laser.power * step_rate) / current_block->nominal_rate; - cutter.set_ocr_power(laser_trap.cur_power); // Cycle efficiency isn't relevant when the last line was many cycles + cutter.ocr_set_power(laser_trap.cur_power); // Cycle efficiency isn't relevant when the last line was many cycles } #endif } @@ -2028,7 +2028,7 @@ uint32_t Stepper::block_phase_isr() { if (laser_trap.enabled) { if (!laser_trap.cruise_set) { laser_trap.cur_power = current_block->laser.power; - cutter.set_ocr_power(laser_trap.cur_power); + cutter.ocr_set_power(laser_trap.cur_power); laser_trap.cruise_set = true; } #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) @@ -2249,14 +2249,14 @@ uint32_t Stepper::block_phase_isr() { #endif // Always have PWM in this case if (stat.isPlanned) { // Planner controls the laser - cutter.set_ocr_power( + cutter.ocr_set_power( stat.isEnabled ? laser_trap.cur_power : 0 // ON with power or OFF ); } #else if (stat.isPlanned) { // Planner controls the laser #if ENABLED(SPINDLE_LASER_PWM) - cutter.set_ocr_power( + cutter.ocr_set_power( stat.isEnabled ? current_block->laser.power : 0 // ON with power or OFF ); #else @@ -2304,7 +2304,7 @@ uint32_t Stepper::block_phase_isr() { const power_status_t stat = planner.laser_inline.status; if (stat.isPlanned) { // Planner controls the laser #if ENABLED(SPINDLE_LASER_PWM) - cutter.set_ocr_power( + cutter.ocr_set_power( stat.isEnabled ? planner.laser_inline.power : 0 // ON with power or OFF ); #else diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h index 31bab5b2dc..f2e4d3da02 100644 --- a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -23,9 +23,9 @@ /** * Protoneer v3.00 pin assignments - * + * * This CNC shield has an UNO pinout and fits all Arduino-compatibles. - * + * * Referenced docs: * - https://blog.protoneer.co.nz/arduino-cnc-shield-v3-00-assembly-guide/ * - https://blog.protoneer.co.nz/arduino-cnc-shield/ From 83a1d3a46b1e12c65d0eadbd663315c400fe022f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 6 Sep 2021 16:33:24 -0500 Subject: [PATCH 0640/2168] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20code=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/stats/M75-M78.cpp | 26 +++++++++---------- Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h | 1 - Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h | 2 -- 3 files changed, 13 insertions(+), 16 deletions(-) diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index f74d9204bd..66f9f8eb8d 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -54,24 +54,24 @@ void GcodeSuite::M77() { #if ENABLED(PRINTCOUNTER) /** - * M78: Show print statistics - */ + * M78: Show print statistics + */ void GcodeSuite::M78() { if (parser.intval('S') == 78) { // "M78 S78" will reset the statistics - print_job_timer.initStats(); - ui.reset_status(); - return; - } - - #if HAS_SERVICE_INTERVALS - if (parser.seenval('R')) { - print_job_timer.resetServiceInterval(parser.value_int()); + print_job_timer.initStats(); ui.reset_status(); - return; + return; } - #endif - print_job_timer.showStats(); + #if HAS_SERVICE_INTERVALS + if (parser.seenval('R')) { + print_job_timer.resetServiceInterval(parser.value_int()); + ui.reset_status(); + return; + } + #endif + + print_job_timer.showStats(); } #endif // PRINTCOUNTER diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h index f6b3231737..fd52f2cfa9 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h @@ -194,7 +194,6 @@ #define TITLE_HOME_RU "Home" #define TITLE_EXTRUDE_RU "экструзия" #define TITLE_LEVELING_RU "уровень" -#define TITLE_MLEVELING_RU "углы" #define TITLE_SET_RU "настройки" #define TITLE_MORE_RU "больше" #define TITLE_CHOOSEFILE_RU "файла" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h index a75bc69ab7..6bba3a3edf 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_sp.h @@ -29,7 +29,6 @@ #define PRINT_TEXT_SP "Imprimir" #define EXTRUDE_TEXT_SP "Extrusor" #define LEVELING_TEXT_SP "Leveling" -#define MLEVELING_TEXT_SP "Leveling" #define AUTO_LEVELING_TEXT_SP "Autolevel" #define SET_TEXT_SP "Config" #define MORE_TEXT_SP "Más" @@ -53,7 +52,6 @@ #define TOOL_MOVE_SP "Mover" #define TOOL_HOME_SP "Origen" #define TOOL_LEVELING_SP "Leveling" -#define TOOL_MLEVELING_SP "Leveling" #define TOOL_AUTO_LEVELING_SP "Autolevel" #define TOOL_FILAMENT_SP "Filamento" #define TOOL_MORE_SP "Más" From 853eebc3f2f6326000da790cfd549c2a44dfeae2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 6 Sep 2021 17:38:47 -0500 Subject: [PATCH 0641/2168] =?UTF-8?q?=F0=9F=9A=B8=20Show=20ExtUI=20message?= =?UTF-8?q?=20for=20PID=5FSTARTED?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 4 +++- Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 3 +++ Marlin/src/lcd/extui/malyan/malyan_extui.cpp | 3 +++ 4 files changed, 10 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index b6f76564f9..9875422742 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -478,7 +478,7 @@ #endif // Aliases for LCD features -#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY,DGUS_LCD_UI_MKS) +#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) #define HAS_DGUS_LCD 1 #endif diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 589821e23a..4b4521c47f 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -135,6 +135,9 @@ namespace ExtUI { void onPidTuning(const result_t rst) { // Called for temperature PID tuning result switch (rst) { + case PID_STARTED: + ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE)); + break; case PID_BAD_EXTRUDER_NUM: ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); break; @@ -147,7 +150,6 @@ namespace ExtUI { case PID_DONE: ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); break; - case PID_STARTED: break; } ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index 9faedae711..a696ca3413 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -133,6 +133,9 @@ namespace ExtUI { // Called for temperature PID tuning result //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { + case PID_STARTED: + StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); + break; case PID_BAD_EXTRUDER_NUM: StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); break; diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index 5815522afc..8a23799988 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -108,6 +108,9 @@ namespace ExtUI { // Called for temperature PID tuning result //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { + case PID_STARTED: + set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE)); + break; case PID_BAD_EXTRUDER_NUM: set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); break; From b0e798330d8f5ade4a230e0a91f05482d100bb97 Mon Sep 17 00:00:00 2001 From: mrv96 Date: Tue, 7 Sep 2021 02:51:04 +0200 Subject: [PATCH 0642/2168] =?UTF-8?q?=E2=9C=A8Add=20DGUS=5FLCD=5FUI=5FRELO?= =?UTF-8?q?ADED=20(#21931)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 5 + Marlin/src/inc/Conditionals_LCD.h | 4 + Marlin/src/inc/SanityCheck.h | 31 +- Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp | 4 +- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 4 +- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 4 +- .../lcd/extui/dgus_reloaded/DGUSDisplay.cpp | 407 +++++++ .../src/lcd/extui/dgus_reloaded/DGUSDisplay.h | 171 +++ .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 1059 +++++++++++++++++ .../lcd/extui/dgus_reloaded/DGUSRxHandler.h | 123 ++ .../extui/dgus_reloaded/DGUSScreenHandler.cpp | 540 +++++++++ .../extui/dgus_reloaded/DGUSScreenHandler.h | 152 +++ .../extui/dgus_reloaded/DGUSSetupHandler.cpp | 209 ++++ .../extui/dgus_reloaded/DGUSSetupHandler.h | 43 + .../lcd/extui/dgus_reloaded/DGUSTxHandler.cpp | 632 ++++++++++ .../lcd/extui/dgus_reloaded/DGUSTxHandler.h | 127 ++ .../extui/dgus_reloaded/config/DGUS_Addr.h | 173 +++ .../dgus_reloaded/config/DGUS_Constants.h | 96 ++ .../extui/dgus_reloaded/config/DGUS_Control.h | 50 + .../extui/dgus_reloaded/config/DGUS_Data.h | 148 +++ .../extui/dgus_reloaded/config/DGUS_Screen.h | 52 + .../definition/DGUS_ScreenAddrList.cpp | 240 ++++ .../definition/DGUS_ScreenAddrList.h | 32 + .../definition/DGUS_ScreenSetup.cpp | 57 + .../definition/DGUS_ScreenSetup.h | 31 + .../extui/dgus_reloaded/definition/DGUS_VP.h | 40 + .../dgus_reloaded/definition/DGUS_VPList.cpp | 368 ++++++ .../dgus_reloaded/definition/DGUS_VPList.h | 26 + .../dgus_reloaded/dgus_reloaded_extui.cpp | 142 +++ ini/features.ini | 3 +- platformio.ini | 1 + 31 files changed, 4966 insertions(+), 8 deletions(-) create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Control.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Data.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VP.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.h create mode 100644 Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bfc39298a2..fea0d51e5f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2565,10 +2565,15 @@ // - Download https://github.com/makerbase-mks/MKS-H43 // - Copy the downloaded DWIN_SET folder to the SD card. // +// RELOADED (T5UID1) +// - Download https://github.com/Desuuuu/DGUS-reloaded +// - Copy the downloaded DWIN_SET folder to the SD card. +// //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC //#define DGUS_LCD_UI_HIPRECY //#define DGUS_LCD_UI_MKS +//#define DGUS_LCD_UI_RELOADED #if ENABLED(DGUS_LCD_UI_MKS) #define USE_MKS_GREEN_UI #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9875422742..0715b1f514 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -479,6 +479,10 @@ // Aliases for LCD features #if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) + #define HAS_DGUS_LCD_CLASSIC 1 +#endif + +#if ANY(HAS_DGUS_LCD_CLASSIC, DGUS_LCD_UI_RELOADED) #define HAS_DGUS_LCD 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 01fdaa3451..75df13127c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2655,7 +2655,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ - + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ + + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ @@ -3798,6 +3798,35 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #undef _BAD_DRIVER +/** + * Require certain features for DGUS_LCD_UI_RELOADED. + */ +#if ENABLED(DGUS_LCD_UI_RELOADED) + #if BUFSIZE < 4 + #error "DGUS_LCD_UI_RELOADED requires a BUFSIZE of at least 4." + #elif HOTENDS < 1 + #error "DGUS_LCD_UI_RELOADED requires at least 1 hotend." + #elif EXTRUDERS < 1 + #error "DGUS_LCD_UI_RELOADED requires at least 1 extruder." + #elif !HAS_HEATED_BED + #error "DGUS_LCD_UI_RELOADED requires a heated bed." + #elif FAN_COUNT < 1 + #error "DGUS_LCD_UI_RELOADED requires a fan." + #elif !HAS_BED_PROBE + #error "DGUS_LCD_UI_RELOADED requires a bed probe." + #elif !HAS_MESH + #error "DGUS_LCD_UI_RELOADED requires mesh leveling." + #elif DISABLED(LEVEL_BED_CORNERS) + #error "DGUS_LCD_UI_RELOADED requires LEVEL_BED_CORNERS." + #elif DISABLED(BABYSTEP_ALWAYS_AVAILABLE) + #error "DGUS_LCD_UI_RELOADED requires BABYSTEP_ALWAYS_AVAILABLE." + #elif DISABLED(BABYSTEP_ZPROBE_OFFSET) + #error "DGUS_LCD_UI_RELOADED requires BABYSTEP_ZPROBE_OFFSET." + #elif ENABLED(AUTO_BED_LEVELING_UBL) && DISABLED(UBL_SAVE_ACTIVE_ON_M500) + #warning "Without UBL_SAVE_ACTIVE_ON_M500, your mesh will not be saved when using the touchscreen." + #endif +#endif + // Misc. Cleanup #undef _TEST_PWM #undef _LINEAR_AXES_STR diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index c2390d63a6..535bc96591 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_DGUS_LCD +#if HAS_DGUS_LCD_CLASSIC #if HOTENDS > 2 #warning "More than 2 hotends not implemented on DGUS Display UI." @@ -268,4 +268,4 @@ bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy) { return true; } -#endif // HAS_DGUS_LCD +#endif // HAS_DGUS_LCD_CLASSIC diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 5c108d0709..9e44cf1331 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_DGUS_LCD +#if HAS_DGUS_LCD_CLASSIC #include "DGUSScreenHandler.h" @@ -772,4 +772,4 @@ void DGUSDisplay::RequestScreen(DGUSLCD_Screens screen) { WriteVariable(0x84, gotoscreen, sizeof(gotoscreen)); } -#endif // HAS_DGUS_LCD +#endif // HAS_DGUS_LCD_CLASSIC diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 4b4521c47f..4f15827a49 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -26,7 +26,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_DGUS_LCD +#if HAS_DGUS_LCD_CLASSIC #include "../ui_api.h" #include "DGUSDisplay.h" @@ -159,4 +159,4 @@ namespace ExtUI { void onSteppersEnabled() {} } -#endif // HAS_DGUS_LCD +#endif // HAS_DGUS_LCD_CLASSIC diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp new file mode 100644 index 0000000000..e82f63bce1 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp @@ -0,0 +1,407 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/* DGUS implementation written by coldtobi in 2019 for Marlin */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUSDisplay.h" + +#include "config/DGUS_Addr.h" +#include "config/DGUS_Constants.h" +#include "definition/DGUS_VPList.h" + +#include "../ui_api.h" +#include "../../../gcode/gcode.h" + +long map_precise(float x, long in_min, long in_max, long out_min, long out_max) { + return LROUND((x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min); +} + +uint8_t DGUSDisplay::gui_version = 0; +uint8_t DGUSDisplay::os_version = 0; + +uint8_t DGUSDisplay::volume = 255; +uint8_t DGUSDisplay::brightness = 100; + +DGUSDisplay::rx_datagram_state_t DGUSDisplay::rx_datagram_state = DGUS_IDLE; +uint8_t DGUSDisplay::rx_datagram_len = 0; + +bool DGUSDisplay::initialized = false; + +void DGUSDisplay::Loop() { + ProcessRx(); +} + +void DGUSDisplay::Init() { + LCD_SERIAL.begin(LCD_BAUDRATE); + + Read(DGUS_VERSION, 1); +} + +void DGUSDisplay::Read(uint16_t addr, uint8_t size) { + WriteHeader(addr, DGUS_READVAR, size); + + LCD_SERIAL.write(size); +} + +void DGUSDisplay::Write(uint16_t addr, const void* data_ptr, uint8_t size) { + if (!data_ptr) return; + + WriteHeader(addr, DGUS_WRITEVAR, size); + + const char* data = static_cast(data_ptr); + + while (size--) { + LCD_SERIAL.write(*data++); + } +} + +void DGUSDisplay::WriteString(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { + if (!data_ptr) return; + + WriteHeader(addr, DGUS_WRITEVAR, size); + + const char* data = static_cast(data_ptr); + size_t len = strlen(data); + uint8_t left_spaces = 0; + uint8_t right_spaces = 0; + + if (len < size) { + if (!len) { + right_spaces = size; + } + else if ((left && right) || (!left && !right)) { + left_spaces = (size - len) / 2; + right_spaces = size - len - left_spaces; + } + else if (left) { + right_spaces = size - len; + } + else { + left_spaces = size - len; + } + } + else { + len = size; + } + + while (left_spaces--) { + LCD_SERIAL.write(' '); + } + while (len--) { + LCD_SERIAL.write(*data++); + } + while (right_spaces--) { + LCD_SERIAL.write(use_space ? ' ' : '\0'); + } +} + +void DGUSDisplay::WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { + if (!data_ptr) return; + + WriteHeader(addr, DGUS_WRITEVAR, size); + + const char* data = static_cast(data_ptr); + size_t len = strlen_P(data); + uint8_t left_spaces = 0; + uint8_t right_spaces = 0; + + if (len < size) { + if (!len) { + right_spaces = size; + } + else if ((left && right) || (!left && !right)) { + left_spaces = (size - len) / 2; + right_spaces = size - len - left_spaces; + } + else if (left) { + right_spaces = size - len; + } + else { + left_spaces = size - len; + } + } + else { + len = size; + } + + while (left_spaces--) { + LCD_SERIAL.write(' '); + } + while (len--) { + LCD_SERIAL.write(pgm_read_byte(data++)); + } + while (right_spaces--) { + LCD_SERIAL.write(use_space ? ' ' : '\0'); + } +} + +void DGUSDisplay::SwitchScreen(DGUS_Screen screen) { + DEBUG_ECHOLNPAIR("SwitchScreen ", (uint8_t)screen); + const uint8_t command[] = { 0x5A, 0x01, 0x00, (uint8_t)screen }; + Write(0x84, command, sizeof(command)); +} + +void DGUSDisplay::PlaySound(uint8_t start, uint8_t len, uint8_t volume) { + if (volume == 0) volume = DGUSDisplay::volume; + if (volume == 0) return; + DEBUG_ECHOLNPAIR("PlaySound ", start, ":", len, "\nVolume ", volume); + const uint8_t command[] = { start, len, volume, 0x00 }; + Write(0xA0, command, sizeof(command)); +} + +void DGUSDisplay::EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { + DEBUG_ECHOLNPAIR("EnableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); + + const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x01 }; + Write(0xB0, command, sizeof(command)); + + FlushTx(); + delay(50); +} + +void DGUSDisplay::DisableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { + DEBUG_ECHOLNPAIR("DisableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); + + const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x00 }; + Write(0xB0, command, sizeof(command)); + + FlushTx(); + delay(50); +} + +uint8_t DGUSDisplay::GetBrightness() { + return brightness; +} + +uint8_t DGUSDisplay::GetVolume() { + return map_precise(volume, 0, 255, 0, 100); +} + +void DGUSDisplay::SetBrightness(uint8_t new_brightness) { + brightness = constrain(new_brightness, 0, 100); + new_brightness = map_precise(brightness, 0, 100, 5, 100); + DEBUG_ECHOLNPAIR("SetBrightness ", new_brightness); + const uint8_t command[] = { new_brightness, new_brightness }; + Write(0x82, command, sizeof(command)); +} + +void DGUSDisplay::SetVolume(uint8_t new_volume) { + volume = map_precise(constrain(new_volume, 0, 100), 0, 100, 0, 255); + DEBUG_ECHOLNPAIR("SetVolume ", volume); + const uint8_t command[] = { volume, 0x00 }; + Write(0xA1, command, sizeof(command)); +} + +void DGUSDisplay::ProcessRx() { + + #if ENABLED(LCD_SERIAL_STATS_RX_BUFFER_OVERRUNS) + if (!LCD_SERIAL.available() && LCD_SERIAL.buffer_overruns()) { + // Overrun, but reset the flag only when the buffer is empty + // We want to extract as many as valid datagrams possible... + DEBUG_ECHOPGM("OVFL"); + rx_datagram_state = DGUS_IDLE; + //LCD_SERIAL.reset_rx_overun(); + LCD_SERIAL.flush(); + } + #endif + + uint8_t receivedbyte; + while (LCD_SERIAL.available()) { + switch (rx_datagram_state) { + + case DGUS_IDLE: // Waiting for the first header byte + receivedbyte = LCD_SERIAL.read(); + DEBUG_ECHOPAIR("< ", receivedbyte); + if (DGUS_HEADER1 == receivedbyte) rx_datagram_state = DGUS_HEADER1_SEEN; + break; + + case DGUS_HEADER1_SEEN: // Waiting for the second header byte + receivedbyte = LCD_SERIAL.read(); + DEBUG_ECHOPAIR(" ", receivedbyte); + rx_datagram_state = (DGUS_HEADER2 == receivedbyte) ? DGUS_HEADER2_SEEN : DGUS_IDLE; + break; + + case DGUS_HEADER2_SEEN: // Waiting for the length byte + rx_datagram_len = LCD_SERIAL.read(); + DEBUG_ECHOPAIR(" (", rx_datagram_len, ") "); + + // Telegram min len is 3 (command and one word of payload) + rx_datagram_state = WITHIN(rx_datagram_len, 3, DGUS_RX_BUFFER_SIZE) ? DGUS_WAIT_TELEGRAM : DGUS_IDLE; + break; + + case DGUS_WAIT_TELEGRAM: // wait for complete datagram to arrive. + if (LCD_SERIAL.available() < rx_datagram_len) return; + + initialized = true; // We've talked to it, so we defined it as initialized. + uint8_t command = LCD_SERIAL.read(); + + DEBUG_ECHOPAIR("# ", command); + + uint8_t readlen = rx_datagram_len - 1; // command is part of len. + unsigned char tmp[rx_datagram_len - 1]; + unsigned char *ptmp = tmp; + + while (readlen--) { + receivedbyte = LCD_SERIAL.read(); + DEBUG_ECHOPAIR(" ", receivedbyte); + *ptmp++ = receivedbyte; + } + DEBUG_ECHOPGM(" # "); + // mostly we'll get this: 5A A5 03 82 4F 4B -- ACK on 0x82, so discard it. + if (command == DGUS_WRITEVAR && 'O' == tmp[0] && 'K' == tmp[1]) { + DEBUG_ECHOLNPGM(">"); + rx_datagram_state = DGUS_IDLE; + break; + } + + /* AutoUpload, (and answer to) Command 0x83 : + | tmp[0 1 2 3 4 ... ] + | Example 5A A5 06 83 20 01 01 78 01 …… + | / / | | \ / | \ \ + | Header | | | | \_____\_ DATA (Words!) + | DatagramLen / VPAdr | + | Command DataLen (in Words) */ + if (command == DGUS_READVAR) { + const uint16_t addr = tmp[0] << 8 | tmp[1]; + const uint8_t dlen = tmp[2] << 1; // Convert to Bytes. (Display works with words) + DEBUG_ECHOPAIR("addr=", addr, " dlen=", dlen, "> "); + + if (addr == DGUS_VERSION && dlen == 2) { + DEBUG_ECHOLNPGM("VERSIONS"); + gui_version = tmp[3]; + os_version = tmp[4]; + rx_datagram_state = DGUS_IDLE; + break; + } + + DGUS_VP vp; + if (!DGUS_PopulateVP((DGUS_Addr)addr, &vp)) { + DEBUG_ECHOLNPGM("VP not found"); + rx_datagram_state = DGUS_IDLE; + break; + } + + if (!vp.rx_handler) { + DEBUG_ECHOLNPGM("VP found, no handler."); + rx_datagram_state = DGUS_IDLE; + break; + } + + gcode.reset_stepper_timeout(); + + if (!vp.size) { + DEBUG_ECHOLN(); + vp.rx_handler(vp, nullptr); + + rx_datagram_state = DGUS_IDLE; + break; + } + + if (vp.flags & VPFLAG_RXSTRING) { + unsigned char buffer[vp.size]; + memset(buffer, 0, vp.size); + + for (uint8_t i = 0; i < dlen; i++) { + if (i >= vp.size) { + break; + } + + if (i + 1 < dlen && tmp[i + 3] == 0xFF && tmp[i + 4] == 0xFF) { + break; + } + + buffer[i] = tmp[i + 3]; + } + + DEBUG_ECHOLN(); + vp.rx_handler(vp, buffer); + + rx_datagram_state = DGUS_IDLE; + break; + } + + if (dlen != vp.size) { + DEBUG_ECHOLNPGM("VP found, size mismatch."); + rx_datagram_state = DGUS_IDLE; + break; + } + + DEBUG_ECHOLN(); + vp.rx_handler(vp, &tmp[3]); + + rx_datagram_state = DGUS_IDLE; + break; + } + + DEBUG_ECHOLNPGM(">"); + rx_datagram_state = DGUS_IDLE; + break; + } + } +} + +size_t DGUSDisplay::GetFreeTxBuffer() { + #ifdef LCD_SERIAL_GET_TX_BUFFER_FREE + return LCD_SERIAL_GET_TX_BUFFER_FREE(); + #else + return SIZE_MAX; + #endif +} + +void DGUSDisplay::FlushTx() { + #ifdef ARDUINO_ARCH_STM32 + LCD_SERIAL.flush(); + #else + LCD_SERIAL.flushTX(); + #endif +} + +void DGUSDisplay::WriteHeader(uint16_t addr, uint8_t command, uint8_t len) { + LCD_SERIAL.write(DGUS_HEADER1); + LCD_SERIAL.write(DGUS_HEADER2); + LCD_SERIAL.write(len + 3); + LCD_SERIAL.write(command); + LCD_SERIAL.write(addr >> 8); + LCD_SERIAL.write(addr & 0xFF); +} + +bool DGUS_PopulateVP(const DGUS_Addr addr, DGUS_VP * const buffer) { + const DGUS_VP *ret = vp_list; + + do { + const uint16_t *paddr = (uint16_t *)(&ret->addr); + const uint16_t addrcheck = pgm_read_word(paddr); + if (addrcheck == 0) break; + if ((DGUS_Addr)addrcheck == addr) { + memcpy_P(buffer, ret, sizeof(*ret)); + return true; + } + } while (++ret); + DEBUG_ECHOLNPAIR("VP not found: ", (uint16_t)addr); + return false; +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h new file mode 100644 index 0000000000..2a679648d1 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -0,0 +1,171 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/* DGUS implementation written by coldtobi in 2019 for Marlin */ + +#include "config/DGUS_Screen.h" +#include "config/DGUS_Control.h" +#include "definition/DGUS_VP.h" + +#include "../../../inc/MarlinConfigPre.h" +#include "../../../MarlinCore.h" + +#define DEBUG_OUT ENABLED(DEBUG_DGUSLCD) +#include "../../../core/debug_out.h" + +#define Swap16(val) ((uint16_t)(((uint16_t)(val) >> 8) |\ + ((uint16_t)(val) << 8))) + +// Low-Level access to the display. +class DGUSDisplay { +public: + + enum DGUS_ControlType : uint8_t { + VARIABLE_DATA_INPUT = 0x00, + POPUP_WINDOW = 0x01, + INCREMENTAL_ADJUST = 0x02, + SLIDER_ADJUST = 0x03, + RTC_SETTINGS = 0x04, + RETURN_KEY_CODE = 0x05, + TEXT_INPUT = 0x06, + FIRMWARE_SETTINGS = 0x07 + }; + + DGUSDisplay() = default; + + static void Init(); + + static void Read(uint16_t addr, uint8_t size); + static void Write(uint16_t addr, const void* data_ptr, uint8_t size); + + static void WriteString(uint16_t addr, const void* data_ptr, uint8_t size, bool left = true, bool right = false, bool use_space = true); + static void WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left = true, bool right = false, bool use_space = true); + + template + static void Write(uint16_t addr, T data) { + Write(addr, static_cast(&data), sizeof(T)); + } + + // Until now I did not need to actively read from the display. That's why there is no ReadVariable + // (I extensively use the auto upload of the display) + + // Force display into another screen. + static void SwitchScreen(DGUS_Screen screen); + // Play sounds using the display speaker. + // start: position at which the sound was stored on the display. + // len: how many sounds to play. Sounds will play consecutively from start to start+len-1. + // volume: playback volume. 0 keeps the current volume. + static void PlaySound(uint8_t start, uint8_t len = 1, uint8_t volume = 0); + // Enable/disable a specific touch control. + // type: control type. + // control: index of the control on the page (set during screen development). + static void EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control); + static void DisableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control); + + static uint8_t GetBrightness(); + static uint8_t GetVolume(); + + // Set the display brightness/volume, ranging 0 - 100 + static void SetBrightness(uint8_t brightness); + static void SetVolume(uint8_t volume); + + // Periodic tasks, eg. Rx-Queue handling. + static void Loop(); + + // Helper for users of this class to estimate if an interaction would be blocking. + static size_t GetFreeTxBuffer(); + static void FlushTx(); + + // Checks two things: Can we confirm the presence of the display and has we initiliazed it. + // (both boils down that the display answered to our chatting) + static inline bool IsInitialized() { + return initialized; + } + + static uint8_t gui_version; + static uint8_t os_version; + + template + static T SwapBytes(const T value) { + union { + T val; + char byte[sizeof(T)]; + } src, dst; + + src.val = value; + LOOP_L_N(i, sizeof(T)) dst.byte[i] = src.byte[sizeof(T) - i - 1]; + return dst.val; + } + + template + T_out FromFixedPoint(const T_in value) { + return (T_out)((float)value / POW(10, decimals)); + } + + template + T_out ToFixedPoint(const T_in value) { + return (T_out)LROUND((float)value * POW(10, decimals)); + } + +private: + enum dgus_header : uint8_t { + DGUS_HEADER1 = 0x5A, + DGUS_HEADER2 = 0xA5 + }; + + enum dgus_command : uint8_t { + DGUS_WRITEVAR = 0x82, + DGUS_READVAR = 0x83 + }; + + enum rx_datagram_state_t : uint8_t { + DGUS_IDLE, //< waiting for DGUS_HEADER1. + DGUS_HEADER1_SEEN, //< DGUS_HEADER1 received + DGUS_HEADER2_SEEN, //< DGUS_HEADER2 received + DGUS_WAIT_TELEGRAM, //< LEN received, Waiting for to receive all bytes. + }; + + enum dgus_system_addr : uint16_t { + DGUS_VERSION = 0x000f // OS/GUI version + }; + + static void WriteHeader(uint16_t addr, uint8_t command, uint8_t len); + static void ProcessRx(); + + static uint8_t volume; + static uint8_t brightness; + + static rx_datagram_state_t rx_datagram_state; + static uint8_t rx_datagram_len; + + static bool initialized; +}; + +template<> inline uint16_t DGUSDisplay::SwapBytes(const uint16_t value) { + return ((value << 8) | (value >> 8)); +} + +extern DGUSDisplay dgus_display; + +/// Helper to populate a DGUS_VP for a given VP. Return false if not found. +extern bool DGUS_PopulateVP(const DGUS_Addr addr, DGUS_VP * const buffer); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp new file mode 100644 index 0000000000..5f36dac7f6 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -0,0 +1,1059 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUSRxHandler.h" + +#include "DGUSScreenHandler.h" +#include "config/DGUS_Screen.h" + +#include "../ui_api.h" +#include "../../../core/language.h" +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" +#include "../../../gcode/queue.h" +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #include "../../../feature/pause.h" +#endif +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { + const DGUS_Screen screen = (DGUS_Screen)((uint8_t*)data_ptr)[1]; + + if (vp.addr == DGUS_Addr::SCREENCHANGE_SD) { + #if ENABLED(SDSUPPORT) + #if !PIN_EXISTS(SD_DETECT) + card.mount(); + #endif + + if (!ExtUI::isMediaInserted()) { + dgus_screen_handler.SetStatusMessagePGM(GET_TEXT(MSG_NO_MEDIA)); + return; + } + + card.cdroot(); + #else + dgus_screen_handler.SetStatusMessagePGM(GET_TEXT(MSG_NO_MEDIA)); + return; + #endif + } + + if (vp.addr == DGUS_Addr::SCREENCHANGE_Idle + && (printingIsActive() || printingIsPaused())) { + dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while printing")); + return; + } + + if (vp.addr == DGUS_Addr::SCREENCHANGE_Printing + && (!printingIsActive() && !printingIsPaused())) { + dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while idle")); + return; + } + + dgus_screen_handler.TriggerScreenChange(screen); +} + +#if ENABLED(SDSUPPORT) + void DGUSRxHandler::Scroll(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Scroll scroll = (DGUS_Data::Scroll)((uint8_t*)data_ptr)[1]; + + switch (scroll) { + case DGUS_Data::Scroll::GO_BACK: + if (dgus_screen_handler.filelist.isAtRootDir()) { + return; + } + + dgus_screen_handler.filelist_offset = 0; + dgus_screen_handler.filelist_selected = -1; + dgus_screen_handler.filelist.upDir(); + break; + case DGUS_Data::Scroll::UP: + if (dgus_screen_handler.filelist_offset < 1) { + return; + } + + --dgus_screen_handler.filelist_offset; + break; + case DGUS_Data::Scroll::DOWN: + if (dgus_screen_handler.filelist_offset + 1 + DGUS_FILE_COUNT > dgus_screen_handler.filelist.count()) { + return; + } + + ++dgus_screen_handler.filelist_offset; + break; + } + + dgus_screen_handler.TriggerFullUpdate(); + } + + void DGUSRxHandler::SelectFile(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const uint8_t index = ((uint8_t*)data_ptr)[1]; + + if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + index)) { + return; + } + + if (dgus_screen_handler.filelist.isDir()) { + dgus_screen_handler.filelist_offset = 0; + dgus_screen_handler.filelist_selected = -1; + dgus_screen_handler.filelist.changeDir(dgus_screen_handler.filelist.filename()); + } + else { + dgus_screen_handler.filelist_selected = dgus_screen_handler.filelist_offset + index; + } + + dgus_screen_handler.TriggerFullUpdate(); + } + + void DGUSRxHandler::PrintFile(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + if (dgus_screen_handler.filelist_selected < 0) { + dgus_screen_handler.SetStatusMessagePGM(PSTR("No file selected")); + return; + } + + if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_selected) + || dgus_screen_handler.filelist.isDir()) { + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + ExtUI::printFile(dgus_screen_handler.filelist.shortFilename()); + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); + } +#endif // SDSUPPORT + +void DGUSRxHandler::PrintAbort(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!printingIsActive() && !printingIsPaused()) { + dgus_screen_handler.TriggerFullUpdate(); + return; + } + + ExtUI::stopPrint(); +} + +void DGUSRxHandler::PrintPause(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!printingIsActive()) { + dgus_screen_handler.TriggerFullUpdate(); + return; + } + + ExtUI::pausePrint(); +} + +void DGUSRxHandler::PrintResume(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!printingIsPaused()) { + dgus_screen_handler.TriggerFullUpdate(); + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + ExtUI::resumePrint(); +} + +void DGUSRxHandler::Feedrate(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const int16_t feedrate = Swap16(*(int16_t*)data_ptr); + + ExtUI::setFeedrate_percent(feedrate); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::Flowrate(DGUS_VP &vp, void *data_ptr) { + const int16_t flowrate = Swap16(*(int16_t*)data_ptr); + + switch (vp.addr) { + default: return; + case DGUS_Addr::ADJUST_SetFlowrate_CUR: + #if EXTRUDERS > 1 + ExtUI::setFlow_percent(flowrate, ExtUI::getActiveTool()); + #else + ExtUI::setFlow_percent(flowrate, ExtUI::E0); + #endif + break; + #if EXTRUDERS > 1 + case DGUS_Addr::ADJUST_SetFlowrate_E0: + ExtUI::setFlow_percent(flowrate, ExtUI::E0); + break; + case DGUS_Addr::ADJUST_SetFlowrate_E1: + ExtUI::setFlow_percent(flowrate, ExtUI::E1); + break; + #endif + } + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::BabystepSet(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const int16_t data = Swap16(*(int16_t*)data_ptr); + const float offset = dgus_display.FromFixedPoint(data); + + const int16_t steps = ExtUI::mmToWholeSteps(offset - ExtUI::getZOffset_mm(), ExtUI::Z); + + ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); + + dgus_screen_handler.TriggerEEPROMSave(); + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::Babystep(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Adjust adjust = (DGUS_Data::Adjust)((uint8_t*)data_ptr)[1]; + int16_t steps; + + switch (adjust) { + default: return; + case DGUS_Data::Adjust::INCREMENT: + steps = ExtUI::mmToWholeSteps(DGUS_PRINT_BABYSTEP, ExtUI::Z); + break; + case DGUS_Data::Adjust::DECREMENT: + steps = ExtUI::mmToWholeSteps(-DGUS_PRINT_BABYSTEP, ExtUI::Z); + break; + } + + ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); + + dgus_screen_handler.TriggerEEPROMSave(); + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::TempPreset(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::TempPreset preset = (DGUS_Data::TempPreset)((uint8_t*)data_ptr)[1]; + + switch (preset) { + case DGUS_Data::TempPreset::PLA: + #if HOTENDS < 2 + ExtUI::setTargetTemp_celsius(DGUS_PLA_TEMP_HOTEND, ExtUI::H0); + #else + ExtUI::setTargetTemp_celsius(DGUS_PLA_TEMP_HOTEND, ExtUI::getActiveTool()); + #endif + ExtUI::setTargetTemp_celsius(DGUS_PLA_TEMP_BED, ExtUI::BED); + break; + case DGUS_Data::TempPreset::ABS: + #if HOTENDS < 2 + ExtUI::setTargetTemp_celsius(DGUS_ABS_TEMP_HOTEND, ExtUI::H0); + #else + ExtUI::setTargetTemp_celsius(DGUS_ABS_TEMP_HOTEND, ExtUI::getActiveTool()); + #endif + ExtUI::setTargetTemp_celsius(DGUS_ABS_TEMP_BED, ExtUI::BED); + break; + case DGUS_Data::TempPreset::PETG: + #if HOTENDS < 2 + ExtUI::setTargetTemp_celsius(DGUS_PETG_TEMP_HOTEND, ExtUI::H0); + #else + ExtUI::setTargetTemp_celsius(DGUS_PETG_TEMP_HOTEND, ExtUI::getActiveTool()); + #endif + ExtUI::setTargetTemp_celsius(DGUS_PETG_TEMP_BED, ExtUI::BED); + break; + } + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::TempTarget(DGUS_VP &vp, void *data_ptr) { + const int16_t temp = Swap16(*(int16_t*)data_ptr); + + switch (vp.addr) { + default: return; + case DGUS_Addr::TEMP_SetTarget_Bed: + ExtUI::setTargetTemp_celsius(temp, ExtUI::BED); + break; + case DGUS_Addr::TEMP_SetTarget_H0: + ExtUI::setTargetTemp_celsius(temp, ExtUI::H0); + break; + #if HOTENDS > 1 + case DGUS_Addr::TEMP_SetTarget_H1: + ExtUI::setTargetTemp_celsius(temp, ExtUI::H1); + break; + #endif + } + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::TempCool(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Heater heater = (DGUS_Data::Heater)Swap16(*(uint16_t*)data_ptr); + + switch (heater) { + default: return; + case DGUS_Data::Heater::ALL: + ExtUI::setTargetTemp_celsius(0, ExtUI::BED); + ExtUI::setTargetTemp_celsius(0, ExtUI::H0); + #if HOTENDS > 1 + ExtUI::setTargetTemp_celsius(0, ExtUI::H1); + #endif + break; + case DGUS_Data::Heater::BED: + ExtUI::setTargetTemp_celsius(0, ExtUI::BED); + break; + case DGUS_Data::Heater::H0: + ExtUI::setTargetTemp_celsius(0, ExtUI::H0); + break; + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + ExtUI::setTargetTemp_celsius(0, ExtUI::H1); + break; + #endif + } + + dgus_screen_handler.SetStatusMessagePGM(PSTR("Cooling...")); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::Steppers(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Control control = (DGUS_Data::Control)((uint8_t*)data_ptr)[1]; + + switch (control) { + case DGUS_Data::Control::ENABLE: + enable_all_steppers(); + break; + case DGUS_Data::Control::DISABLE: + disable_all_steppers(); + break; + } + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::ZOffset(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!ExtUI::isAxisPositionKnown(ExtUI::Z)) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + const int16_t data = Swap16(*(int16_t*)data_ptr); + const float offset = dgus_display.FromFixedPoint(data); + + const int16_t steps = ExtUI::mmToWholeSteps(offset - ExtUI::getZOffset_mm(), ExtUI::Z); + + ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); + + dgus_screen_handler.TriggerEEPROMSave(); + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::ZOffsetStep(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!ExtUI::isAxisPositionKnown(ExtUI::Z)) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + const DGUS_Data::Adjust adjust = (DGUS_Data::Adjust)((uint8_t*)data_ptr)[1]; + int16_t steps; + + switch (dgus_screen_handler.offset_steps) { + default: return; + case DGUS_Data::StepSize::MMP1: + steps = ExtUI::mmToWholeSteps((adjust == DGUS_Data::Adjust::INCREMENT ? 0.1f : -0.1f), ExtUI::Z); + break; + case DGUS_Data::StepSize::MMP01: + steps = ExtUI::mmToWholeSteps((adjust == DGUS_Data::Adjust::INCREMENT ? 0.01f : -0.01f), ExtUI::Z); + break; + } + + ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); + + dgus_screen_handler.TriggerEEPROMSave(); + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::ZOffsetSetStep(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::StepSize size = (DGUS_Data::StepSize)((uint8_t*)data_ptr)[1]; + + dgus_screen_handler.offset_steps = size; + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!ExtUI::isPositionKnown()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + const uint8_t point = ((uint8_t*)data_ptr)[1]; + constexpr float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; + float x, y; + + switch (point) { + default: return; + case 1: + x = DGUS_LEVEL_CENTER_X; + y = DGUS_LEVEL_CENTER_Y; + break; + case 2: + x = X_MIN_POS + lfrb[0]; + y = Y_MIN_POS + lfrb[1]; + break; + case 3: + x = X_MAX_POS - lfrb[2]; + y = Y_MIN_POS + lfrb[1]; + break; + case 4: + x = X_MAX_POS - lfrb[2]; + y = Y_MAX_POS - lfrb[3]; + break; + case 5: + x = X_MIN_POS + lfrb[0]; + y = Y_MAX_POS - lfrb[3]; + break; + } + + if (ExtUI::getAxisPosition_mm(ExtUI::Z) < Z_MIN_POS + LEVEL_CORNERS_Z_HOP) { + ExtUI::setAxisPosition_mm(Z_MIN_POS + LEVEL_CORNERS_Z_HOP, ExtUI::Z); + } + ExtUI::setAxisPosition_mm(x, ExtUI::X); + ExtUI::setAxisPosition_mm(y, ExtUI::Y); + ExtUI::setAxisPosition_mm(Z_MIN_POS + LEVEL_CORNERS_HEIGHT, ExtUI::Z); +} + +void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + #if ENABLED(MESH_BED_LEVELING) + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_ABL_REQUIRED); + return; + #endif + + if (!ExtUI::isPositionKnown()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::LEVELING_PROBING); + + #if ENABLED(AUTO_BED_LEVELING_UBL) + queue.enqueue_now_P(PSTR("G29P1\nG29P3\nG29P5C")); + #else + queue.enqueue_now_P(PSTR("G29")); + #endif + queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); +} + +void DGUSRxHandler::DisableABL(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + ExtUI::setLevelingActive(false); + + dgus_screen_handler.TriggerEEPROMSave(); + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::FilamentSelect(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Extruder extruder = (DGUS_Data::Extruder)Swap16(*(uint16_t*)data_ptr); + + switch (extruder) { + default: return; + case DGUS_Data::Extruder::CURRENT: + case DGUS_Data::Extruder::E0: + #if EXTRUDERS > 1 + case DGUS_Data::Extruder::E1: + #endif + dgus_screen_handler.filament_extruder = extruder; + break; + } + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::FilamentLength(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const uint16_t length = Swap16(*(uint16_t*)data_ptr); + + dgus_screen_handler.filament_length = constrain(length, 0, EXTRUDE_MAXLENGTH); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + ExtUI::extruder_t extruder; + + switch (dgus_screen_handler.filament_extruder) { + default: return; + case DGUS_Data::Extruder::CURRENT: + #if EXTRUDERS > 1 + extruder = ExtUI::getActiveTool(); + break; + #endif + case DGUS_Data::Extruder::E0: + extruder = ExtUI::E0; + break; + #if EXTRUDERS > 1 + case DGUS_Data::Extruder::E1: + extruder = ExtUI::E1; + break; + #endif + } + + if (ExtUI::getActualTemp_celsius(extruder) < (float)EXTRUDE_MINTEMP) { + dgus_screen_handler.SetStatusMessagePGM(PSTR("Temperature too low")); + return; + } + + const DGUS_Data::FilamentMove move = (DGUS_Data::FilamentMove)((uint8_t*)data_ptr)[1]; + + switch (move) { + case DGUS_Data::FilamentMove::RETRACT: + UI_DECREMENT_BY(AxisPosition_mm, (float)dgus_screen_handler.filament_length, extruder); + break; + case DGUS_Data::FilamentMove::EXTRUDE: + UI_INCREMENT_BY(AxisPosition_mm, (float)dgus_screen_handler.filament_length, extruder); + break; + } +} + +void DGUSRxHandler::Home(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + DGUS_Data::Axis axis = (DGUS_Data::Axis)((uint8_t*)data_ptr)[1]; + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(DGUS_MSG_HOMING, 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(dgus_screen_handler.GetCurrentScreen()); + + switch (axis) { + case DGUS_Data::Axis::X_Y_Z: + queue.enqueue_now_P(PSTR("G28XYZ")); + break; + case DGUS_Data::Axis::X_Y: + queue.enqueue_now_P(PSTR("G28XY")); + break; + case DGUS_Data::Axis::Z: + queue.enqueue_now_P(PSTR("G28Z")); + break; + } +} + +void DGUSRxHandler::Move(DGUS_VP &vp, void *data_ptr) { + const int16_t data = Swap16(*(int16_t*)data_ptr); + const float position = dgus_display.FromFixedPoint(data); + ExtUI::axis_t axis; + + switch (vp.addr) { + default: return; + case DGUS_Addr::MOVE_SetX: + axis = ExtUI::X; + break; + case DGUS_Addr::MOVE_SetY: + axis = ExtUI::Y; + break; + case DGUS_Addr::MOVE_SetZ: + axis = ExtUI::Z; + break; + } + + if (!ExtUI::isAxisPositionKnown(axis)) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + ExtUI::setAxisPosition_mm(position, axis); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::MoveStep(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + float offset; + + switch (dgus_screen_handler.move_steps) { + default: return; + case DGUS_Data::StepSize::MM10: + offset = 10.0f; + break; + case DGUS_Data::StepSize::MM1: + offset = 1.0f; + break; + case DGUS_Data::StepSize::MMP1: + offset = 0.1f; + break; + } + + const DGUS_Data::MoveDirection direction = (DGUS_Data::MoveDirection)((uint8_t*)data_ptr)[1]; + ExtUI::axis_t axis; + + switch (direction) { + default: return; + case DGUS_Data::MoveDirection::XP: + axis = ExtUI::X; + break; + case DGUS_Data::MoveDirection::XM: + axis = ExtUI::X; + offset = -offset; + break; + case DGUS_Data::MoveDirection::YP: + axis = ExtUI::Y; + break; + case DGUS_Data::MoveDirection::YM: + axis = ExtUI::Y; + offset = -offset; + break; + case DGUS_Data::MoveDirection::ZP: + axis = ExtUI::Z; + break; + case DGUS_Data::MoveDirection::ZM: + axis = ExtUI::Z; + offset = -offset; + break; + } + + if (!ExtUI::isAxisPositionKnown(axis)) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + return; + } + + UI_INCREMENT_BY(AxisPosition_mm, offset, axis); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::MoveSetStep(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::StepSize size = (DGUS_Data::StepSize)((uint8_t*)data_ptr)[1]; + + dgus_screen_handler.move_steps = size; + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::GcodeClear(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + ZERO(dgus_screen_handler.gcode); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::GcodeExecute(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + if (!strlen(dgus_screen_handler.gcode)) { + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(PSTR("Executing command..."), 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(DGUS_Screen::GCODE); + + queue.enqueue_one_now(dgus_screen_handler.gcode); +} + +void DGUSRxHandler::ResetEEPROM(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + queue.enqueue_now_P(PSTR("M502")); + queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); +} + +void DGUSRxHandler::SettingsExtra(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Extra extra = (DGUS_Data::Extra)((uint8_t*)data_ptr)[1]; + + switch (extra) { + default: return; + case DGUS_Data::Extra::BUTTON1: + #if ENABLED(BLTOUCH) + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + queue.enqueue_now_P(PSTR(DGUS_RESET_BLTOUCH)); + #else + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::INFOS); + #endif + break; + #if ENABLED(BLTOUCH) + case DGUS_Data::Extra::BUTTON2: + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::INFOS); + break; + #endif + } +} + +void DGUSRxHandler::PIDSelect(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Heater heater = (DGUS_Data::Heater)Swap16(*(uint16_t*)data_ptr); + + switch (heater) { + default: return; + case DGUS_Data::Heater::BED: + dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_BED; + dgus_screen_handler.pid_heater = heater; + break; + case DGUS_Data::Heater::H0: + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + #endif + dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_HOTEND; + dgus_screen_handler.pid_heater = heater; + break; + } + + dgus_screen_handler.pid_cycles = 5; + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::PIDSetTemp(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + uint16_t temp = Swap16(*(uint16_t*)data_ptr); + + switch (dgus_screen_handler.pid_heater) { + default: return; + case DGUS_Data::Heater::BED: + temp = constrain(temp, BED_MINTEMP, BED_MAX_TARGET); + break; + case DGUS_Data::Heater::H0: + temp = constrain(temp, HEATER_0_MINTEMP, (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT)); + break; + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + temp = constrain(temp, HEATER_1_MINTEMP, (HEATER_1_MAXTEMP - HOTEND_OVERSHOOT)); + break; + #endif + } + + dgus_screen_handler.pid_temp = temp; + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + heater_id_t heater; + uint8_t cycles = constrain(dgus_screen_handler.pid_cycles, 3, 10); + + switch (dgus_screen_handler.pid_heater) { + default: return; + case DGUS_Data::Heater::BED: + #if ENABLED(PIDTEMPBED) + heater = H_BED; + break; + #else + dgus_screen_handler.SetStatusMessagePGM(PSTR("Bed PID disabled")); + return; + #endif + case DGUS_Data::Heater::H0: + #if ENABLED(PIDTEMP) + heater = H_E0; + break; + #else + dgus_screen_handler.SetStatusMessagePGM(PSTR("PID disabled")); + return; + #endif + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + #if ENABLED(PIDTEMP) + heater = H_E1; + break; + #else + dgus_screen_handler.SetStatusMessagePGM(PSTR("PID disabled")); + return; + #endif + #endif + } + + char buffer[24]; + snprintf_P(buffer, sizeof(buffer), PSTR("M303C%dE%dS%dU1"), cycles, heater, dgus_screen_handler.pid_temp); + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(PSTR("PID autotuning..."), 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(DGUS_Screen::PID); + + queue.enqueue_one_now(buffer); + queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); +} + +#if ENABLED(POWER_LOSS_RECOVERY) + void DGUSRxHandler::PowerLossAbort(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::HOME); + + queue.enqueue_now_P(PSTR("M1000C")); + } + + void DGUSRxHandler::PowerLossResume(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return; + } + + if (!recovery.valid()) { + dgus_screen_handler.SetStatusMessagePGM(PSTR("Invalid recovery data")); + return; + } + + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); + + queue.enqueue_now_P(PSTR("M1000")); + } +#endif // POWER_LOSS_RECOVERY + +void DGUSRxHandler::WaitAbort(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; + + if (result != DGUS_Data::Popup::CONFIRMED) { + return; + } + + if (!printingIsPaused() + #if ENABLED(ADVANCED_PAUSE_FEATURE) + || !did_pause_print + #endif + ) { + dgus_screen_handler.TriggerFullUpdate(); + return; + } + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + did_pause_print = 0; + #endif + + ExtUI::setUserConfirmed(); + ExtUI::stopPrint(); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::WaitContinue(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + ExtUI::setUserConfirmed(); + + dgus_screen_handler.TriggerFullUpdate(); +} + +void DGUSRxHandler::FanSpeed(DGUS_VP &vp, void *data_ptr) { + uint8_t speed = ((uint8_t*)data_ptr)[1]; + switch (vp.addr) { + default: return; + case DGUS_Addr::FAN0_Speed: + ExtUI::setTargetFan_percent(speed, ExtUI::FAN0); + break; + } +} + +void DGUSRxHandler::Volume(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + uint8_t volume = ((uint8_t*)data_ptr)[1]; + dgus_display.SetVolume(volume); + + dgus_screen_handler.TriggerEEPROMSave(); +} + +void DGUSRxHandler::Brightness(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + + uint8_t brightness = ((uint8_t*)data_ptr)[1]; + dgus_display.SetBrightness(brightness); + + dgus_screen_handler.TriggerEEPROMSave(); +} + +void DGUSRxHandler::Debug(DGUS_VP &vp, void *data_ptr) { + UNUSED(vp); + UNUSED(data_ptr); + + ++dgus_screen_handler.debug_count; + + if (dgus_screen_handler.debug_count >= 10) { + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::DEBUG); + } +} + +void DGUSRxHandler::StringToExtra(DGUS_VP &vp, void *data_ptr) { + if (!vp.size || !vp.extra) return; + memcpy(vp.extra, data_ptr, vp.size); +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h new file mode 100644 index 0000000000..d092d3a5b7 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h @@ -0,0 +1,123 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "DGUSDisplay.h" +#include "definition/DGUS_VP.h" + +namespace DGUSRxHandler { + + void ScreenChange(DGUS_VP &, void *); + + #if ENABLED(SDSUPPORT) + void Scroll(DGUS_VP &, void *); + void SelectFile(DGUS_VP &, void *); + void PrintFile(DGUS_VP &, void *); + #endif + + void PrintAbort(DGUS_VP &, void *); + void PrintPause(DGUS_VP &, void *); + void PrintResume(DGUS_VP &, void *); + + void Feedrate(DGUS_VP &, void *); + void Flowrate(DGUS_VP &, void *); + void BabystepSet(DGUS_VP &, void *); + void Babystep(DGUS_VP &, void *); + + void TempPreset(DGUS_VP &, void *); + void TempTarget(DGUS_VP &, void *); + void TempCool(DGUS_VP &, void *); + + void Steppers(DGUS_VP &, void *); + + void ZOffset(DGUS_VP &, void *); + void ZOffsetStep(DGUS_VP &, void *); + void ZOffsetSetStep(DGUS_VP &, void *); + + void MoveToPoint(DGUS_VP &, void *); + + void Probe(DGUS_VP &, void *); + void DisableABL(DGUS_VP &, void *); + + void FilamentSelect(DGUS_VP &, void *); + void FilamentLength(DGUS_VP &, void *); + void FilamentMove(DGUS_VP &, void *); + + void Home(DGUS_VP &, void *); + void Move(DGUS_VP &, void *); + void MoveStep(DGUS_VP &, void *); + void MoveSetStep(DGUS_VP &, void *); + + void GcodeClear(DGUS_VP &, void *); + void GcodeExecute(DGUS_VP &, void *); + + void ResetEEPROM(DGUS_VP &, void *); + + void SettingsExtra(DGUS_VP &, void *); + + void PIDSelect(DGUS_VP &, void *); + void PIDSetTemp(DGUS_VP &, void *); + void PIDRun(DGUS_VP &, void *); + + #if ENABLED(POWER_LOSS_RECOVERY) + void PowerLossAbort(DGUS_VP &, void *); + void PowerLossResume(DGUS_VP &, void *); + #endif + + void WaitAbort(DGUS_VP &, void *); + void WaitContinue(DGUS_VP &, void *); + + void FanSpeed(DGUS_VP &, void *); + + void Volume(DGUS_VP &, void *); + + void Brightness(DGUS_VP &, void *); + + void Debug(DGUS_VP &, void *); + + void StringToExtra(DGUS_VP &, void *); + + template + void IntegerToExtra(DGUS_VP &vp, void *data_ptr) { + if (!vp.size || !vp.extra) return; + switch (vp.size) { + default: return; + case 1: { + const uint8_t data = *(uint8_t*)data_ptr; + *(T*)vp.extra = (T)data; + break; + } + case 2: { + const uint16_t data = Swap16(*(uint16_t*)data_ptr); + *(T*)vp.extra = (T)data; + break; + } + case 4: { + const uint32_t data = dgus_display.SwapBytes(*(uint32_t*)data_ptr); + *(T*)vp.extra = (T)data; + break; + } + } + } + +} diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp new file mode 100644 index 0000000000..6316f1194b --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -0,0 +1,540 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUSScreenHandler.h" + +#include "DGUSDisplay.h" +#include "definition/DGUS_ScreenAddrList.h" +#include "definition/DGUS_ScreenSetup.h" + +#include "../../../gcode/queue.h" + +uint8_t DGUSScreenHandler::debug_count = 0; + +#if ENABLED(SDSUPPORT) + ExtUI::FileList DGUSScreenHandler::filelist; + uint16_t DGUSScreenHandler::filelist_offset = 0; + int16_t DGUSScreenHandler::filelist_selected = -1; +#endif + +DGUS_Data::StepSize DGUSScreenHandler::offset_steps = DGUS_Data::StepSize::MMP1; +DGUS_Data::StepSize DGUSScreenHandler::move_steps = DGUS_Data::StepSize::MM10; + +uint16_t DGUSScreenHandler::probing_icons[] = { 0, 0 }; + +DGUS_Data::Extruder DGUSScreenHandler::filament_extruder = DGUS_Data::Extruder::CURRENT; +uint16_t DGUSScreenHandler::filament_length = DGUS_DEFAULT_FILAMENT_LEN; + +char DGUSScreenHandler::gcode[] = ""; + +DGUS_Data::Heater DGUSScreenHandler::pid_heater = DGUS_Data::Heater::H0; +uint16_t DGUSScreenHandler::pid_temp = DGUS_PLA_TEMP_HOTEND; +uint8_t DGUSScreenHandler::pid_cycles = 5; + +bool DGUSScreenHandler::settings_ready = false; +bool DGUSScreenHandler::booted = false; + +DGUS_Screen DGUSScreenHandler::current_screen = DGUS_Screen::BOOT; +DGUS_Screen DGUSScreenHandler::new_screen = DGUS_Screen::BOOT; +bool DGUSScreenHandler::full_update = false; + +DGUS_Screen DGUSScreenHandler::wait_return_screen = DGUS_Screen::HOME; +bool DGUSScreenHandler::wait_continue = false; + +bool DGUSScreenHandler::leveling_active = false; + +millis_t DGUSScreenHandler::status_expire = 0; +millis_t DGUSScreenHandler::eeprom_save = 0; + +const char DGUS_MSG_HOMING_REQUIRED[] PROGMEM = "Homing required", + DGUS_MSG_BUSY[] PROGMEM = "Busy", + DGUS_MSG_UNDEF[] PROGMEM = "-", + DGUS_MSG_HOMING[] PROGMEM = "Homing...", + DGUS_MSG_FW_OUTDATED[] PROGMEM = "DWIN GUI/OS update required", + DGUS_MSG_ABL_REQUIRED[] PROGMEM = "Auto bed leveling required"; + +const char DGUS_CMD_HOME[] PROGMEM = "G28", + DGUS_CMD_EEPROM_SAVE[] PROGMEM = "M500"; + +void DGUSScreenHandler::Init() { + dgus_display.Init(); + + MoveToScreen(DGUS_Screen::BOOT, true); +} + +void DGUSScreenHandler::Ready() { + dgus_display.PlaySound(1); +} + +void DGUSScreenHandler::Loop() { + if (!settings_ready || current_screen == DGUS_Screen::KILL) { + return; + } + + const millis_t ms = ExtUI::safe_millis(); + static millis_t next_event_ms = 0; + + if (new_screen != DGUS_Screen::BOOT) { + const DGUS_Screen screen = new_screen; + new_screen = DGUS_Screen::BOOT; + + if (current_screen == screen) { + TriggerFullUpdate(); + } + else { + MoveToScreen(screen); + } + return; + } + + if (!booted && ELAPSED(ms, 3000)) { + booted = true; + + if (current_screen == DGUS_Screen::BOOT) { + MoveToScreen(DGUS_Screen::HOME); + } + return; + } + + if (ELAPSED(ms, next_event_ms) || full_update) { + next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; + + if (!SendScreenVPData(current_screen, full_update)) { + DEBUG_ECHOLNPGM("SendScreenVPData failed"); + } + return; + } + + if (current_screen == DGUS_Screen::WAIT + && ((wait_continue && !wait_for_user) + || (!wait_continue && IsPrinterIdle()))) { + MoveToScreen(wait_return_screen, true); + return; + } + + if (current_screen == DGUS_Screen::LEVELING_PROBING + && IsPrinterIdle()) { + dgus_display.PlaySound(3); + + SetStatusMessagePGM(ExtUI::getMeshValid() ? + PSTR("Probing successful") + : PSTR("Probing failed")); + + MoveToScreen(DGUS_Screen::LEVELING_AUTOMATIC); + return; + } + + if (status_expire > 0 && ELAPSED(ms, status_expire)) { + SetStatusMessagePGM(NUL_STR, 0); + return; + } + + if (eeprom_save > 0 && ELAPSED(ms, eeprom_save) && IsPrinterIdle()) { + eeprom_save = 0; + + queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); + return; + } + + dgus_display.Loop(); +} + +void DGUSScreenHandler::PrinterKilled(PGM_P error, PGM_P component) { + SetMessageLinePGM(error, 1); + SetMessageLinePGM(component, 2); + SetMessageLinePGM(NUL_STR, 3); + SetMessageLinePGM(GET_TEXT(MSG_PLEASE_RESET), 4); + + dgus_display.PlaySound(3, 1, 200); + + MoveToScreen(DGUS_Screen::KILL, true); +} + +void DGUSScreenHandler::UserConfirmRequired(const char * const msg) { + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLine(msg, 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + + dgus_display.PlaySound(3); + + dgus_screen_handler.ShowWaitScreen(current_screen, true); +} + +void DGUSScreenHandler::SettingsReset() { + dgus_display.SetVolume(DGUS_DEFAULT_VOLUME); + dgus_display.SetBrightness(DGUS_DEFAULT_BRIGHTNESS); + + if (!settings_ready) { + settings_ready = true; + + Ready(); + } + + SetStatusMessagePGM(PSTR("EEPROM reset")); +} + +void DGUSScreenHandler::StoreSettings(char *buff) { + eeprom_data_t data; + + static_assert(sizeof(data) <= ExtUI::eeprom_data_size, "sizeof(eeprom_data_t) > eeprom_data_size."); + + data.initialized = true; + data.volume = dgus_display.GetVolume(); + data.brightness = dgus_display.GetBrightness(); + data.abl = (ExtUI::getLevelingActive() && ExtUI::getMeshValid()); + + memcpy(buff, &data, sizeof(data)); +} + +void DGUSScreenHandler::LoadSettings(const char *buff) { + eeprom_data_t data; + + static_assert(sizeof(data) <= ExtUI::eeprom_data_size, "sizeof(eeprom_data_t) > eeprom_data_size."); + + memcpy(&data, buff, sizeof(data)); + + dgus_display.SetVolume(data.initialized ? data.volume : DGUS_DEFAULT_VOLUME); + dgus_display.SetBrightness(data.initialized ? data.brightness : DGUS_DEFAULT_BRIGHTNESS); + + if (data.initialized) { + leveling_active = (data.abl && ExtUI::getMeshValid()); + + ExtUI::setLevelingActive(leveling_active); + } +} + +void DGUSScreenHandler::ConfigurationStoreWritten(bool success) { + if (!success) { + SetStatusMessagePGM(PSTR("EEPROM write failed")); + } +} + +void DGUSScreenHandler::ConfigurationStoreRead(bool success) { + if (!success) { + SetStatusMessagePGM(PSTR("EEPROM read failed")); + } + else if (!settings_ready) { + settings_ready = true; + + Ready(); + } +} + +void DGUSScreenHandler::PlayTone(const uint16_t frequency, const uint16_t duration) { + UNUSED(duration); + + if (frequency >= 1 && frequency <= 255) { + if (duration >= 1 && duration <= 255) { + dgus_display.PlaySound((uint8_t)frequency, (uint8_t)duration); + } + else { + dgus_display.PlaySound((uint8_t)frequency); + } + } +} + +void DGUSScreenHandler::MeshUpdate(const int8_t xpos, const int8_t ypos) { + if (current_screen != DGUS_Screen::LEVELING_PROBING) { + if (current_screen == DGUS_Screen::LEVELING_AUTOMATIC) { + TriggerFullUpdate(); + } + + return; + } + + uint8_t point = ypos * GRID_MAX_POINTS_X + xpos; + probing_icons[point < 16 ? 0 : 1] |= (1U << (point % 16)); + + if (xpos >= GRID_MAX_POINTS_X - 1 + && ypos >= GRID_MAX_POINTS_Y - 1 + && !ExtUI::getMeshValid()) { + probing_icons[0] = 0; + probing_icons[1] = 0; + } + + TriggerFullUpdate(); +} + +void DGUSScreenHandler::PrintTimerStarted() { + TriggerScreenChange(DGUS_Screen::PRINT_STATUS); +} + +void DGUSScreenHandler::PrintTimerPaused() { + dgus_display.PlaySound(3); + + TriggerFullUpdate(); +} + +void DGUSScreenHandler::PrintTimerStopped() { + if (current_screen != DGUS_Screen::PRINT_STATUS + && current_screen != DGUS_Screen::PRINT_ADJUST) { + return; + } + + dgus_display.PlaySound(3); + + TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); +} + +void DGUSScreenHandler::FilamentRunout(const ExtUI::extruder_t extruder) { + char buffer[21]; + snprintf_P(buffer, sizeof(buffer), PSTR("Filament runout E%d"), extruder); + + SetStatusMessage(buffer); + + dgus_display.PlaySound(3); +} + +#if ENABLED(SDSUPPORT) + + void DGUSScreenHandler::SDCardInserted() { + if (current_screen == DGUS_Screen::HOME) { + TriggerScreenChange(DGUS_Screen::PRINT); + } + } + + void DGUSScreenHandler::SDCardRemoved() { + if (current_screen == DGUS_Screen::PRINT) { + TriggerScreenChange(DGUS_Screen::HOME); + } + } + + void DGUSScreenHandler::SDCardError() { + SetStatusMessagePGM(GET_TEXT(MSG_MEDIA_READ_ERROR)); + + if (current_screen == DGUS_Screen::PRINT) { + TriggerScreenChange(DGUS_Screen::HOME); + } + } + +#endif // SDSUPPORT + +#if ENABLED(POWER_LOSS_RECOVERY) + + void DGUSScreenHandler::PowerLossResume() { + MoveToScreen(DGUS_Screen::POWERLOSS, true); + } + +#endif // POWER_LOSS_RECOVERY + +#if HAS_PID_HEATING + + void DGUSScreenHandler::PidTuning(const ExtUI::result_t rst) { + switch (rst) { + case ExtUI::PID_STARTED: + SetStatusMessagePGM(GET_TEXT(MSG_PID_AUTOTUNE)); + break; + case ExtUI::PID_BAD_EXTRUDER_NUM: + SetStatusMessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + break; + case ExtUI::PID_TEMP_TOO_HIGH: + SetStatusMessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + break; + case ExtUI::PID_TUNING_TIMEOUT: + SetStatusMessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); + break; + case ExtUI::PID_DONE: + SetStatusMessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + break; + default: + return; + } + + dgus_display.PlaySound(3); + } + +#endif // HAS_PID_HEATING + +void DGUSScreenHandler::SetMessageLine(const char* msg, uint8_t line) { + switch (line) { + default: return; + case 1: + dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); + break; + case 2: + dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); + break; + case 3: + dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); + break; + case 4: + dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); + break; + } +} + +void DGUSScreenHandler::SetMessageLinePGM(PGM_P msg, uint8_t line) { + switch (line) { + default: return; + case 1: + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); + break; + case 2: + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); + break; + case 3: + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); + break; + case 4: + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); + break; + } +} + +void DGUSScreenHandler::SetStatusMessage(const char* msg, const millis_t duration) { + dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Status, msg, DGUS_STATUS_LEN, false, true); + + status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); +} + +void DGUSScreenHandler::SetStatusMessagePGM(PGM_P msg, const millis_t duration) { + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Status, msg, DGUS_STATUS_LEN, false, true); + + status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); +} + +void DGUSScreenHandler::ShowWaitScreen(DGUS_Screen return_screen, bool has_continue) { + if (return_screen != DGUS_Screen::WAIT) { + wait_return_screen = return_screen; + } + wait_continue = has_continue; + + TriggerScreenChange(DGUS_Screen::WAIT); +} + +DGUS_Screen DGUSScreenHandler::GetCurrentScreen() { + return current_screen; +} + +void DGUSScreenHandler::TriggerScreenChange(DGUS_Screen screen) { + new_screen = screen; +} + +void DGUSScreenHandler::TriggerFullUpdate() { + full_update = true; +} + +void DGUSScreenHandler::TriggerEEPROMSave() { + eeprom_save = ExtUI::safe_millis() + 500; +} + +bool DGUSScreenHandler::IsPrinterIdle() { + return (!ExtUI::commandsInQueue() + && !ExtUI::isMoving()); +} + +const DGUS_Addr* DGUSScreenHandler::FindScreenAddrList(DGUS_Screen screen) { + DGUS_ScreenAddrList list; + const DGUS_ScreenAddrList *map = screen_addr_list_map; + + do { + memcpy_P(&list, map, sizeof(*map)); + if (!list.addr_list) break; + if (list.screen == screen) { + return list.addr_list; + } + } while (++map); + + return nullptr; +} + +bool DGUSScreenHandler::CallScreenSetup(DGUS_Screen screen) { + DGUS_ScreenSetup setup; + const DGUS_ScreenSetup *list = screen_setup_list; + + do { + memcpy_P(&setup, list, sizeof(*list)); + if (!setup.setup_fn) break; + if (setup.screen == screen) { + return setup.setup_fn(); + } + } while (++list); + + return true; +} + +void DGUSScreenHandler::MoveToScreen(DGUS_Screen screen, bool abort_wait) { + if (current_screen == DGUS_Screen::KILL) { + return; + } + + if (current_screen == DGUS_Screen::WAIT) { + if (screen != DGUS_Screen::WAIT) { + wait_return_screen = screen; + } + + if (!abort_wait) return; + + if (wait_continue && wait_for_user) { + ExtUI::setUserConfirmed(); + } + } + + if (!CallScreenSetup(screen)) return; + + if (!SendScreenVPData(screen, true)) { + DEBUG_ECHOLNPGM("SendScreenVPData failed"); + return; + } + + current_screen = screen; + dgus_display.SwitchScreen(current_screen); +} + +bool DGUSScreenHandler::SendScreenVPData(DGUS_Screen screen, bool complete_update) { + if (complete_update) { + full_update = false; + } + + const DGUS_Addr *list = FindScreenAddrList(screen); + + while (true) { + if (!list) return true; // Nothing left to send + + const uint16_t addr = pgm_read_word(list++); + if (!addr) return true; // Nothing left to send + + DGUS_VP vp; + if (!DGUS_PopulateVP((DGUS_Addr)addr, &vp)) continue; // Invalid VP + if (!vp.tx_handler) continue; // Nothing to send + if (!complete_update && !(vp.flags & VPFLAG_AUTOUPLOAD)) continue; // Unnecessary VP + + uint8_t expected_tx = 6 + vp.size; // 6 bytes header + payload. + const millis_t try_until = ExtUI::safe_millis() + 1000; + + while (expected_tx > dgus_display.GetFreeTxBuffer()) { + if (ELAPSED(ExtUI::safe_millis(), try_until)) return false; // Stop trying after 1 second + + dgus_display.FlushTx(); // Flush the TX buffer + delay(50); + } + + vp.tx_handler(vp); + } +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h new file mode 100644 index 0000000000..056757fedf --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -0,0 +1,152 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "config/DGUS_Addr.h" +#include "config/DGUS_Data.h" +#include "config/DGUS_Screen.h" +#include "config/DGUS_Constants.h" + +#include "../ui_api.h" +#include "../../../inc/MarlinConfigPre.h" + +class DGUSScreenHandler { +public: + DGUSScreenHandler() = default; + + static void Init(); + static void Ready(); + static void Loop(); + + static void PrinterKilled(PGM_P error, PGM_P component); + static void UserConfirmRequired(const char * const msg); + static void SettingsReset(); + static void StoreSettings(char *buff); + static void LoadSettings(const char *buff); + static void ConfigurationStoreWritten(bool success); + static void ConfigurationStoreRead(bool success); + + static void PlayTone(const uint16_t frequency, const uint16_t duration); + static void MeshUpdate(const int8_t xpos, const int8_t ypos); + static void PrintTimerStarted(); + static void PrintTimerPaused(); + static void PrintTimerStopped(); + static void FilamentRunout(const ExtUI::extruder_t extruder); + + #if ENABLED(SDSUPPORT) + /// Marlin informed us that a new SD has been inserted. + static void SDCardInserted(); + /// Marlin informed us that the SD Card has been removed(). + static void SDCardRemoved(); + /// Marlin informed us about a bad SD Card. + static void SDCardError(); + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + static void PowerLossResume(); + #endif + + #if HAS_PID_HEATING + static void PidTuning(const ExtUI::result_t rst); + #endif + + static void SetMessageLine(const char* msg, uint8_t line); + static void SetMessageLinePGM(PGM_P msg, uint8_t line); + + static void SetStatusMessage(const char* msg, const millis_t duration = DGUS_STATUS_EXPIRATION_MS); + static void SetStatusMessagePGM(PGM_P msg, const millis_t duration = DGUS_STATUS_EXPIRATION_MS); + + static void ShowWaitScreen(DGUS_Screen return_screen, bool has_continue = false); + + static DGUS_Screen GetCurrentScreen(); + static void TriggerScreenChange(DGUS_Screen screen); + static void TriggerFullUpdate(); + + static void TriggerEEPROMSave(); + + static bool IsPrinterIdle(); + + static uint8_t debug_count; + + #if ENABLED(SDSUPPORT) + static ExtUI::FileList filelist; + static uint16_t filelist_offset; + static int16_t filelist_selected; + #endif + + static DGUS_Data::StepSize offset_steps; + static DGUS_Data::StepSize move_steps; + + static uint16_t probing_icons[2]; + + static DGUS_Data::Extruder filament_extruder; + static uint16_t filament_length; + + static char gcode[DGUS_GCODE_LEN + 1]; + + static DGUS_Data::Heater pid_heater; + static uint16_t pid_temp; + static uint8_t pid_cycles; + + static bool wait_continue; + + static bool leveling_active; + +private: + static const DGUS_Addr* FindScreenAddrList(DGUS_Screen screen); + static bool CallScreenSetup(DGUS_Screen screen); + + static void MoveToScreen(DGUS_Screen screen, bool abort_wait = false); + static bool SendScreenVPData(DGUS_Screen screen, bool complete_update); + + static bool settings_ready; + static bool booted; + + static DGUS_Screen current_screen; + static DGUS_Screen new_screen; + static bool full_update; + + static DGUS_Screen wait_return_screen; + + static millis_t status_expire; + static millis_t eeprom_save; + + typedef struct { + bool initialized; + uint8_t volume; + uint8_t brightness; + bool abl; + } eeprom_data_t; +}; + +extern DGUSScreenHandler dgus_screen_handler; + +extern const char DGUS_MSG_HOMING_REQUIRED[], + DGUS_MSG_BUSY[], + DGUS_MSG_UNDEF[], + DGUS_MSG_HOMING[], + DGUS_MSG_FW_OUTDATED[], + DGUS_MSG_ABL_REQUIRED[]; + +extern const char DGUS_CMD_HOME[], + DGUS_CMD_EEPROM_SAVE[]; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp new file mode 100644 index 0000000000..c12282c4ef --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -0,0 +1,209 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUSSetupHandler.h" + +#include "DGUSDisplay.h" +#include "DGUSScreenHandler.h" + +#include "../../../gcode/queue.h" + +#if ENABLED(SDSUPPORT) + bool DGUSSetupHandler::Print() { + dgus_screen_handler.filelist.refresh(); + + while (!dgus_screen_handler.filelist.isAtRootDir()) { + dgus_screen_handler.filelist.upDir(); + } + + dgus_screen_handler.filelist_offset = 0; + dgus_screen_handler.filelist_selected = -1; + + return true; + } +#endif + +bool DGUSSetupHandler::PrintStatus() { + if (printingIsActive() || printingIsPaused()) { + return true; + } + + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); + return false; +} + +bool DGUSSetupHandler::PrintAdjust() { + if (printingIsActive() || printingIsPaused()) { + return true; + } + + dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); + return false; +} + +bool DGUSSetupHandler::LevelingMenu() { + ExtUI::setLevelingActive(dgus_screen_handler.leveling_active); + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return false; + } + + if (ExtUI::isPositionKnown()) { + if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 10.0f) { + queue.enqueue_now_P(PSTR("G0Z10")); + } + + return true; + } + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(DGUS_MSG_HOMING, 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(DGUS_Screen::LEVELING_MENU); + + queue.enqueue_now_P(DGUS_CMD_HOME); + + return false; +} + +bool DGUSSetupHandler::LevelingManual() { + ExtUI::setLevelingActive(false); + + if (ExtUI::isPositionKnown()) { + return true; + } + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return false; + } + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(DGUS_MSG_HOMING, 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(DGUS_Screen::LEVELING_MANUAL); + + queue.enqueue_now_P(DGUS_CMD_HOME); + + return false; +} + +bool DGUSSetupHandler::LevelingOffset() { + dgus_screen_handler.offset_steps = DGUS_Data::StepSize::MMP1; + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return false; + } + + if (ExtUI::isPositionKnown()) { + if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 4.0f) { + queue.enqueue_now_P(PSTR("G0Z4")); + } + + char buffer[20]; + snprintf_P(buffer, sizeof(buffer), PSTR("G0X%dY%d"), DGUS_LEVEL_CENTER_X, DGUS_LEVEL_CENTER_Y); + + queue.enqueue_one_now(buffer); + queue.enqueue_now_P(PSTR("G0Z0")); + + return true; + } + + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 1); + dgus_screen_handler.SetMessageLinePGM(DGUS_MSG_HOMING, 2); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 3); + dgus_screen_handler.SetMessageLinePGM(NUL_STR, 4); + dgus_screen_handler.ShowWaitScreen(DGUS_Screen::LEVELING_OFFSET); + + queue.enqueue_now_P(DGUS_CMD_HOME); + + return false; +} + +bool DGUSSetupHandler::LevelingAutomatic() { + if (ExtUI::getMeshValid()) { + dgus_screen_handler.leveling_active = true; + + ExtUI::setLevelingActive(true); + } + + return true; +} + +bool DGUSSetupHandler::LevelingProbing() { + dgus_screen_handler.probing_icons[0] = 0; + dgus_screen_handler.probing_icons[1] = 0; + + return true; +} + +bool DGUSSetupHandler::Filament() { + dgus_screen_handler.filament_extruder = DGUS_Data::Extruder::CURRENT; + dgus_screen_handler.filament_length = DGUS_DEFAULT_FILAMENT_LEN; + + return true; +} + +bool DGUSSetupHandler::Move() { + dgus_screen_handler.move_steps = DGUS_Data::StepSize::MM10; + + if (!dgus_screen_handler.IsPrinterIdle()) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + return false; + } + + return true; +} + +bool DGUSSetupHandler::Gcode() { + ZERO(dgus_screen_handler.gcode); + + if (dgus_display.gui_version < 0x30 || dgus_display.os_version < 0x21) { + dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_FW_OUTDATED); + return false; + } + + return true; +} + +bool DGUSSetupHandler::PID() { + dgus_screen_handler.pid_heater = DGUS_Data::Heater::H0; + dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_HOTEND; + + return true; +} + +bool DGUSSetupHandler::Infos() { + dgus_screen_handler.debug_count = 0; + + return true; +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h new file mode 100644 index 0000000000..b1159ff708 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h @@ -0,0 +1,43 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +namespace DGUSSetupHandler { + + #if ENABLED(SDSUPPORT) + bool Print(); + #endif + bool PrintStatus(); + bool PrintAdjust(); + bool LevelingMenu(); + bool LevelingOffset(); + bool LevelingManual(); + bool LevelingAutomatic(); + bool LevelingProbing(); + bool Filament(); + bool Move(); + bool Gcode(); + bool PID(); + bool Infos(); + +} diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp new file mode 100644 index 0000000000..04362b07e8 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -0,0 +1,632 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUSTxHandler.h" + +#include "DGUSScreenHandler.h" +#include "config/DGUS_Data.h" + +#include "../ui_api.h" +#include "../../../module/stepper.h" +#include "../../../module/printcounter.h" +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #include "../../../feature/pause.h" +#endif + +#if ENABLED(SDSUPPORT) + void DGUSTxHandler::SetFileControlState(int file, bool state) { + DGUS_Control control; + + switch (file) { + default: return; + case 0: + control = DGUS_Control::FILE0; + break; + case 1: + control = DGUS_Control::FILE1; + break; + case 2: + control = DGUS_Control::FILE2; + break; + case 3: + control = DGUS_Control::FILE3; + break; + case 4: + control = DGUS_Control::FILE4; + break; + } + + if (state) { + dgus_display.EnableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + control); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + control); + } + } + + void DGUSTxHandler::FileType(DGUS_VP &vp) { + // Batch send + uint16_t data[DGUS_FILE_COUNT]; + + for (int i = 0; i < DGUS_FILE_COUNT; i++) { + if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + i)) { + data[i] = Swap16((uint16_t)DGUS_Data::SDType::NONE); + + SetFileControlState(i, false); + continue; + } + + data[i] = dgus_screen_handler.filelist.isDir() ? + Swap16((uint16_t)DGUS_Data::SDType::DIRECTORY) + : Swap16((uint16_t)DGUS_Data::SDType::FILE); + + SetFileControlState(i, true); + } + + dgus_display.Write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_FILE_COUNT); + } + + void DGUSTxHandler::FileName(DGUS_VP &vp) { + uint8_t offset; + + switch (vp.addr) { + default: return; + case DGUS_Addr::SD_FileName0: + offset = 0; + break; + case DGUS_Addr::SD_FileName1: + offset = 1; + break; + case DGUS_Addr::SD_FileName2: + offset = 2; + break; + case DGUS_Addr::SD_FileName3: + offset = 3; + break; + case DGUS_Addr::SD_FileName4: + offset = 4; + break; + } + + if (dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + offset)) { + dgus_display.WriteString((uint16_t)vp.addr, dgus_screen_handler.filelist.filename(), vp.size); + } + else { + dgus_display.WriteStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); + } + } + + void DGUSTxHandler::ScrollIcons(DGUS_VP &vp) { + uint16_t icons = 0; + + if (!dgus_screen_handler.filelist.isAtRootDir()) { + icons |= (uint16_t)DGUS_Data::ScrollIcon::GO_BACK; + + dgus_display.EnableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::GO_BACK); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::GO_BACK); + } + + if (dgus_screen_handler.filelist_offset > 0) { + icons |= (uint16_t)DGUS_Data::ScrollIcon::UP; + + dgus_display.EnableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::SCROLL_UP); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::SCROLL_UP); + } + + if (dgus_screen_handler.filelist_offset + DGUS_FILE_COUNT < dgus_screen_handler.filelist.count()) { + icons |= (uint16_t)DGUS_Data::ScrollIcon::DOWN; + + dgus_display.EnableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::SCROLL_DOWN); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::SCROLL_DOWN); + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + } + + void DGUSTxHandler::SelectedFileName(DGUS_VP &vp) { + if (dgus_screen_handler.filelist_selected < 0 + || !dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_selected)) { + dgus_display.WriteStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); + return; + } + + dgus_display.WriteString((uint16_t)vp.addr, dgus_screen_handler.filelist.filename(), vp.size); + } +#endif // SDSUPPORT + +void DGUSTxHandler::PositionZ(DGUS_VP &vp) { + float position = ExtUI::isAxisPositionKnown(ExtUI::Z) ? + planner.get_axis_position_mm(Z_AXIS) + : 0; + + const int16_t data = dgus_display.ToFixedPoint(position); + dgus_display.Write((uint16_t)vp.addr, Swap16(data)); +} + +void DGUSTxHandler::Ellapsed(DGUS_VP &vp) { + char buffer[21]; + duration_t(print_job_timer.duration()).toString(buffer); + + dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); +} + +void DGUSTxHandler::Percent(DGUS_VP &vp) { + uint16_t progress; + + switch (vp.addr) { + default: return; + case DGUS_Addr::STATUS_Percent: + progress = constrain(ExtUI::getProgress_percent(), 0, 100); + break; + case DGUS_Addr::STATUS_Percent_Complete: + progress = 100; + break; + } + + dgus_display.Write((uint16_t)DGUS_Addr::STATUS_Percent, Swap16(progress)); +} + +void DGUSTxHandler::StatusIcons(DGUS_VP &vp) { + uint16_t icons = 0; + + if (printingIsActive()) { + icons |= (uint16_t)DGUS_Data::StatusIcon::PAUSE; + + dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::PAUSE); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT_STATUS, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::PAUSE); + } + + if (printingIsPaused()) { + icons |= (uint16_t)DGUS_Data::StatusIcon::RESUME; + + dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::RESUME); + } + else { + dgus_display.DisableControl(DGUS_Screen::PRINT_STATUS, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::RESUME); + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); +} + +void DGUSTxHandler::Flowrate(DGUS_VP &vp) { + int16_t flowrate; + + switch (vp.addr) { + default: return; + case DGUS_Addr::ADJUST_Flowrate_CUR: + #if EXTRUDERS > 1 + flowrate = ExtUI::getFlow_percent(ExtUI::getActiveTool()); + #else + flowrate = ExtUI::getFlow_percent(ExtUI::E0); + #endif + break; + #if EXTRUDERS > 1 + case DGUS_Addr::ADJUST_Flowrate_E0: + flowrate = ExtUI::getFlow_percent(ExtUI::E0); + break; + case DGUS_Addr::ADJUST_Flowrate_E1: + flowrate = ExtUI::getFlow_percent(ExtUI::E1); + break; + #endif + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(flowrate)); +} + +void DGUSTxHandler::TempMax(DGUS_VP &vp) { + uint16_t temp; + + switch (vp.addr) { + default: return; + case DGUS_Addr::TEMP_Max_Bed: + temp = BED_MAX_TARGET; + break; + case DGUS_Addr::TEMP_Max_H0: + temp = HEATER_0_MAXTEMP - HOTEND_OVERSHOOT; + break; + #if HOTENDS > 1 + case DGUS_Addr::TEMP_Max_H1: + temp = HEATER_1_MAXTEMP - HOTEND_OVERSHOOT; + break; + #endif + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(temp)); +} + +void DGUSTxHandler::StepperStatus(DGUS_VP &vp) { + if (X_ENABLE_READ() == X_ENABLE_ON + && Y_ENABLE_READ() == Y_ENABLE_ON + && Z_ENABLE_READ() == Z_ENABLE_ON) { + dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::ENABLED)); + } + else { + dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::DISABLED)); + } +} + +void DGUSTxHandler::StepIcons(DGUS_VP &vp) { + if (!vp.extra) return; + uint16_t icons = 0; + DGUS_Data::StepSize size = *(DGUS_Data::StepSize*)vp.extra; + + switch (size) { + case DGUS_Data::StepSize::MM10: + icons |= (uint16_t)DGUS_Data::StepIcon::MM10; + break; + case DGUS_Data::StepSize::MM1: + icons |= (uint16_t)DGUS_Data::StepIcon::MM1; + break; + case DGUS_Data::StepSize::MMP1: + icons |= (uint16_t)DGUS_Data::StepIcon::MMP1; + break; + case DGUS_Data::StepSize::MMP01: + icons |= (uint16_t)DGUS_Data::StepIcon::MMP01; + break; + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); +} + +void DGUSTxHandler::ABLDisableIcon(DGUS_VP &vp) { + uint16_t data; + + if (ExtUI::getLevelingActive()) { + data = (uint16_t)DGUS_Data::Status::ENABLED; + + dgus_display.EnableControl(DGUS_Screen::LEVELING_AUTOMATIC, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::DISABLE); + } + else { + data = (uint16_t)DGUS_Data::Status::DISABLED; + + dgus_display.DisableControl(DGUS_Screen::LEVELING_AUTOMATIC, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::DISABLE); + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(data)); +} + +void DGUSTxHandler::ABLGrid(DGUS_VP &vp) { + // Batch send + int16_t data[DGUS_LEVEL_GRID_SIZE]; + xy_uint8_t point; + int16_t fixed; + + for (int i = 0; i < DGUS_LEVEL_GRID_SIZE; i++) { + point.x = i % GRID_MAX_POINTS_X; + point.y = i / GRID_MAX_POINTS_X; + fixed = dgus_display.ToFixedPoint(ExtUI::getMeshPoint(point)); + data[i] = Swap16(fixed); + } + + dgus_display.Write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_LEVEL_GRID_SIZE); +} + +void DGUSTxHandler::FilamentIcons(DGUS_VP &vp) { + uint16_t icons = 0; + + switch (dgus_screen_handler.filament_extruder) { + default: return; + case DGUS_Data::Extruder::CURRENT: + #if EXTRUDERS > 1 + switch (ExtUI::getActiveTool()) { + default: break; + case ExtUI::E0: + icons |= (uint16_t)DGUS_Data::ExtruderIcon::E0; + break; + case ExtUI::E1: + icons |= (uint16_t)DGUS_Data::ExtruderIcon::E1; + break; + } + break; + #endif + case DGUS_Data::Extruder::E0: + icons |= (uint16_t)DGUS_Data::ExtruderIcon::E0; + break; + case DGUS_Data::Extruder::E1: + icons |= (uint16_t)DGUS_Data::ExtruderIcon::E1; + break; + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); +} + +void DGUSTxHandler::BLTouch(DGUS_VP &vp) { + #if ENABLED(BLTOUCH) + dgus_display.EnableControl(DGUS_Screen::SETTINGS_MENU2, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::EXTRA2); + + dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::ENABLED)); + #else + dgus_display.DisableControl(DGUS_Screen::SETTINGS_MENU2, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::EXTRA2); + + dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::DISABLED)); + #endif +} + +void DGUSTxHandler::PIDIcons(DGUS_VP &vp) { + uint16_t icons = 0; + + switch (dgus_screen_handler.pid_heater) { + default: return; + case DGUS_Data::Heater::BED: + icons |= (uint16_t)DGUS_Data::HeaterIcon::BED; + break; + case DGUS_Data::Heater::H0: + icons |= (uint16_t)DGUS_Data::HeaterIcon::H0; + break; + case DGUS_Data::Heater::H1: + icons |= (uint16_t)DGUS_Data::HeaterIcon::H1; + break; + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); +} + +void DGUSTxHandler::PIDKp(DGUS_VP &vp) { + float value; + + switch (dgus_screen_handler.pid_heater) { + default: return; + #if ENABLED(PIDTEMPBED) + case DGUS_Data::Heater::BED: + value = ExtUI::getBedPIDValues_Kp(); + break; + #endif + #if ENABLED(PIDTEMP) + case DGUS_Data::Heater::H0: + value = ExtUI::getPIDValues_Kp(ExtUI::E0); + break; + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + value = ExtUI::getPIDValues_Kp(ExtUI::E1); + break; + #endif + #endif + } + + const int32_t data = dgus_display.ToFixedPoint(value); + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); +} + +void DGUSTxHandler::PIDKi(DGUS_VP &vp) { + float value; + + switch (dgus_screen_handler.pid_heater) { + default: return; + #if ENABLED(PIDTEMPBED) + case DGUS_Data::Heater::BED: + value = ExtUI::getBedPIDValues_Ki(); + break; + #endif + #if ENABLED(PIDTEMP) + case DGUS_Data::Heater::H0: + value = ExtUI::getPIDValues_Ki(ExtUI::E0); + break; + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + value = ExtUI::getPIDValues_Ki(ExtUI::E1); + break; + #endif + #endif + } + + const int32_t data = dgus_display.ToFixedPoint(value); + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); +} + +void DGUSTxHandler::PIDKd(DGUS_VP &vp) { + float value; + + switch (dgus_screen_handler.pid_heater) { + default: return; + #if ENABLED(PIDTEMPBED) + case DGUS_Data::Heater::BED: + value = ExtUI::getBedPIDValues_Kd(); + break; + #endif + #if ENABLED(PIDTEMP) + case DGUS_Data::Heater::H0: + value = ExtUI::getPIDValues_Kd(ExtUI::E0); + break; + #if HOTENDS > 1 + case DGUS_Data::Heater::H1: + value = ExtUI::getPIDValues_Kd(ExtUI::E1); + break; + #endif + #endif + } + + const int32_t data = dgus_display.ToFixedPoint(value); + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); +} + +void DGUSTxHandler::BuildVolume(DGUS_VP &vp) { + char buffer[vp.size]; + snprintf_P(buffer, vp.size, PSTR("%dx%dx%d"), X_BED_SIZE, Y_BED_SIZE, (Z_MAX_POS - Z_MIN_POS)); + + dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); +} + +void DGUSTxHandler::TotalPrints(DGUS_VP &vp) { + #if ENABLED(PRINTCOUNTER) + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(print_job_timer.getStats().totalPrints)); + #else + UNUSED(vp); + #endif +} + +void DGUSTxHandler::FinishedPrints(DGUS_VP &vp) { + #if ENABLED(PRINTCOUNTER) + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(print_job_timer.getStats().finishedPrints)); + #else + UNUSED(vp); + #endif +} + +void DGUSTxHandler::PrintTime(DGUS_VP &vp) { + #if ENABLED(PRINTCOUNTER) + char buffer[21]; + ExtUI::getTotalPrintTime_str(buffer); + + dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + #else + dgus_display.WriteStringPGM((uint16_t)vp.addr, DGUS_MSG_UNDEF, vp.size); + #endif +} + +void DGUSTxHandler::LongestPrint(DGUS_VP &vp) { + #if ENABLED(PRINTCOUNTER) + char buffer[21]; + ExtUI::getLongestPrint_str(buffer); + + dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + #else + dgus_display.WriteStringPGM((uint16_t)vp.addr, DGUS_MSG_UNDEF, vp.size); + #endif +} + +void DGUSTxHandler::FilamentUsed(DGUS_VP &vp) { + #if ENABLED(PRINTCOUNTER) + char buffer[21]; + ExtUI::getFilamentUsed_str(buffer); + + dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + #else + dgus_display.WriteStringPGM((uint16_t)vp.addr, DGUS_MSG_UNDEF, vp.size); + #endif +} + +void DGUSTxHandler::WaitIcons(DGUS_VP &vp) { + uint16_t icons = 0; + + if (printingIsPaused() + #if ENABLED(ADVANCED_PAUSE_FEATURE) + && did_pause_print + #endif + ) { + icons |= (uint16_t)DGUS_Data::WaitIcon::ABORT; + + dgus_display.EnableControl(DGUS_Screen::WAIT, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::ABORT); + } + else { + dgus_display.DisableControl(DGUS_Screen::WAIT, + DGUSDisplay::POPUP_WINDOW, + DGUS_Control::ABORT); + } + + if (dgus_screen_handler.wait_continue) { + icons |= (uint16_t)DGUS_Data::WaitIcon::CONTINUE; + + dgus_display.EnableControl(DGUS_Screen::WAIT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::CONTINUE); + } + else { + dgus_display.DisableControl(DGUS_Screen::WAIT, + DGUSDisplay::RETURN_KEY_CODE, + DGUS_Control::CONTINUE); + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); +} + +void DGUSTxHandler::FanSpeed(DGUS_VP &vp) { + uint16_t fan_speed; + + switch (vp.addr) { + default: return; + case DGUS_Addr::FAN0_Speed: fan_speed = ExtUI::getTargetFan_percent(ExtUI::FAN0); break; + } + + dgus_display.Write((uint16_t)vp.addr, Swap16(fan_speed)); +} + +void DGUSTxHandler::Volume(DGUS_VP &vp) { + const uint16_t volume = dgus_display.GetVolume(); + + dgus_display.Write((uint16_t)vp.addr, Swap16(volume)); +} + +void DGUSTxHandler::Brightness(DGUS_VP &vp) { + const uint16_t brightness = dgus_display.GetBrightness(); + + dgus_display.Write((uint16_t)vp.addr, Swap16(brightness)); +} + +void DGUSTxHandler::ExtraToString(DGUS_VP &vp) { + if (!vp.size || !vp.extra) return; + + dgus_display.WriteString((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); +} + +void DGUSTxHandler::ExtraPGMToString(DGUS_VP &vp) { + if (!vp.size || !vp.extra) return; + + dgus_display.WriteStringPGM((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h new file mode 100644 index 0000000000..5715abbedf --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h @@ -0,0 +1,127 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "DGUSDisplay.h" +#include "definition/DGUS_VP.h" + +namespace DGUSTxHandler { + + #if ENABLED(SDSUPPORT) + void SetFileControlState(int, bool); + void FileType(DGUS_VP &); + void FileName(DGUS_VP &); + void ScrollIcons(DGUS_VP &); + void SelectedFileName(DGUS_VP &); + #endif + + void PositionZ(DGUS_VP &); + void Ellapsed(DGUS_VP &); + void Percent(DGUS_VP &); + void StatusIcons(DGUS_VP &); + + void Flowrate(DGUS_VP &); + + void TempMax(DGUS_VP &); + + void StepperStatus(DGUS_VP &); + + void StepIcons(DGUS_VP &); + + void ABLDisableIcon(DGUS_VP &); + void ABLGrid(DGUS_VP &); + + void FilamentIcons(DGUS_VP &); + + void BLTouch(DGUS_VP &); + + void PIDIcons(DGUS_VP &); + void PIDKp(DGUS_VP &); + void PIDKi(DGUS_VP &); + void PIDKd(DGUS_VP &); + + void BuildVolume(DGUS_VP &); + void TotalPrints(DGUS_VP &); + void FinishedPrints(DGUS_VP &); + void PrintTime(DGUS_VP &); + void LongestPrint(DGUS_VP &); + void FilamentUsed(DGUS_VP &); + + void WaitIcons(DGUS_VP &); + + void FanSpeed(DGUS_VP &); + + void Volume(DGUS_VP &); + + void Brightness(DGUS_VP &); + + void ExtraToString(DGUS_VP &); + void ExtraPGMToString(DGUS_VP &); + + template + void ExtraToInteger(DGUS_VP &vp) { + if (!vp.size || !vp.extra) return; + switch (vp.size) { + default: return; + case 1: { + const uint8_t data = (uint8_t)(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, data); + break; + } + case 2: { + const uint16_t data = (uint16_t)(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, Swap16(data)); + break; + } + case 4: { + const uint32_t data = (uint32_t)(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + break; + } + } + } + + template + void ExtraToFixedPoint(DGUS_VP &vp) { + if (!vp.size || !vp.extra) return; + switch (vp.size) { + default: return; + case 1: { + const uint8_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, data); + break; + } + case 2: { + const uint16_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, Swap16(data)); + break; + } + case 4: { + const uint32_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); + dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + break; + } + } + } + +} diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h new file mode 100644 index 0000000000..de64fe2b10 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h @@ -0,0 +1,173 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +constexpr uint8_t DGUS_LINE_LEN = 32; +constexpr uint8_t DGUS_STATUS_LEN = 32; +constexpr uint8_t DGUS_FILE_COUNT = 5; +constexpr uint8_t DGUS_FILENAME_LEN = 32; +constexpr uint8_t DGUS_ELLAPSED_LEN = 15; +constexpr uint8_t DGUS_LEVEL_GRID_SIZE = 25; +constexpr uint8_t DGUS_MACHINE_LEN = 24; +constexpr uint8_t DGUS_BUILDVOLUME_LEN = 24; +constexpr uint8_t DGUS_VERSION_LEN = 16; +constexpr uint8_t DGUS_PRINTTIME_LEN = 24; +constexpr uint8_t DGUS_LONGESTPRINT_LEN = 24; +constexpr uint8_t DGUS_FILAMENTUSED_LEN = 24; +constexpr uint8_t DGUS_GCODE_LEN = 32; + +enum class DGUS_Addr : uint16_t { + MESSAGE_Line1 = 0x1100, // 0x1100 - 0x111F + MESSAGE_Line2 = 0x1120, // 0x1120 - 0x113F + MESSAGE_Line3 = 0x1140, // 0x1140 - 0x115F + MESSAGE_Line4 = 0x1160, // 0x1160 - 0x117F + + // READ-ONLY VARIABLES + + SCREENCHANGE = 0x2000, // Screen change request. Data contains target screen in low byte. + SCREENCHANGE_SD = 0x2001, // Only change if SD card present. + SCREENCHANGE_Idle = 0x2002, // Only change if not printing. + SCREENCHANGE_Printing = 0x2003, // Only change if printing. + SD_SelectFile = 0x2004, // Data: file index (0-4) + SD_Scroll = 0x2005, // Data: DGUS_Data::Scroll + SD_Print = 0x2006, + STATUS_Abort = 0x2007, // Popup / Data: DGUS_Data::Popup + STATUS_Pause = 0x2008, // Popup / Data: DGUS_Data::Popup + STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup + ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) + #if EXTRUDERS > 1 + ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) + #endif + ADJUST_SetBabystep = 0x200E, // Type: Fixed point, 2 decimals (16 bits signed) + ADJUST_Babystep = 0x200F, // Data: DGUS_Data::Adjust + TEMP_Preset = 0x2010, // Popup / Data: DGUS_Data::TempPreset + TEMP_SetTarget_Bed = 0x2011, // Type: Integer (16 bits signed) + TEMP_SetTarget_H0 = 0x2012, // Type: Integer (16 bits signed) + #if HOTENDS > 1 + TEMP_SetTarget_H1 = 0x2013, // Type: Integer (16 bits signed) + #endif + TEMP_Cool = 0x2014, // Data: DGUS_Data::Heater + STEPPER_Control = 0x2015, // Popup / Data: DGUS_Data::Control + LEVEL_OFFSET_Set = 0x2016, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_Step = 0x2017, // Data: DGUS_Data::Adjust + LEVEL_OFFSET_SetStep = 0x2018, // Data: DGUS_Data::StepSize + LEVEL_MANUAL_Point = 0x2019, // Data: point index (1-5) + LEVEL_AUTO_Probe = 0x201A, + LEVEL_AUTO_Disable = 0x201B, + FILAMENT_Select = 0x201C, // Data: DGUS_Data::Extruder + FILAMENT_SetLength = 0x201D, // Type: Integer (16 bits unsigned) + FILAMENT_Move = 0x201E, // Data: DGUS_Data::FilamentMove + MOVE_Home = 0x201F, // Data: DGUS_Data::Axis + MOVE_SetX = 0x2020, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetY = 0x2021, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetZ = 0x2022, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_Step = 0x2023, // Data: DGUS_Data::MoveDirection + MOVE_SetStep = 0x2024, // Data: DGUS_Data::StepSize + GCODE_Clear = 0x2025, + GCODE_Execute = 0x2026, + EEPROM_Reset = 0x2027, // Popup / Data: DGUS_Data::Popup + SETTINGS2_Extra = 0x2028, // Data: DGUS_Data::Extra + PID_Select = 0x2029, // Data: DGUS_Data::Heater + PID_SetTemp = 0x202A, // Type: Integer (16 bits unsigned) + PID_Run = 0x202B, + POWERLOSS_Abort = 0x202C, // Popup / Data: DGUS_Data::Popup + POWERLOSS_Resume = 0x202D, // Popup / Data: DGUS_Data::Popup + WAIT_Abort = 0x202E, // Popup / Data: DGUS_Data::Popup + WAIT_Continue = 0x202F, + + // WRITE-ONLY VARIABLES + + MESSAGE_Status = 0x3000, // 0x3000 - 0x301F + SD_Type = 0x3020, // 0x3020 - 0x3024 / Data: DGUS_Data::SDType + SD_FileName0 = 0x3025, // 0x3025 - 0x3044 + SD_FileName1 = 0x3045, // 0x3045 - 0x3064 + SD_FileName2 = 0x3065, // 0x3065 - 0x3084 + SD_FileName3 = 0x3085, // 0x3085 - 0x30A4 + SD_FileName4 = 0x30A5, // 0x30A5 - 0x30C4 + SD_ScrollIcons = 0x30C5, // Bits: DGUS_Data::ScrollIcon + SD_SelectedFileName = 0x30C6, // 0x30C6 - 0x30E5 + STATUS_PositionZ = 0x30E6, // Type: Fixed point, 1 decimal (16 bits signed) + STATUS_Ellapsed = 0x30E7, // 0x30E7 - 0x30F5 + STATUS_Percent = 0x30F6, // Type: Integer (16 bits unsigned) + STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon + ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) + ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) + #if EXTRUDERS > 1 + ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) + ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) + #endif + TEMP_Current_Bed = 0x30FC, // Type: Integer (16 bits signed) + TEMP_Target_Bed = 0x30FD, // Type: Integer (16 bits signed) + TEMP_Max_Bed = 0x30FE, // Type: Integer (16 bits unsigned) + TEMP_Current_H0 = 0x30FF, // Type: Integer (16 bits signed) + TEMP_Target_H0 = 0x3100, // Type: Integer (16 bits signed) + TEMP_Max_H0 = 0x3101, // Type: Integer (16 bits unsigned) + #if HOTENDS > 1 + TEMP_Current_H1 = 0x3102, // Type: Integer (16 bits signed) + TEMP_Target_H1 = 0x3103, // Type: Integer (16 bits signed) + TEMP_Max_H1 = 0x3104, // Type: Integer (16 bits unsigned) + #endif + STEPPER_Status = 0x3105, // Data: DGUS_Data::Status + LEVEL_OFFSET_Current = 0x3106, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_StepIcons = 0x3107, // Bits: DGUS_Data::StepIcon + LEVEL_AUTO_DisableIcon = 0x3108, // Data: DGUS_Data::Status + LEVEL_AUTO_Grid = 0x3109, // 0x3109 - 0x3121 / Type: Fixed point, 3 decimals (16 bits signed) + LEVEL_PROBING_Icons1 = 0x3122, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + LEVEL_PROBING_Icons2 = 0x3123, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + FILAMENT_ExtruderIcons = 0x3124, // Data: DGUS_Data::ExtruderIcon + FILAMENT_Length = 0x3125, // Type: Integer (16 bits unsigned) + MOVE_CurrentX = 0x3126, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentY = 0x3127, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentZ = 0x3128, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_StepIcons = 0x3129, // Bits: DGUS_Data::StepIcon + SETTINGS2_BLTouch = 0x312A, // Data: DGUS_Data::Status + PID_HeaterIcons = 0x312B, // Data: DGUS_Data::HeaterIcon + PID_Temp = 0x312C, // Type: Integer (16 bits unsigned) + PID_Kp = 0x312D, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Ki = 0x312F, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Kd = 0x3131, // Type: Fixed point, 2 decimals (32 bits signed) + INFOS_Machine = 0x3133, // 0x3133 - 0x314A + INFOS_BuildVolume = 0x314B, // 0x314B - 0x3162 + INFOS_Version = 0x3163, // 0x3163 - 0x3172 + INFOS_TotalPrints = 0x3173, // Type: Integer (16 bits unsigned) + INFOS_FinishedPrints = 0x3174, // Type: Integer (16 bits unsigned) + INFOS_PrintTime = 0x3175, // 0x3175 - 0x318C + INFOS_LongestPrint = 0x318D, // 0x318D - 0x31A4 + INFOS_FilamentUsed = 0x31A5, // 0x31A5 - 0x31BC + WAIT_Icons = 0x31BD, // Bits: DGUS_Data::WaitIcon + + // READ-WRITE VARIABLES + + FAN0_Speed = 0x4000, // Type: Integer (16 bits unsigned) / Data: fan speed as percent (0-100) + GCODE_Data = 0x4001, // 0x4001 - 0x4020 + PID_Cycles = 0x4021, // Type: Integer (16 bits unsigned) + VOLUME_Level = 0x4022, // Type: Integer (16 bits unsigned) / Data: volume as percent (0-100) + BRIGHTNESS_Level = 0x4023, // Type: Integer (16 bits unsigned) / Data: brightness as percent (0-100) + + // SPECIAL CASES + + STATUS_Percent_Complete = 0x5000, // Same as STATUS_Percent, but always 100% + INFOS_Debug = 0x5001, + +}; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h new file mode 100644 index 0000000000..4047a6d6dc --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h @@ -0,0 +1,96 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../../../../inc/MarlinConfigPre.h" + +#include "DGUS_Addr.h" + +static_assert((DGUS_LEVEL_GRID_SIZE == GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y), "DGUS_LEVEL_GRID_SIZE incompatible with current mesh."); + +#ifndef DGUS_DEFAULT_VOLUME + #define DGUS_DEFAULT_VOLUME 50 +#endif + +#ifndef DGUS_DEFAULT_BRIGHTNESS + #define DGUS_DEFAULT_BRIGHTNESS 100 +#endif + +#ifndef DGUS_STATUS_EXPIRATION_MS + #define DGUS_STATUS_EXPIRATION_MS 30000 +#endif + +#ifndef DGUS_PRINT_BABYSTEP + #define DGUS_PRINT_BABYSTEP 0.01f +#endif + +#ifndef DGUS_PLA_TEMP_HOTEND + #define DGUS_PLA_TEMP_HOTEND 200 +#endif + +#ifndef DGUS_PLA_TEMP_BED + #define DGUS_PLA_TEMP_BED 60 +#endif + +#ifndef DGUS_ABS_TEMP_HOTEND + #define DGUS_ABS_TEMP_HOTEND 240 +#endif + +#ifndef DGUS_ABS_TEMP_BED + #define DGUS_ABS_TEMP_BED 80 +#endif + +#ifndef DGUS_PETG_TEMP_HOTEND + #define DGUS_PETG_TEMP_HOTEND 240 +#endif + +#ifndef DGUS_PETG_TEMP_BED + #define DGUS_PETG_TEMP_BED 60 +#endif + +#ifndef DGUS_DEFAULT_FILAMENT_LEN + #define DGUS_DEFAULT_FILAMENT_LEN 10 +#endif + +#ifndef LEVEL_CORNERS_Z_HOP + #define LEVEL_CORNERS_Z_HOP 4.0 +#endif + +#ifndef LEVEL_CORNERS_HEIGHT + #define LEVEL_CORNERS_HEIGHT 0.0 +#endif + +static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); + +#ifndef DGUS_LEVEL_CENTER_X + #define DGUS_LEVEL_CENTER_X ((X_BED_SIZE) / 2) +#endif + +#ifndef DGUS_LEVEL_CENTER_Y + #define DGUS_LEVEL_CENTER_Y ((Y_BED_SIZE) / 2) +#endif + +#if ENABLED(BLTOUCH) + #ifndef DGUS_RESET_BLTOUCH + #define DGUS_RESET_BLTOUCH "M999\nM280P0S160" + #endif +#endif diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Control.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Control.h new file mode 100644 index 0000000000..92d2f5ece2 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Control.h @@ -0,0 +1,50 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +enum class DGUS_Control : uint8_t { + + // PRINT + FILE0 = 1, // RETURN_KEY_CODE + FILE1 = 2, // RETURN_KEY_CODE + FILE2 = 3, // RETURN_KEY_CODE + FILE3 = 4, // RETURN_KEY_CODE + FILE4 = 5, // RETURN_KEY_CODE + GO_BACK = 6, // RETURN_KEY_CODE + SCROLL_UP = 7, // RETURN_KEY_CODE + SCROLL_DOWN = 8, // RETURN_KEY_CODE + + // PRINT_STATUS + PAUSE = 1, // POPUP_WINDOW + RESUME = 2, // POPUP_WINDOW + + // LEVELING_AUTOMATIC + DISABLE = 5, // RETURN_KEY_CODE + + // SETTINGS_MENU2 + EXTRA2 = 6, // RETURN_KEY_CODE + + // WAIT + ABORT = 1, // POPUP_WINDOW + CONTINUE = 2 // RETURN_KEY_CODE + +}; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Data.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Data.h new file mode 100644 index 0000000000..886109054c --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Data.h @@ -0,0 +1,148 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +namespace DGUS_Data { + + // RX constants + + enum class Scroll : uint8_t { + GO_BACK = 0, + UP = 1, + DOWN = 2 + }; + + enum class Popup : uint8_t { + CONFIRMED = 1 + }; + + enum class Adjust : uint8_t { + INCREMENT = 0, + DECREMENT = 1 + }; + + enum class TempPreset : uint8_t { + PLA = 1, + ABS = 2, + PETG = 3 + }; + + enum class Extruder : int8_t { + CURRENT = -1, + E0 = 0, + E1 = 1 + }; + + enum class Heater : int8_t { + ALL = -2, + BED = -1, + H0 = 0, + H1 = 1 + }; + + enum class Control : uint8_t { + ENABLE = 1, + DISABLE = 2 + }; + + enum class StepSize : uint8_t { + MM10 = 0, // 10mm + MM1 = 1, // 1mm + MMP1 = 2, // 0.1mm + MMP01 = 3 // 0.01mm + }; + + enum class FilamentMove : uint8_t { + RETRACT = 0, + EXTRUDE = 1 + }; + + enum class Axis : uint8_t { + X_Y_Z = 0, + X_Y = 1, + Z = 2 + }; + + enum class MoveDirection : uint8_t { + XP = 0, // X+ + XM = 1, // X- + YP = 2, // Y+ + YM = 3, // Y- + ZP = 4, // Z+ + ZM = 5 // Z- + }; + + enum class Extra : uint8_t { + BUTTON1 = 0, + BUTTON2 = 1 + }; + + // TX constants + + enum class SDType : uint16_t { + NONE = 0, + FILE = 1, + DIRECTORY = 2 + }; + + enum class ScrollIcon : uint16_t { + GO_BACK = 1U << 0, + UP = 1U << 1, + DOWN = 1U << 2 + }; + + enum class StatusIcon : uint16_t { + PAUSE = 1U << 0, + RESUME = 1U << 1 + }; + + enum class Status : uint16_t { + DISABLED = 0, + ENABLED = 1 + }; + + enum class StepIcon : uint16_t { + MM10 = 1U << 0, // 10mm + MM1 = 1U << 1, // 1mm + MMP1 = 1U << 2, // 0.1mm + MMP01 = 1U << 3 // 0.01mm + }; + + enum class ExtruderIcon : uint16_t { + E0 = 1U << 0, + E1 = 1U << 1 + }; + + enum class HeaterIcon : uint16_t { + BED = 1U << 0, + H0 = 1U << 1, + H1 = 1U << 2 + }; + + enum class WaitIcon : uint16_t { + ABORT = 1U << 0, + CONTINUE = 1U << 1 + }; + +}; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h new file mode 100644 index 0000000000..b3d2ad6d3c --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h @@ -0,0 +1,52 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +enum class DGUS_Screen : uint8_t { + BOOT = 0, + HOME = 1, + PRINT = 2, + PRINT_STATUS = 3, + PRINT_ADJUST = 4, + PRINT_FINISHED = 5, + TEMP_MENU = 6, + TEMP_MANUAL = 7, + FAN = 8, + SETTINGS_MENU = 9, + LEVELING_MENU = 10, + LEVELING_OFFSET = 11, + LEVELING_MANUAL = 12, + LEVELING_AUTOMATIC = 13, + LEVELING_PROBING = 14, + FILAMENT = 15, + MOVE = 16, + GCODE = 17, + SETTINGS_MENU2 = 18, + PID = 19, + VOLUME = 20, + BRIGHTNESS = 21, + INFOS = 22, + DEBUG = 240, + POWERLOSS = 248, + WAIT = 249, + KILL = 250 +}; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp new file mode 100644 index 0000000000..95e6444956 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp @@ -0,0 +1,240 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUS_ScreenAddrList.h" + +#include "../../ui_api.h" + +constexpr DGUS_Addr LIST_HOME[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + (DGUS_Addr)0 +}; + +#if ENABLED(SDSUPPORT) + constexpr DGUS_Addr LIST_PRINT[] PROGMEM = { + DGUS_Addr::SD_Type, + DGUS_Addr::SD_FileName0, + DGUS_Addr::SD_FileName1, + DGUS_Addr::SD_FileName2, + DGUS_Addr::SD_FileName3, + DGUS_Addr::SD_FileName4, + DGUS_Addr::SD_ScrollIcons, + DGUS_Addr::SD_SelectedFileName, + (DGUS_Addr)0 + }; +#endif + +constexpr DGUS_Addr LIST_PRINT_STATUS[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + DGUS_Addr::STATUS_PositionZ, + DGUS_Addr::STATUS_Ellapsed, + DGUS_Addr::STATUS_Percent, + DGUS_Addr::STATUS_Icons, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_PRINT_ADJUST[] PROGMEM = { + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Target_Bed, + DGUS_Addr::FAN0_Speed, + DGUS_Addr::ADJUST_Feedrate, + DGUS_Addr::ADJUST_Flowrate_CUR, + DGUS_Addr::LEVEL_OFFSET_Current, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_PRINT_FINISHED[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + DGUS_Addr::STATUS_PositionZ, + DGUS_Addr::STATUS_Ellapsed, + DGUS_Addr::STATUS_Percent_Complete, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_TEMP_MENU[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_TEMP_MANUAL[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Max_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + DGUS_Addr::TEMP_Max_Bed, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_FAN[] PROGMEM = { + DGUS_Addr::FAN0_Speed, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_SETTINGS_MENU[] PROGMEM = { + DGUS_Addr::STEPPER_Status, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_LEVELING_OFFSET[] PROGMEM = { + DGUS_Addr::LEVEL_OFFSET_Current, + DGUS_Addr::LEVEL_OFFSET_StepIcons, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_LEVELING_MANUAL[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_LEVELING_AUTOMATIC[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::TEMP_Current_Bed, + DGUS_Addr::TEMP_Target_Bed, + DGUS_Addr::LEVEL_AUTO_DisableIcon, + DGUS_Addr::LEVEL_AUTO_Grid, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_LEVELING_PROBING[] PROGMEM = { + DGUS_Addr::LEVEL_PROBING_Icons1, + DGUS_Addr::LEVEL_PROBING_Icons2, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_FILAMENT[] PROGMEM = { + DGUS_Addr::TEMP_Current_H0, + DGUS_Addr::TEMP_Target_H0, + DGUS_Addr::FILAMENT_ExtruderIcons, + DGUS_Addr::FILAMENT_Length, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_MOVE[] PROGMEM = { + DGUS_Addr::MOVE_CurrentX, + DGUS_Addr::MOVE_CurrentY, + DGUS_Addr::MOVE_CurrentZ, + DGUS_Addr::MOVE_StepIcons, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_GCODE[] PROGMEM = { + DGUS_Addr::GCODE_Data, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_SETTINGS_MENU2[] PROGMEM = { + DGUS_Addr::SETTINGS2_BLTouch, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_PID[] PROGMEM = { + DGUS_Addr::PID_HeaterIcons, + DGUS_Addr::PID_Temp, + DGUS_Addr::PID_Cycles, + DGUS_Addr::PID_Kp, + DGUS_Addr::PID_Ki, + DGUS_Addr::PID_Kd, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_VOLUME[] PROGMEM = { + DGUS_Addr::VOLUME_Level, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_BRIGHTNESS[] PROGMEM = { + DGUS_Addr::BRIGHTNESS_Level, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_INFOS[] PROGMEM = { + DGUS_Addr::INFOS_Machine, + DGUS_Addr::INFOS_BuildVolume, + DGUS_Addr::INFOS_Version, + DGUS_Addr::INFOS_TotalPrints, + DGUS_Addr::INFOS_FinishedPrints, + DGUS_Addr::INFOS_PrintTime, + DGUS_Addr::INFOS_LongestPrint, + DGUS_Addr::INFOS_FilamentUsed, + (DGUS_Addr)0 +}; + +constexpr DGUS_Addr LIST_WAIT[] PROGMEM = { + DGUS_Addr::WAIT_Icons, + (DGUS_Addr)0 +}; + +#define MAP_HELPER(SCREEN, LIST) \ + { .screen = SCREEN, \ + .addr_list = LIST } + +const struct DGUS_ScreenAddrList screen_addr_list_map[] PROGMEM = { + MAP_HELPER(DGUS_Screen::HOME, LIST_HOME), + #if ENABLED(SDSUPPORT) + MAP_HELPER(DGUS_Screen::PRINT, LIST_PRINT), + #endif + MAP_HELPER(DGUS_Screen::PRINT_STATUS, LIST_PRINT_STATUS), + MAP_HELPER(DGUS_Screen::PRINT_ADJUST, LIST_PRINT_ADJUST), + MAP_HELPER(DGUS_Screen::PRINT_FINISHED, LIST_PRINT_FINISHED), + MAP_HELPER(DGUS_Screen::TEMP_MENU, LIST_TEMP_MENU), + MAP_HELPER(DGUS_Screen::TEMP_MANUAL, LIST_TEMP_MANUAL), + MAP_HELPER(DGUS_Screen::FAN, LIST_FAN), + MAP_HELPER(DGUS_Screen::SETTINGS_MENU, LIST_SETTINGS_MENU), + MAP_HELPER(DGUS_Screen::LEVELING_OFFSET, LIST_LEVELING_OFFSET), + MAP_HELPER(DGUS_Screen::LEVELING_MANUAL, LIST_LEVELING_MANUAL), + MAP_HELPER(DGUS_Screen::LEVELING_AUTOMATIC, LIST_LEVELING_AUTOMATIC), + MAP_HELPER(DGUS_Screen::LEVELING_PROBING, LIST_LEVELING_PROBING), + MAP_HELPER(DGUS_Screen::FILAMENT, LIST_FILAMENT), + MAP_HELPER(DGUS_Screen::MOVE, LIST_MOVE), + MAP_HELPER(DGUS_Screen::GCODE, LIST_GCODE), + MAP_HELPER(DGUS_Screen::SETTINGS_MENU2, LIST_SETTINGS_MENU2), + MAP_HELPER(DGUS_Screen::PID, LIST_PID), + MAP_HELPER(DGUS_Screen::VOLUME, LIST_VOLUME), + MAP_HELPER(DGUS_Screen::BRIGHTNESS, LIST_BRIGHTNESS), + MAP_HELPER(DGUS_Screen::INFOS, LIST_INFOS), + MAP_HELPER(DGUS_Screen::WAIT, LIST_WAIT), + + MAP_HELPER((DGUS_Screen)0, nullptr) +}; + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h new file mode 100644 index 0000000000..af05c46d28 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h @@ -0,0 +1,32 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../config/DGUS_Screen.h" +#include "../config/DGUS_Addr.h" + +struct DGUS_ScreenAddrList { + DGUS_Screen screen; + const DGUS_Addr *addr_list; +}; + +extern const struct DGUS_ScreenAddrList screen_addr_list_map[]; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp new file mode 100644 index 0000000000..213e430334 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp @@ -0,0 +1,57 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUS_ScreenSetup.h" + +#include "../DGUSSetupHandler.h" + +#include "../../ui_api.h" + +#define SETUP_HELPER(SCREEN, SETUP) \ + { .screen = SCREEN, \ + .setup_fn = SETUP } + +const struct DGUS_ScreenSetup screen_setup_list[] PROGMEM = { + #if ENABLED(SDSUPPORT) + SETUP_HELPER(DGUS_Screen::PRINT, &DGUSSetupHandler::Print), + #endif + SETUP_HELPER(DGUS_Screen::PRINT_STATUS, &DGUSSetupHandler::PrintStatus), + SETUP_HELPER(DGUS_Screen::PRINT_ADJUST, &DGUSSetupHandler::PrintAdjust), + SETUP_HELPER(DGUS_Screen::LEVELING_MENU, &DGUSSetupHandler::LevelingMenu), + SETUP_HELPER(DGUS_Screen::LEVELING_OFFSET, &DGUSSetupHandler::LevelingOffset), + SETUP_HELPER(DGUS_Screen::LEVELING_MANUAL, &DGUSSetupHandler::LevelingManual), + SETUP_HELPER(DGUS_Screen::LEVELING_AUTOMATIC, &DGUSSetupHandler::LevelingAutomatic), + SETUP_HELPER(DGUS_Screen::LEVELING_PROBING, &DGUSSetupHandler::LevelingProbing), + SETUP_HELPER(DGUS_Screen::FILAMENT, &DGUSSetupHandler::Filament), + SETUP_HELPER(DGUS_Screen::MOVE, &DGUSSetupHandler::Move), + SETUP_HELPER(DGUS_Screen::GCODE, &DGUSSetupHandler::Gcode), + SETUP_HELPER(DGUS_Screen::PID, &DGUSSetupHandler::PID), + SETUP_HELPER(DGUS_Screen::INFOS, &DGUSSetupHandler::Infos), + + SETUP_HELPER((DGUS_Screen)0, nullptr) +}; + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h new file mode 100644 index 0000000000..3b9208e5ec --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h @@ -0,0 +1,31 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../config/DGUS_Screen.h" + +struct DGUS_ScreenSetup { + DGUS_Screen screen; + bool (*setup_fn)(void); +}; + +extern const struct DGUS_ScreenSetup screen_setup_list[]; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VP.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VP.h new file mode 100644 index 0000000000..b1b6792224 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VP.h @@ -0,0 +1,40 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "../config/DGUS_Addr.h" + +#define VPFLAG_NONE 0 +#define VPFLAG_AUTOUPLOAD (1U << 0) // Upload on every DGUS update +#define VPFLAG_RXSTRING (1U << 1) // Treat the received data as a string (terminated with 0xFFFF) + +struct DGUS_VP { + DGUS_Addr addr; + uint8_t size; + uint8_t flags; + void *extra; + + // Callback that will be called if the display modified the value. + // nullptr makes it readonly for the display. + void (*rx_handler)(DGUS_VP &, void *); + void (*tx_handler)(DGUS_VP &); +}; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp new file mode 100644 index 0000000000..3f5690cfe7 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp @@ -0,0 +1,368 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "DGUS_VPList.h" + +#include "../config/DGUS_Addr.h" +#include "../DGUSScreenHandler.h" +#include "../DGUSRxHandler.h" +#include "../DGUSTxHandler.h" + +#include "../../ui_api.h" +#include "../../../../module/probe.h" +#include "../../../../module/motion.h" +#include "../../../../module/temperature.h" + +const char DGUS_MACHINENAME[] PROGMEM = MACHINE_NAME; +const char DGUS_MARLINVERSION[] PROGMEM = SHORT_BUILD_VERSION; + +#define VP_HELPER(ADDR, SIZE, FLAGS, EXTRA, RXHANDLER, TXHANDLER) \ + { .addr = ADDR, \ + .size = SIZE, \ + .flags = FLAGS, \ + .extra = EXTRA, \ + .rx_handler = RXHANDLER, \ + .tx_handler = TXHANDLER } + +#define VP_HELPER_WORD(ADDR, FLAGS, EXTRA, RXHANDLER, TXHANDLER) \ + VP_HELPER(ADDR, 2, FLAGS, EXTRA, RXHANDLER, TXHANDLER) + +#define VP_HELPER_DWORD(ADDR, FLAGS, EXTRA, RXHANDLER, TXHANDLER) \ + VP_HELPER(ADDR, 4, FLAGS, EXTRA, RXHANDLER, TXHANDLER) + +#define VP_HELPER_RX(ADDR, RXHANDLER) \ + VP_HELPER_WORD(ADDR, VPFLAG_NONE, nullptr, RXHANDLER, nullptr) + +#define VP_HELPER_RX_NODATA(ADDR, RXHANDLER) \ + VP_HELPER(ADDR, 0, VPFLAG_NONE, nullptr, RXHANDLER, nullptr) + +#define VP_HELPER_TX(ADDR, TXHANDLER) \ + VP_HELPER_WORD(ADDR, VPFLAG_NONE, nullptr, nullptr, TXHANDLER) + +#define VP_HELPER_TX_SIZE(ADDR, SIZE, TXHANDLER) \ + VP_HELPER(ADDR, SIZE, VPFLAG_NONE, nullptr, nullptr, TXHANDLER) + +#define VP_HELPER_TX_EXTRA(ADDR, EXTRA, TXHANDLER) \ + VP_HELPER_WORD(ADDR, VPFLAG_NONE, EXTRA, nullptr, TXHANDLER) + +#define VP_HELPER_TX_AUTO(ADDR, EXTRA, TXHANDLER) \ + VP_HELPER_WORD(ADDR, VPFLAG_AUTOUPLOAD, EXTRA, nullptr, TXHANDLER) + +const struct DGUS_VP vp_list[] PROGMEM = { + + // READ-ONLY VARIABLES + + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE, &DGUSRxHandler::ScreenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_SD, &DGUSRxHandler::ScreenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Idle, &DGUSRxHandler::ScreenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Printing, &DGUSRxHandler::ScreenChange), + + #if ENABLED(SDSUPPORT) + VP_HELPER_RX(DGUS_Addr::SD_SelectFile, &DGUSRxHandler::SelectFile), + VP_HELPER_RX(DGUS_Addr::SD_Scroll, &DGUSRxHandler::Scroll), + VP_HELPER_RX_NODATA(DGUS_Addr::SD_Print, &DGUSRxHandler::PrintFile), + #endif + + VP_HELPER_RX(DGUS_Addr::STATUS_Abort, &DGUSRxHandler::PrintAbort), + VP_HELPER_RX(DGUS_Addr::STATUS_Pause, &DGUSRxHandler::PrintPause), + VP_HELPER_RX(DGUS_Addr::STATUS_Resume, &DGUSRxHandler::PrintResume), + + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFeedrate, &DGUSRxHandler::Feedrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_CUR, &DGUSRxHandler::Flowrate), + #if EXTRUDERS > 1 + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E0, &DGUSRxHandler::Flowrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E1, &DGUSRxHandler::Flowrate), + #endif + VP_HELPER_RX(DGUS_Addr::ADJUST_SetBabystep, &DGUSRxHandler::BabystepSet), + VP_HELPER_RX(DGUS_Addr::ADJUST_Babystep, &DGUSRxHandler::Babystep), + + VP_HELPER_RX(DGUS_Addr::TEMP_Preset, &DGUSRxHandler::TempPreset), + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_Bed, &DGUSRxHandler::TempTarget), + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H0, &DGUSRxHandler::TempTarget), + #if HOTENDS > 1 + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H1, &DGUSRxHandler::TempTarget), + #endif + VP_HELPER_RX(DGUS_Addr::TEMP_Cool, &DGUSRxHandler::TempCool), + + VP_HELPER_RX(DGUS_Addr::STEPPER_Control, &DGUSRxHandler::Steppers), + + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Set, &DGUSRxHandler::ZOffset), + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Step, &DGUSRxHandler::ZOffsetStep), + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_SetStep, &DGUSRxHandler::ZOffsetSetStep), + + VP_HELPER_RX(DGUS_Addr::LEVEL_MANUAL_Point, &DGUSRxHandler::MoveToPoint), + + VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Probe, &DGUSRxHandler::Probe), + VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Disable, + &DGUSRxHandler::DisableABL), + + VP_HELPER_RX(DGUS_Addr::FILAMENT_Select, &DGUSRxHandler::FilamentSelect), + VP_HELPER_RX(DGUS_Addr::FILAMENT_SetLength, &DGUSRxHandler::FilamentLength), + VP_HELPER_RX(DGUS_Addr::FILAMENT_Move, &DGUSRxHandler::FilamentMove), + + VP_HELPER_RX(DGUS_Addr::MOVE_Home, &DGUSRxHandler::Home), + VP_HELPER_RX(DGUS_Addr::MOVE_SetX, &DGUSRxHandler::Move), + VP_HELPER_RX(DGUS_Addr::MOVE_SetY, &DGUSRxHandler::Move), + VP_HELPER_RX(DGUS_Addr::MOVE_SetZ, &DGUSRxHandler::Move), + VP_HELPER_RX(DGUS_Addr::MOVE_Step, &DGUSRxHandler::MoveStep), + VP_HELPER_RX(DGUS_Addr::MOVE_SetStep, &DGUSRxHandler::MoveSetStep), + + VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Clear, &DGUSRxHandler::GcodeClear), + VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Execute, &DGUSRxHandler::GcodeExecute), + + VP_HELPER_RX(DGUS_Addr::EEPROM_Reset, &DGUSRxHandler::ResetEEPROM), + + VP_HELPER_RX(DGUS_Addr::SETTINGS2_Extra, &DGUSRxHandler::SettingsExtra), + + VP_HELPER_RX(DGUS_Addr::PID_Select, &DGUSRxHandler::PIDSelect), + VP_HELPER_RX(DGUS_Addr::PID_SetTemp, &DGUSRxHandler::PIDSetTemp), + VP_HELPER_RX_NODATA(DGUS_Addr::PID_Run, &DGUSRxHandler::PIDRun), + + #if ENABLED(POWER_LOSS_RECOVERY) + VP_HELPER_RX(DGUS_Addr::POWERLOSS_Abort, &DGUSRxHandler::PowerLossAbort), + VP_HELPER_RX(DGUS_Addr::POWERLOSS_Resume, &DGUSRxHandler::PowerLossResume), + #endif + + VP_HELPER_RX(DGUS_Addr::WAIT_Abort, &DGUSRxHandler::WaitAbort), + VP_HELPER_RX_NODATA(DGUS_Addr::WAIT_Continue, &DGUSRxHandler::WaitContinue), + + // WRITE-ONLY VARIABLES + + #if ENABLED(SDSUPPORT) + VP_HELPER_TX(DGUS_Addr::SD_Type, &DGUSTxHandler::FileType), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName0, + DGUS_FILENAME_LEN, + &DGUSTxHandler::FileName), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName1, + DGUS_FILENAME_LEN, + &DGUSTxHandler::FileName), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName2, + DGUS_FILENAME_LEN, + &DGUSTxHandler::FileName), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName3, + DGUS_FILENAME_LEN, + &DGUSTxHandler::FileName), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName4, + DGUS_FILENAME_LEN, + &DGUSTxHandler::FileName), + VP_HELPER_TX(DGUS_Addr::SD_ScrollIcons, &DGUSTxHandler::ScrollIcons), + VP_HELPER_TX_SIZE(DGUS_Addr::SD_SelectedFileName, + DGUS_FILENAME_LEN, + &DGUSTxHandler::SelectedFileName), + #endif + + VP_HELPER_TX_AUTO(DGUS_Addr::STATUS_PositionZ, + nullptr, + &DGUSTxHandler::PositionZ), + VP_HELPER(DGUS_Addr::STATUS_Ellapsed, + DGUS_ELLAPSED_LEN, + VPFLAG_AUTOUPLOAD, + nullptr, + nullptr, + &DGUSTxHandler::Ellapsed), + VP_HELPER_TX_AUTO(DGUS_Addr::STATUS_Percent, + nullptr, + &DGUSTxHandler::Percent), + VP_HELPER_TX(DGUS_Addr::STATUS_Icons, &DGUSTxHandler::StatusIcons), + + VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Feedrate, + &feedrate_percentage, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_CUR, + nullptr, + &DGUSTxHandler::Flowrate), + #if EXTRUDERS > 1 + VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_E0, + nullptr, + &DGUSTxHandler::Flowrate), + VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_E1, + nullptr, + &DGUSTxHandler::Flowrate), + #endif + + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_Bed, + &thermalManager.temp_bed.celsius, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_Bed, + &thermalManager.temp_bed.target, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_Bed, &DGUSTxHandler::TempMax), + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_H0, + &thermalManager.temp_hotend[ExtUI::heater_t::H0].celsius, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_H0, + &thermalManager.temp_hotend[ExtUI::heater_t::H0].target, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_H0, &DGUSTxHandler::TempMax), + #if HOTENDS > 1 + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_H1, + &thermalManager.temp_hotend[ExtUI::heater_t::H1].celsius, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_H1, + &thermalManager.temp_hotend[ExtUI::heater_t::H1].target, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_H1, &DGUSTxHandler::TempMax), + #endif + + VP_HELPER_TX_AUTO(DGUS_Addr::STEPPER_Status, + nullptr, + &DGUSTxHandler::StepperStatus), + + VP_HELPER_TX_AUTO(DGUS_Addr::LEVEL_OFFSET_Current, + &probe.offset.z, + (&DGUSTxHandler::ExtraToFixedPoint)), + VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_OFFSET_StepIcons, + &DGUSScreenHandler::offset_steps, + &DGUSTxHandler::StepIcons), + + VP_HELPER_TX_AUTO(DGUS_Addr::LEVEL_AUTO_DisableIcon, + nullptr, + &DGUSTxHandler::ABLDisableIcon), + VP_HELPER_TX(DGUS_Addr::LEVEL_AUTO_Grid, &DGUSTxHandler::ABLGrid), + + VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_PROBING_Icons1, + &DGUSScreenHandler::probing_icons[0], + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_PROBING_Icons2, + &DGUSScreenHandler::probing_icons[1], + &DGUSTxHandler::ExtraToInteger), + + VP_HELPER_TX(DGUS_Addr::FILAMENT_ExtruderIcons, &DGUSTxHandler::FilamentIcons), + VP_HELPER_TX_EXTRA(DGUS_Addr::FILAMENT_Length, + &DGUSScreenHandler::filament_length, + &DGUSTxHandler::ExtraToInteger), + + VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentX, + ¤t_position.x, + (&DGUSTxHandler::ExtraToFixedPoint)), + VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentY, + ¤t_position.y, + (&DGUSTxHandler::ExtraToFixedPoint)), + VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentZ, + ¤t_position.z, + (&DGUSTxHandler::ExtraToFixedPoint)), + VP_HELPER_TX_EXTRA(DGUS_Addr::MOVE_StepIcons, + &DGUSScreenHandler::move_steps, + &DGUSTxHandler::StepIcons), + + VP_HELPER_TX(DGUS_Addr::SETTINGS2_BLTouch, &DGUSTxHandler::BLTouch), + + VP_HELPER_TX(DGUS_Addr::PID_HeaterIcons, &DGUSTxHandler::PIDIcons), + VP_HELPER_TX_EXTRA(DGUS_Addr::PID_Temp, + &DGUSScreenHandler::pid_temp, + &DGUSTxHandler::ExtraToInteger), + VP_HELPER_DWORD(DGUS_Addr::PID_Kp, + VPFLAG_AUTOUPLOAD, + nullptr, + nullptr, + &DGUSTxHandler::PIDKp), + VP_HELPER_DWORD(DGUS_Addr::PID_Ki, + VPFLAG_AUTOUPLOAD, + nullptr, + nullptr, + &DGUSTxHandler::PIDKi), + VP_HELPER_DWORD(DGUS_Addr::PID_Kd, + VPFLAG_AUTOUPLOAD, + nullptr, + nullptr, + &DGUSTxHandler::PIDKd), + + VP_HELPER(DGUS_Addr::INFOS_Machine, + DGUS_MACHINE_LEN, + VPFLAG_NONE, + (void*)DGUS_MACHINENAME, + nullptr, + &DGUSTxHandler::ExtraPGMToString), + VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_BuildVolume, + DGUS_BUILDVOLUME_LEN, + &DGUSTxHandler::BuildVolume), + VP_HELPER(DGUS_Addr::INFOS_Version, + DGUS_VERSION_LEN, + VPFLAG_NONE, + (void*)DGUS_MARLINVERSION, + nullptr, + &DGUSTxHandler::ExtraPGMToString), + VP_HELPER_TX(DGUS_Addr::INFOS_TotalPrints, &DGUSTxHandler::TotalPrints), + VP_HELPER_TX(DGUS_Addr::INFOS_FinishedPrints, &DGUSTxHandler::FinishedPrints), + VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_PrintTime, + DGUS_PRINTTIME_LEN, + &DGUSTxHandler::PrintTime), + VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_LongestPrint, + DGUS_LONGESTPRINT_LEN, + &DGUSTxHandler::LongestPrint), + VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_FilamentUsed, + DGUS_FILAMENTUSED_LEN, + &DGUSTxHandler::FilamentUsed), + + VP_HELPER_TX(DGUS_Addr::WAIT_Icons, &DGUSTxHandler::WaitIcons), + + // READ-WRITE VARIABLES + + VP_HELPER(DGUS_Addr::FAN0_Speed, + 2, + VPFLAG_AUTOUPLOAD, + nullptr, + &DGUSRxHandler::FanSpeed, + &DGUSTxHandler::FanSpeed), + + VP_HELPER(DGUS_Addr::GCODE_Data, + DGUS_GCODE_LEN, + VPFLAG_RXSTRING, + (void*)DGUSScreenHandler::gcode, + &DGUSRxHandler::StringToExtra, + &DGUSTxHandler::ExtraToString), + + VP_HELPER(DGUS_Addr::PID_Cycles, + 2, + VPFLAG_NONE, + &DGUSScreenHandler::pid_cycles, + &DGUSRxHandler::IntegerToExtra, + &DGUSTxHandler::ExtraToInteger), + + VP_HELPER(DGUS_Addr::VOLUME_Level, + 2, + VPFLAG_NONE, + nullptr, + &DGUSRxHandler::Volume, + &DGUSTxHandler::Volume), + + VP_HELPER(DGUS_Addr::BRIGHTNESS_Level, + 2, + VPFLAG_NONE, + nullptr, + &DGUSRxHandler::Brightness, + &DGUSTxHandler::Brightness), + + // SPECIAL CASES + + VP_HELPER_TX(DGUS_Addr::STATUS_Percent_Complete, &DGUSTxHandler::Percent), + VP_HELPER_RX_NODATA(DGUS_Addr::INFOS_Debug, &DGUSRxHandler::Debug), + + VP_HELPER((DGUS_Addr)0, 0, VPFLAG_NONE, nullptr, nullptr, nullptr) + +}; + +#endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.h new file mode 100644 index 0000000000..d481fbab5c --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include "DGUS_VP.h" + +extern const struct DGUS_VP vp_list[]; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp new file mode 100644 index 0000000000..4d57fbd7e2 --- /dev/null +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -0,0 +1,142 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DGUS_LCD_UI_RELOADED) + +#include "../ui_api.h" +#include "DGUSScreenHandler.h" + +namespace ExtUI { + + void onStartup() { dgus_screen_handler.Init(); } + + void onIdle() { + static bool processing = false; + + // Prevent recursion + if (!processing) { + processing = true; + dgus_screen_handler.Loop(); + processing = false; + } + } + + void onPrinterKilled(PGM_P error, PGM_P component) { + dgus_screen_handler.PrinterKilled(error, component); + } + + void onMediaInserted() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardInserted()); } + void onMediaError() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardError()); } + void onMediaRemoved() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardRemoved()); } + + void onPlayTone(const uint16_t frequency, const uint16_t duration) { + dgus_screen_handler.PlayTone(frequency, duration); + } + + void onPrintTimerStarted() { + dgus_screen_handler.PrintTimerStarted(); + } + + void onPrintTimerPaused() { + dgus_screen_handler.PrintTimerPaused(); + } + + void onPrintTimerStopped() { + dgus_screen_handler.PrintTimerStopped(); + } + + void onFilamentRunout(const extruder_t extruder) { + dgus_screen_handler.FilamentRunout(extruder); + } + + void onUserConfirmRequired(const char * const msg) { + dgus_screen_handler.UserConfirmRequired(msg); + } + + void onStatusChanged(const char * const msg) { + dgus_screen_handler.SetStatusMessage(msg); + } + + void onHomingStart() {} + void onHomingComplete() {} + void onPrintFinished() {} + + void onFactoryReset() { + dgus_screen_handler.SettingsReset(); + } + + void onStoreSettings(char *buff) { + dgus_screen_handler.StoreSettings(buff); + } + + void onLoadSettings(const char *buff) { + dgus_screen_handler.LoadSettings(buff); + } + + void onPostprocessSettings() {} + + void onConfigurationStoreWritten(bool success) { + dgus_screen_handler.ConfigurationStoreWritten(success); + } + + void onConfigurationStoreRead(bool success) { + dgus_screen_handler.ConfigurationStoreRead(success); + } + + #if HAS_MESH + void onMeshLevelingStart() {} + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { + dgus_screen_handler.MeshUpdate(xpos, ypos); + } + + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { + if (state == G29_POINT_FINISH) + dgus_screen_handler.MeshUpdate(xpos, ypos); + } + #endif + + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + dgus_screen_handler.PowerLossResume(); + } + #endif + + #if HAS_PID_HEATING + void onPidTuning(const result_t rst) { + // Called for temperature PID tuning result + dgus_screen_handler.PidTuning(rst); + } + #endif + + void onSteppersDisabled() {} + void onSteppersEnabled() {} +} + +#endif // DGUS_LCD_UI_RELOADED diff --git a/ini/features.ini b/ini/features.ini index fa7d151938..4a1c638de2 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -78,7 +78,8 @@ HAS_MENU_TRAMMING = src_filter=+ ANYCUBIC_LCD_CHIRON = src_filter=+ ANYCUBIC_LCD_I3MEGA = src_filter=+ -HAS_DGUS_LCD = src_filter=+ +HAS_DGUS_LCD_CLASSIC = src_filter=+ +DGUS_LCD_UI_RELOADED = src_filter=+ DGUS_LCD_UI_FYSETC = src_filter=+ DGUS_LCD_UI_HIPRECY = src_filter=+ DGUS_LCD_UI_MKS = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 9ee1e76a5b..55c7577e37 100644 --- a/platformio.ini +++ b/platformio.ini @@ -77,6 +77,7 @@ default_src_filter = + - - + - - - - - - - + - - - - From ed0c5aefd8c79d88f5b5fb69baae161b58c72eae Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 7 Sep 2021 00:57:25 +0000 Subject: [PATCH 0643/2168] [cron] Bump distribution date (2021-09-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 45d4db7264..d11b20166e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-06" +//#define STRING_DISTRIBUTION_DATE "2021-09-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2dbbd144e7..3139e96475 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 "2021-09-06" + #define STRING_DISTRIBUTION_DATE "2021-09-07" #endif /** From 43a9c71ef7a1c9e9e294707017d372d344c774ce Mon Sep 17 00:00:00 2001 From: Jyers <76993396+Jyers@users.noreply.github.com> Date: Mon, 6 Sep 2021 21:06:27 -0700 Subject: [PATCH 0644/2168] =?UTF-8?q?=E2=9C=A8=20Ender-3=20V2=20with=20Jye?= =?UTF-8?q?rs=20UI=20(#22422)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 5 + Marlin/Configuration_adv.h | 2 +- Marlin/src/MarlinCore.cpp | 3 + Marlin/src/gcode/feature/powerloss/M1000.cpp | 4 + Marlin/src/inc/Conditionals_LCD.h | 10 +- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/Conditionals_post.h | 10 +- Marlin/src/inc/SanityCheck.h | 8 +- Marlin/src/lcd/buttons.h | 2 +- .../src/lcd/e3v2/creality/rotary_encoder.cpp | 9 +- Marlin/src/lcd/e3v2/jyersui/README.md | 7 + Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 5041 +++++++++++++++++ Marlin/src/lcd/e3v2/jyersui/dwin.h | 364 ++ Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp | 474 ++ Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 218 + .../src/lcd/e3v2/jyersui/rotary_encoder.cpp | 261 + Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h | 91 + Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/lcd/marlinui.cpp | 30 +- Marlin/src/lcd/marlinui.h | 15 +- Marlin/src/module/settings.cpp | 37 + Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 2 +- buildroot/tests/STM32F103RET6_creality | 5 + ini/features.ini | 1 + platformio.ini | 2 +- 29 files changed, 6575 insertions(+), 40 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/jyersui/README.md create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin.cpp create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin.h create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h create mode 100644 Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp create mode 100644 Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index fea0d51e5f..a424b1967e 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2756,6 +2756,11 @@ // //#define DWIN_CREALITY_LCD +// +// Ender-3 v2 OEM display with enhancements by Jacob Myers +// +//#define DWIN_CREALITY_LCD_JYERSUI + // // MarlinUI for Creality's DWIN display (and others) // diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 9e232f95bb..6857c4063b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1196,7 +1196,7 @@ // @section lcd -#if EITHER(IS_ULTIPANEL, EXTENSIBLE_UI) +#if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel #define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines #if IS_ULTIPANEL diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 6d4e0eab90..d68e87eb89 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -77,6 +77,9 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "lcd/e3v2/creality/dwin.h" #include "lcd/e3v2/creality/rotary_encoder.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "lcd/e3v2/jyersui/dwin.h" + #include "lcd/e3v2/jyersui/rotary_encoder.h" #endif #if ENABLED(EXTENSIBLE_UI) diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index ea92dc66b3..0e731016dd 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -30,6 +30,8 @@ #include "../../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented #endif #define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY) @@ -64,6 +66,8 @@ void GcodeSuite::M1000() { ui.goto_screen(menu_job_recovery); #elif ENABLED(DWIN_CREALITY_LCD) recovery.dwin_flag = true; + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) // Temporary fix until it can be better implemented + CrealityDWIN.Popup_Handler(Resume); #elif ENABLED(EXTENSIBLE_UI) ExtUI::onPowerLossResume(); #else diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 0715b1f514..825ad58f9a 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -493,6 +493,10 @@ #endif // Aliases for LCD features +#if ANY(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI) + #define HAS_DWIN_E3V2 1 +#endif + #if IS_ULTRA_LCD #define HAS_WIRED_LCD 1 #if ENABLED(DOGLCD) @@ -507,11 +511,11 @@ #endif #endif -#if EITHER(HAS_WIRED_LCD, EXTENSIBLE_UI) +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DISPLAY 1 #endif -#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD, GLOBAL_STATUS_MESSAGE) +#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2, GLOBAL_STATUS_MESSAGE) #define HAS_STATUS_MESSAGE 1 #endif @@ -1101,7 +1105,7 @@ #define HAS_ETHERNET 1 #endif -#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) #define SERIAL_CATCHALL 0 #ifndef LCD_SERIAL_PORT #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index c259750c6f..9fae92affe 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -594,7 +594,7 @@ #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif -#if ANY(EXTENSIBLE_UI, IS_NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, DWIN_CREALITY_LCD) +#if ANY(EXTENSIBLE_UI, IS_NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, HAS_DWIN_E3V2) #define HAS_RESUME_CONTINUE 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d82b651650..6de8dc9860 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -421,6 +421,10 @@ #endif #endif +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #define HAS_LCD_BRIGHTNESS 1 +#endif + /** * Override the SD_DETECT_STATE set in Configuration_adv.h * and enable sharing of onboard SD host drives (all platforms but AGCM4) @@ -2828,7 +2832,7 @@ #define HAS_TEMPERATURE 1 #endif -#if HAS_TEMPERATURE && EITHER(HAS_LCD_MENU, DWIN_CREALITY_LCD) +#if HAS_TEMPERATURE && EITHER(HAS_LCD_MENU, HAS_DWIN_E3V2) #ifdef PREHEAT_6_LABEL #define PREHEAT_COUNT 6 #elif defined(PREHEAT_5_LABEL) @@ -2949,7 +2953,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH @@ -3205,7 +3209,7 @@ #endif // Number of VFAT entries used. Each entry has 13 UTF-16 characters -#if EITHER(SCROLL_LONG_FILENAMES, DWIN_CREALITY_LCD) +#if EITHER(SCROLL_LONG_FILENAMES, HAS_DWIN_E3V2) #define MAX_VFAT_ENTRIES (5) #else #define MAX_VFAT_ENTRIES (2) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 75df13127c..59b4a68ff1 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -807,10 +807,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif PROGRESS_MSG_EXPIRE < 0 #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif -#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - #if NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, IS_DWIN_MARLINUI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, EXTENSIBLE_UI, OR DWIN MarlinUI." - #endif +#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, or EXTENSIBLE_UI." #endif #if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) @@ -2657,7 +2655,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ - + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h index f39cb0a9aa..6d028e9bc6 100644 --- a/Marlin/src/lcd/buttons.h +++ b/Marlin/src/lcd/buttons.h @@ -75,7 +75,7 @@ #endif #endif -#if EITHER(HAS_DIGITAL_BUTTONS, DWIN_CREALITY_LCD) +#if EITHER(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) #define BLEN_A 0 #define BLEN_B 1 diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp index 4fc10393b9..f46fef073e 100644 --- a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp @@ -122,8 +122,13 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { } if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; - else temp_diffState = ENCODER_DIFF_CCW; + #if ENABLED(REVERSE_ENCODER_DIRECTION) + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CCW; + else temp_diffState = ENCODER_DIFF_CW; + #else + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; + else temp_diffState = ENCODER_DIFF_CCW; + #endif #if ENABLED(ENCODER_RATE_MULTIPLIER) diff --git a/Marlin/src/lcd/e3v2/jyersui/README.md b/Marlin/src/lcd/e3v2/jyersui/README.md new file mode 100644 index 0000000000..10b05455fd --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/README.md @@ -0,0 +1,7 @@ +# DWIN for Creality Ender 3 v2 + +Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x/config/examples/Creality/Ender-3%20V2). + +## Easy Install + +Copy the `DWIN_SET` folder onto a Micro-SD card and insert the card into the slot on the DWIN screen. Cycle the machine and wait for the screen to go from blue to orange. Turn the machine off and remove the SD card. When you turn on the machine the screen will display a "Creality" loading screen. diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp new file mode 100644 index 0000000000..e41e51bee4 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -0,0 +1,5041 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * lcd/e3v2/jyersui/dwin.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + +#include "dwin.h" + +#include "../../marlinui.h" +#include "../../../MarlinCore.h" + +#include "../../../module/temperature.h" +#include "../../../module/planner.h" +#include "../../../module/settings.h" +#include "../../../libs/buzzer.h" +#include "../../../inc/Conditionals_post.h" + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #include "../../../feature/pause.h" +#endif + +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #include "../../../feature/runout.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../../feature/host_actions.h" +#endif + +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 +#endif + +#ifndef strcasecmp_P + #define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif + +#if HAS_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../../libs/least_squares_fit.h" + #include "../../../libs/vector_3.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +#if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT + #define HAS_PREHEAT 1 +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) + +#ifndef CORP_WEBSITE + #define CORP_WEBSITE WEBSITE_URL + #endif + +#define DWIN_FONT_MENU font8x16 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 + +#define MENU_CHAR_LIMIT 24 +#define STATUS_Y 352 + +#define MAX_PRINT_SPEED 500 +#define MIN_PRINT_SPEED 10 + +#if HAS_FAN + #define MAX_FAN_SPEED 255 + #define MIN_FAN_SPEED 0 +#endif + +#define MAX_XY_OFFSET 100 + +#if HAS_ZOFFSET_ITEM + #define MAX_Z_OFFSET 9.99 + #if HAS_BED_PROBE + #define MIN_Z_OFFSET -9.99 + #else + #define MIN_Z_OFFSET -1 + #endif +#endif + +#if HAS_HOTEND + #define MAX_FLOW_RATE 200 + #define MIN_FLOW_RATE 10 + + #define MAX_E_TEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) + #define MIN_E_TEMP 0 +#endif + +#if HAS_HEATED_BED + #define MAX_BED_TEMP BED_MAXTEMP + #define MIN_BED_TEMP 0 +#endif + +constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, + TITLE_HEIGHT = 30, + MLINE = 53, + LBLX = 60, + MENU_CHR_W = 8, MENU_CHR_H = 16, STAT_CHR_W = 10; + +#define MBASE(L) (49 + MLINE * (L)) + +constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; +constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; +constexpr float default_steps[] = DEFAULT_AXIS_STEPS_PER_UNIT; +#if HAS_CLASSIC_JERK + constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; +#endif + +uint8_t active_menu = MainMenu; +uint8_t last_menu = MainMenu; +uint8_t selection = 0; +uint8_t last_selection = 0; +uint8_t scrollpos = 0; +uint8_t process = Main; +uint8_t last_process = Main; +PopupID popup; +PopupID last_popup; + +void (*funcpointer)() = nullptr; +void *valuepointer = nullptr; +float tempvalue; +float valuemin; +float valuemax; +uint8_t valueunit; +uint8_t valuetype; + +char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; +char statusmsg[64]; +char filename[LONG_FILENAME_LENGTH]; +bool printing = false; +bool paused = false; +bool sdprint = false; + +int16_t pausetemp, pausebed, pausefan; + +bool livemove = false; +bool liveadjust = false; +uint8_t preheatmode = 0; +float zoffsetvalue = 0; +uint8_t gridpoint; +float corner_avg; +float corner_pos; + +bool probe_deployed = false; + +CrealityDWINClass CrealityDWIN; + +#if HAS_MESH + struct Mesh_Settings { + bool viewer_asymmetric_range = false; + bool viewer_print_value = false; + bool goto_mesh_value = false; + bool drawing_mesh = false; + uint8_t mesh_x = 0; + uint8_t mesh_y = 0; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + bed_mesh_t &mesh_z_values = ubl.z_values; + uint8_t tilt_grid = 1; + + void manual_value_update(bool undefined=false) { + sprintf_P(cmd, PSTR("M421 I%i J%i Z%s %s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1), undefined ? "N" : ""); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + } + + bool create_plane_from_mesh() { + struct linear_fit_data lsf_results; + incremental_LSF_reset(&lsf_results); + GRID_LOOP(x, y) { + if (!isnan(mesh_z_values[x][y])) { + xy_pos_t rpos; + rpos.x = ubl.mesh_index_to_xpos(x); + rpos.y = ubl.mesh_index_to_ypos(y); + incremental_LSF(&lsf_results, rpos, mesh_z_values[x][y]); + } + } + + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOPGM("Could not complete LSF!"); + return true; + } + + ubl.set_all_mesh_points_to_value(0); + + matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); + GRID_LOOP(i, j) { + float mx = ubl.mesh_index_to_xpos(i), + my = ubl.mesh_index_to_ypos(j), + mz = mesh_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); + } + + rotation.apply_rotation_xyz(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); + } + + mesh_z_values[i][j] = mz - lsf_results.D; + } + return false; + } + + #else + bed_mesh_t &mesh_z_values = z_values; + + void manual_value_update() { + sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + } + + #endif + + void manual_move(bool zmove=false) { + if (zmove) { + planner.synchronize(); + current_position.z = goto_mesh_value ? mesh_z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + } + else { + CrealityDWIN.Popup_Handler(MoveWait); + sprintf_P(cmd, PSTR("G0 F300 Z%s"), dtostrf(Z_CLEARANCE_BETWEEN_PROBES, 1, 3, str_1)); + gcode.process_subcommands_now_P(cmd); + sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + current_position.z = goto_mesh_value ? mesh_z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + CrealityDWIN.Redraw_Menu(); + } + } + + float get_max_value() { + float max = __FLT_MIN__; + GRID_LOOP(x, y) { + if (!isnan(mesh_z_values[x][y]) && mesh_z_values[x][y] > max) + max = mesh_z_values[x][y]; + } + return max; + } + + float get_min_value() { + float min = __FLT_MAX__; + GRID_LOOP(x, y) { + if (!isnan(mesh_z_values[x][y]) && mesh_z_values[x][y] < min) + min = mesh_z_values[x][y]; + } + return min; + } + + void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7) { + drawing_mesh = true; + const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x; + const uint16_t cell_width_px = total_width_px / GRID_MAX_POINTS_X; + const uint16_t cell_height_px = total_width_px / GRID_MAX_POINTS_Y; + const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = max(v_min, v_max); + + // Clear background from previous selection and select new square + DWIN_Draw_Rectangle(1, Color_Bg_Black, max(0, padding_x - gridline_width), max(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); + if (selected >= 0) { + const auto selected_y = selected / GRID_MAX_POINTS_X; + const auto selected_x = selected - (GRID_MAX_POINTS_X * selected_y); + const auto start_y_px = padding_y_top + selected_y * cell_height_px; + const auto start_x_px = padding_x + selected_x * cell_width_px; + DWIN_Draw_Rectangle(1, Color_White, max(0, start_x_px - gridline_width), max(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); + } + + // Draw value square grid + char buf[8]; + GRID_LOOP(x, y) { + const auto start_x_px = padding_x + x * cell_width_px; + const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; + const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px; + const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; + DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ + isnan(mesh_z_values[x][y]) ? Color_Grey : ( // gray if undefined + (mesh_z_values[x][y] < 0 ? + (uint16_t)round(0b11111 * -mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)round(0b111111 * mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive + min(0b11111, (((uint8_t)abs(mesh_z_values[x][y]) / 10) * 4))), // + blue stepping for every mm + start_x_px, start_y_px, end_x_px, end_y_px); + while (LCD_SERIAL.availableForWrite() < 32) { // wait for serial to be available without blocking and resetting the MCU + gcode.process_subcommands_now_P("G4 P10"); + planner.synchronize(); + } + // Draw value text on + if (viewer_print_value) { + gcode.process_subcommands_now_P("G4 P10"); // still fails without additional delay... + planner.synchronize(); + int8_t offset_x, offset_y = cell_height_px / 2 - 6; + if (isnan(mesh_z_values[x][y])) { // undefined + DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); + } + else { // has value + if (GRID_MAX_POINTS_X < 10) + sprintf_P(buf, PSTR("%s"), dtostrf(abs(mesh_z_values[x][y]), 1, 2, str_1)); + else + sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(mesh_z_values[x][y] - (int16_t)mesh_z_values[x][y]) * 100)); + offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; + if (!(GRID_MAX_POINTS_X < 10)) + DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); + DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); + } + } + } + } + + void Set_Mesh_Viewer_Status() { // TODO: draw gradient with values as a legend instead + float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = max(v_min, v_max); + if (v_min > 3e+10F) v_min = 0.0000001; + if (v_max > 3e+10F) v_max = 0.0000001; + if (range > 3e+10F) range = 0.0000001; + char msg[32]; + if (viewer_asymmetric_range) { + dtostrf(-v_min, 1, 3, str_1); + dtostrf( v_max, 1, 3, str_2); + } + else { + dtostrf(-range, 1, 3, str_1); + dtostrf( range, 1, 3, str_2); + } + sprintf_P(msg, PSTR("Red %s..0..%s Green"), str_1, str_2); + CrealityDWIN.Update_Status(msg); + drawing_mesh = false; + } + + }; + Mesh_Settings mesh_conf; +#endif + +/* General Display Functions */ + +struct CrealityDWINClass::EEPROM_Settings CrealityDWINClass::eeprom_settings{0}; +constexpr const char * const CrealityDWINClass::color_names[11]; +constexpr const char * const CrealityDWINClass::preheat_modes[3]; + +// Clear a part of the screen +// 4=Entire screen +// 3=Title bar and Menu area (default) +// 2=Menu area +// 1=Title bar +void CrealityDWINClass::Clear_Screen(uint8_t e/*=3*/) { + if (e == 1 || e == 3 || e == 4) DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.menu_top_bg, Color_Bg_Blue, false), 0, 0, DWIN_WIDTH, TITLE_HEIGHT); // Clear Title Bar + if (e == 2 || e == 3) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); // Clear Menu Area + if (e == 4) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); // Clear Popup Area +} + +void CrealityDWINClass::Draw_Float(float value, uint8_t row, bool selected/*=false*/, uint8_t minunit/*=10*/) { + const uint8_t digits = (uint8_t)floor(log10(abs(value))) + log10(minunit) + (minunit > 1); + const uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; + const uint16_t xpos = 240 - (digits * 8); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 194, MBASE(row), 234 - (digits * 8), MBASE(row) + 16); + if (isnan(value)) { + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" NaN")); + } + else if (value < 0) { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), -value * minunit); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F("-")); + } + else { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), value * minunit); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" ")); + } +} + +void CrealityDWINClass::Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected/*=false*/, bool color/*=false*/) { + uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; + uint16_t tColor = (color) ? GetColor(value, Color_White, false) : Color_White; + DWIN_Draw_Rectangle(1, bColor, 202, MBASE(row) + 14, 258, MBASE(row) - 2); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, tColor, bColor, 202, MBASE(row) - 1, options[value]); +} + +uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool light/*=false*/) { + switch (color){ + case Default: + return original; + break; + case White: + return (light) ? Color_Light_White : Color_White; + break; + case Green: + return (light) ? Color_Light_Green : Color_Green; + break; + case Cyan: + return (light) ? Color_Light_Cyan : Color_Cyan; + break; + case Blue: + return (light) ? Color_Light_Blue : Color_Blue; + break; + case Magenta: + return (light) ? Color_Light_Magenta : Color_Magenta; + break; + case Red: + return (light) ? Color_Light_Red : Color_Red; + break; + case Orange: + return (light) ? Color_Light_Orange : Color_Orange; + break; + case Yellow: + return (light) ? Color_Light_Yellow : Color_Yellow; + break; + case Brown: + return (light) ? Color_Light_Brown : Color_Brown; + break; + case Black: + return Color_Black; + break; + } + return Color_White; +} + +void CrealityDWINClass::Draw_Title(const char * title) { + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(title) * STAT_CHR_W) / 2, 5, title); +} + +void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { + const uint8_t label_offset_y = !(label1 && label2) ? 0 : MENU_CHR_H * 3 / 5; + const uint8_t label1_offset_x = !centered ? LBLX : LBLX * 4/5 + max(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2); + const uint8_t label2_offset_x = !centered ? LBLX : LBLX * 4/5 + max(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); + if (label1) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label + if (label2) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label + if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon + if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow + DWIN_Draw_Line(GetColor(eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line +} + +void CrealityDWINClass::Draw_Checkbox(uint8_t row, bool value) { + #if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) // Draw appropriate checkbox icon + DWIN_ICON_Show(ICON, (value ? ICON_Checkbox_T : ICON_Checkbox_F), 226, MBASE(row) - 3); + #else // Draw a basic checkbox using rectangles and lines + DWIN_Draw_Rectangle(1, Color_Bg_Black, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); + DWIN_Draw_Rectangle(0, Color_White, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); + if (value) { + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 11, 226 + 8, MBASE(row) - 3 + 17); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 17, 226 + 19, MBASE(row) - 3 + 1); + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 12, 226 + 8, MBASE(row) - 3 + 18); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 18, 226 + 19, MBASE(row) - 3 + 2); + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 13, 226 + 8, MBASE(row) - 3 + 19); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 19, 226 + 19, MBASE(row) - 3 + 3); + } + #endif +} + +void CrealityDWINClass::Draw_Menu(uint8_t menu, uint8_t select/*=0*/, uint8_t scroll/*=0*/) { + if (active_menu != menu) { + last_menu = active_menu; + if (process == Menu) last_selection = selection; + } + selection = min(select, Get_Menu_Size(menu)); + scrollpos = scroll; + if (selection - scrollpos > MROWS) + scrollpos = selection - MROWS; + process = Menu; + active_menu = menu; + Clear_Screen(); + Draw_Title(Get_Menu_Title(menu)); + LOOP_L_N(i, TROWS) Menu_Item_Handler(menu, i + scrollpos); + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); +} + +void CrealityDWINClass::Redraw_Menu(bool lastprocess/*=true*/, bool lastselection/*=false*/, bool lastmenu/*=false*/) { + switch ((lastprocess) ? last_process : process) { + case Menu: + Draw_Menu((lastmenu) ? last_menu : active_menu, (lastselection) ? last_selection : selection, (lastmenu) ? 0 : scrollpos); + break; + case Main: Draw_Main_Menu((lastselection) ? last_selection : selection); break; + case Print: Draw_Print_Screen(); break; + case File: Draw_SD_List(); break; + default: break; + } +} + +void CrealityDWINClass::Redraw_Screen() { + Redraw_Menu(false); + Draw_Status_Area(true); + Update_Status_Bar(true); +} + +/* Primary Menus and Screen Elements */ + +void CrealityDWINClass::Main_Menu_Icons() { + if (selection == 0) { + DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 130, 126, 229); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + } + else { + DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + } + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 130, 254, 229); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + } + else { + DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + } + if (selection == 2) { + DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 246, 126, 345); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + } + else { + DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + } + #if HAS_ABL_OR_UBL + if (selection == 3) { + DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + } + else { + DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + } + #else + if (selection == 3) { + DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); + } + else { + DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); + //DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); + } + #endif +} + +void CrealityDWINClass::Draw_Main_Menu(uint8_t select/*=0*/) { + process = Main; + active_menu = MainMenu; + selection = select; + Clear_Screen(); + Draw_Title(Get_Menu_Title(MainMenu)); + SERIAL_ECHOPGM("\nDWIN handshake "); + DWIN_ICON_Show(ICON, ICON_LOGO, 71, 72); + Main_Menu_Icons(); +} + +void CrealityDWINClass::Print_Screen_Icons() { + if (selection == 0) { + DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 8, 252, 87, 351); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + } + else { + DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + } + if (selection == 2) { + DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 184, 252, 263, 351); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + } + else { + DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + } + if (paused) { + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + } + else { + DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + } + } + else { + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + } + else { + DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + } + } +} + +void CrealityDWINClass::Draw_Print_Screen() { + process = Print; + selection = 0; + Clear_Screen(); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + Draw_Title("Printing..."); + Print_Screen_Icons(); + DWIN_ICON_Show(ICON, ICON_PrintTime, 14, 171); + DWIN_ICON_Show(ICON, ICON_RemainTime, 147, 169); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 41, 163, "Elapsed"); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 176, 163, "Remaining"); + Update_Status_Bar(true); + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); + Draw_Print_Filename(true); +} + +void CrealityDWINClass::Draw_Print_Filename(const bool reset/*=false*/) { + static uint8_t namescrl = 0; + if (reset) namescrl = 0; + if (process == Print) { + size_t len = strlen(filename); + int8_t pos = len; + if (pos > 30) { + pos -= namescrl; + len = _MIN(pos, 30); + char dispname[len + 1]; + if (pos >= 0) { + LOOP_L_N(i, len) dispname[i] = filename[i + namescrl]; + } + else { + LOOP_L_N(i, 30 + pos) dispname[i] = ' '; + LOOP_S_L_N(i, 30 + pos, 30) dispname[i] = filename[i - (30 + pos)]; + } + dispname[len] = '\0'; + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); + const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, dispname); + if (-pos >= 30) namescrl = 0; + namescrl++; + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); + const int8_t npos = (DWIN_WIDTH - strlen(filename) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, filename); + } + } +} + +void CrealityDWINClass::Draw_Print_ProgressBar() { + uint8_t printpercent = sdprint ? card.percentDone() : (ui._get_progress() / 100); + DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); + DWIN_Draw_Rectangle(1, BarFill_Color, 16 + printpercent * 240 / 100, 93, 256, 113); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 3, 109, 133, printpercent); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 133, 133, "%"); +} + +#if ENABLED(USE_M73_REMAINING_TIME) + + void CrealityDWINClass::Draw_Print_ProgressRemain() { + uint16_t remainingtime = ui.get_remaining_time(); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 176, 187, remainingtime / 3600); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 200, 187, (remainingtime % 3600) / 60); + if (eeprom_settings.time_format_textual) { + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, "h"); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 216, 187, "m"); + } + else + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, ":"); + } + +#endif + +void CrealityDWINClass::Draw_Print_ProgressElapsed() { + duration_t elapsed = print_job_timer.duration(); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 42, 187, elapsed.value / 3600); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 66, 187, (elapsed.value % 3600) / 60); + if (eeprom_settings.time_format_textual) { + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, "h"); + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 82, 187, "m"); + } + else + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, ":"); +} + +void CrealityDWINClass::Draw_Print_confirm() { + Draw_Print_Screen(); + process = Confirm; + popup = Complete; + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 252, 263, 351); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 87, 283); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 86, 282, 187, 321); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 85, 281, 188, 322); +} + +void CrealityDWINClass::Draw_SD_Item(uint8_t item, uint8_t row) { + if (item == 0) + Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? "Back" : ".."); + else { + card.getfilename_sorted(SD_ORDER(item - 1, card.get_num_Files())); + char * const filename = card.longest_filename(); + size_t max = MENU_CHAR_LIMIT; + size_t pos = strlen(filename), len = pos; + if (!card.flag.filenameIsDir) + while (pos && filename[pos] != '.') pos--; + len = pos; + if (len > max) len = max; + char name[len + 1]; + LOOP_L_N(i, len) name[i] = filename[i]; + if (pos > max) + LOOP_S_L_N(i, len - 3, len) name[i] = '.'; + name[len] = '\0'; + Draw_Menu_Item(row, card.flag.filenameIsDir ? ICON_More : ICON_File, name); + } +} + +void CrealityDWINClass::Draw_SD_List(bool removed/*=false*/) { + Clear_Screen(); + Draw_Title("Select File"); + selection = 0; + scrollpos = 0; + process = File; + if (card.isMounted() && !removed) { + LOOP_L_N(i, _MIN(card.get_num_Files() + 1, TROWS)) + Draw_SD_Item(i, i); + } + else { + Draw_Menu_Item(0, ICON_Back, "Back"); + DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); + DWIN_Draw_String(false, false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), "No Media"); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(0) - 18, 14, MBASE(0) + 33); +} + +void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { + + if (icons) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + + #if HAS_HOTEND + static float hotend = -1; + static int16_t hotendtarget = -1, flow = -1; + if (icons) { + hotend = -1; + hotendtarget = -1; + DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + } + if (thermalManager.temp_hotend[0].celsius != hotend) { + hotend = thermalManager.temp_hotend[0].celsius; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 384, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 386); + } + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.temp_hotend[0].target); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 386); + } + if (icons) { + flow = -1; + DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + } + if (planner.flow_percentage[0] != flow) { + flow = planner.flow_percentage[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); + } + #endif + + #if HAS_HEATED_BED + static float bed = -1; + static int16_t bedtarget = -1; + if (icons) { + bed = -1; + bedtarget = -1; + DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + } + if (thermalManager.temp_bed.celsius != bed) { + bed = thermalManager.temp_bed.celsius; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 417, thermalManager.temp_bed.celsius); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 419); + } + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.temp_bed.target); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 419); + } + #endif + + #if HAS_FAN + static uint8_t fan = -1; + if (icons) { + fan = -1; + DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); + } + if (thermalManager.fan_speed[0] != fan) { + fan = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); + } + #endif + + #if HAS_ZOFFSET_ITEM + static float offset = -1; + + if (icons) { + offset = -1; + DWIN_ICON_Show(ICON, ICON_Zoffset, 187, 416); + } + if (zoffsetvalue != offset) { + offset = zoffsetvalue; + if (zoffsetvalue < 0) { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, -zoffsetvalue * 100); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, "-"); + } + else { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, zoffsetvalue* 100); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, " "); + } + } + #endif + + static int16_t feedrate = -1; + if (icons) { + feedrate = -1; + DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + } + if (feedrate_percentage != feedrate) { + feedrate = feedrate_percentage; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); + } + + static float x = -1, y = -1, z = -1; + static bool update_x = false, update_y = false, update_z = false; + update_x = (current_position.x != x || axis_should_home(X_AXIS) || update_x); + update_y = (current_position.y != y || axis_should_home(Y_AXIS) || update_y); + update_z = (current_position.z != z || axis_should_home(Z_AXIS) || update_z); + if (icons) { + x = y = z = -1; + DWIN_Draw_Line(GetColor(eeprom_settings.coordinates_split_line, Line_Color, true), 16, 450, 256, 450); + DWIN_ICON_Show(ICON, ICON_MaxSpeedX, 10, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedY, 95, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedZ, 180, 456); + } + if (update_x) { + x = current_position.x; + if ((update_x = axis_should_home(X_AXIS) && ui.get_blink())) + DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 35, 459, " -?- "); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 35, 459, current_position.x * 10); + } + if (update_y) { + y = current_position.y; + if ((update_y = axis_should_home(Y_AXIS) && ui.get_blink())) + DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 120, 459, " -?- "); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 120, 459, current_position.y * 10); + } + if (update_z) { + z = current_position.z; + if ((update_z = axis_should_home(Z_AXIS) && ui.get_blink())) + DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 205, 459, " -?- "); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 2, 205, 459, (current_position.z>=0) ? current_position.z * 100 : 0); + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P const line3, uint8_t mode, uint8_t icon/*=0*/) { + if (process != Confirm && process != Popup && process != Wait) last_process = process; + if ((process == Menu || process == Wait) && mode == Popup) last_selection = selection; + process = mode; + Clear_Screen(); + DWIN_Draw_Rectangle(0, Color_White, 13, 59, 259, 351); + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 350); + const uint8_t ypos = (mode == Popup || mode == Confirm) ? 150 : 230; + if (icon > 0) DWIN_ICON_Show(ICON, icon, 101, 105); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line1)) / 2, ypos, line1); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line2)) / 2, ypos + 30, line2); + DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line3)) / 2, ypos + 60, line3); + if (mode == Popup) { + selection = 0; + DWIN_Draw_Rectangle(1, Confirm_Color, 26, 280, 125, 317); + DWIN_Draw_Rectangle(1, Cancel_Color, 146, 280, 245, 317); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 39, 290, "Confirm"); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 165, 290, "Cancel"); + Popup_Select(); + } + else if (mode == Confirm) { + DWIN_Draw_Rectangle(1, Confirm_Color, 87, 280, 186, 317); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 96, 290, "Continue"); + } +} + +void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { + CrealityDWIN.Draw_Popup(PSTR("Printer Kill Reason:"), error, PSTR("Restart Required"), Wait, ICON_BLTouch); +} + +void CrealityDWINClass::Popup_Select() { + const uint16_t c1 = (selection == 0) ? GetColor(eeprom_settings.highlight_box, Color_White) : Color_Bg_Window, + c2 = (selection == 0) ? Color_Bg_Window : GetColor(eeprom_settings.highlight_box, Color_White); + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { + static bool new_msg; + static uint8_t msgscrl = 0; + static char lastmsg[64]; + if (strcmp_P(lastmsg, statusmsg) != 0 || refresh) { + strcpy_P(lastmsg, statusmsg); + msgscrl = 0; + new_msg = true; + } + size_t len = strlen(statusmsg); + int8_t pos = len; + if (pos > 30) { + pos -= msgscrl; + len = pos; + if (len > 30) + len = 30; + char dispmsg[len + 1]; + if (pos >= 0) { + LOOP_L_N(i, len) dispmsg[i] = statusmsg[i + msgscrl]; + } + else { + LOOP_L_N(i, 30 + pos) dispmsg[i] = ' '; + LOOP_S_L_N(i, 30 + pos, 30) dispmsg[i] = statusmsg[i - (30 + pos)]; + } + dispmsg[len] = '\0'; + if (process == Print) { + DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); + const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, dispmsg); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, dispmsg); + } + if (-pos >= 30) msgscrl = 0; + msgscrl++; + } + else { + if (new_msg) { + new_msg = false; + if (process == Print) { + DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); + const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, statusmsg); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, statusmsg); + } + } + } +} + +/* Menu Item Config */ + +void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/*=true*/) { + uint8_t row = item - scrollpos; + #if HAS_LEVELING + static bool level_state; + #endif + switch (menu) { + case Prepare: + + #define PREPARE_BACK 0 + #define PREPARE_MOVE (PREPARE_BACK + 1) + #define PREPARE_DISABLE (PREPARE_MOVE + 1) + #define PREPARE_HOME (PREPARE_DISABLE + 1) + #define PREPARE_MANUALLEVEL (PREPARE_HOME + 1) + #define PREPARE_ZOFFSET (PREPARE_MANUALLEVEL + ENABLED(HAS_ZOFFSET_ITEM)) + #define PREPARE_PREHEAT (PREPARE_ZOFFSET + ENABLED(HAS_PREHEAT)) + #define PREPARE_COOLDOWN (PREPARE_PREHEAT + ENABLED(HAS_PREHEAT)) + #define PREPARE_CHANGEFIL (PREPARE_COOLDOWN + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define PREPARE_TOTAL PREPARE_CHANGEFIL + + switch (item) { + case PREPARE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Main_Menu(1); + break; + case PREPARE_MOVE: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Move", nullptr, true); + else + Draw_Menu(Move); + break; + case PREPARE_DISABLE: + if (draw) + Draw_Menu_Item(row, ICON_CloseMotor, "Disable Stepper"); + else + queue.inject_P(PSTR("M84")); + break; + case PREPARE_HOME: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, "Homing", nullptr, true); + else + Draw_Menu(HomeMenu); + break; + case PREPARE_MANUALLEVEL: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, "Manual Leveling", nullptr, true); + else { + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + #if HAS_LEVELING + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif + Draw_Menu(ManualLevel); + } + break; + + #if HAS_ZOFFSET_ITEM + case PREPARE_ZOFFSET: + if (draw) + Draw_Menu_Item(row, ICON_Zoffset, "Z-Offset", nullptr, true); + else { + #if HAS_LEVELING + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif + Draw_Menu(ZOffset); + } + break; + #endif + + #if HAS_PREHEAT + case PREPARE_PREHEAT: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, "Preheat", nullptr, true); + else + Draw_Menu(Preheat); + break; + case PREPARE_COOLDOWN: + if (draw) + Draw_Menu_Item(row, ICON_Cool, "Cooldown"); + else { + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + thermalManager.disable_all_heaters(); + } + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case PREPARE_CHANGEFIL: + if (draw) { + Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament" + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + , nullptr, true + #endif + ); + } + else { + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + Draw_Menu(ChangeFilament); + #else + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now_P(cmd); + } + #endif + } + break; + #endif + } + break; + + case HomeMenu: + + #define HOME_BACK 0 + #define HOME_ALL (HOME_BACK + 1) + #define HOME_X (HOME_ALL + 1) + #define HOME_Y (HOME_X + 1) + #define HOME_Z (HOME_Y + 1) + #define HOME_SET (HOME_Z + 1) + #define HOME_TOTAL HOME_SET + + switch (item) { + case HOME_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Prepare, PREPARE_HOME); + break; + case HOME_ALL: + if (draw) + Draw_Menu_Item(row, ICON_Homing, "Home All"); + else { + Popup_Handler(Home); + gcode.home_all_axes(true); + Redraw_Menu(); + } + break; + case HOME_X: + if (draw) + Draw_Menu_Item(row, ICON_MoveX, "Home X"); + else { + Popup_Handler(Home); + gcode.process_subcommands_now_P(PSTR("G28 X")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_Y: + if (draw) + Draw_Menu_Item(row, ICON_MoveY, "Home Y"); + else { + Popup_Handler(Home); + gcode.process_subcommands_now_P(PSTR("G28 Y")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_Z: + if (draw) + Draw_Menu_Item(row, ICON_MoveZ,"Home Z"); + else { + Popup_Handler(Home); + gcode.process_subcommands_now_P(PSTR("G28 Z")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_SET: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, "Set Home Position"); + else { + gcode.process_subcommands_now_P(PSTR("G92 X0 Y0 Z0")); + AudioFeedback(); + } + break; + } + break; + + case Move: + + #define MOVE_BACK 0 + #define MOVE_X (MOVE_BACK + 1) + #define MOVE_Y (MOVE_X + 1) + #define MOVE_Z (MOVE_Y + 1) + #define MOVE_E (MOVE_Z + ENABLED(HAS_HOTEND)) + #define MOVE_P (MOVE_E + ENABLED(HAS_BED_PROBE)) + #define MOVE_LIVE (MOVE_P + 1) + #define MOVE_TOTAL MOVE_LIVE + + switch (item) { + case MOVE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else { + #if HAS_BED_PROBE + probe_deployed = false; + probe.set_deployed(probe_deployed); + #endif + Draw_Menu(Prepare, PREPARE_MOVE); + } + break; + case MOVE_X: + if (draw) { + Draw_Menu_Item(row, ICON_MoveX, "Move X"); + Draw_Float(current_position.x, row, false); + } + else + Modify_Value(current_position.x, X_MIN_POS, X_MAX_POS, 10); + break; + case MOVE_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MoveY, "Move Y"); + Draw_Float(current_position.y, row); + } + else + Modify_Value(current_position.y, Y_MIN_POS, Y_MAX_POS, 10); + break; + case MOVE_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MoveZ, "Move Z"); + Draw_Float(current_position.z, row); + } + else + Modify_Value(current_position.z, Z_MIN_POS, Z_MAX_POS, 10); + break; + + #if HAS_HOTEND + case MOVE_E: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, "Extruder"); + current_position.e = 0; + sync_plan_position(); + Draw_Float(current_position.e, row); + } + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { + Popup_Handler(ETemp); + } + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + Redraw_Menu(); + } + current_position.e = 0; + sync_plan_position(); + Modify_Value(current_position.e, -500, 500, 10); + } + } + break; + #endif // HAS_HOTEND + + #if HAS_BED_PROBE + case MOVE_P: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguraton, "Probe"); + Draw_Checkbox(row, probe_deployed); + } + else { + probe_deployed = !probe_deployed; + probe.set_deployed(probe_deployed); + Draw_Checkbox(row, probe_deployed); + } + break; + #endif + + case MOVE_LIVE: + if (draw) { + Draw_Menu_Item(row, ICON_Axis, "Live Movement"); + Draw_Checkbox(row, livemove); + } + else { + livemove = !livemove; + Draw_Checkbox(row, livemove); + } + break; + } + break; + case ManualLevel: + + #define MLEVEL_BACK 0 + #define MLEVEL_PROBE (MLEVEL_BACK + ENABLED(HAS_BED_PROBE)) + #define MLEVEL_BL (MLEVEL_PROBE + 1) + #define MLEVEL_TL (MLEVEL_BL + 1) + #define MLEVEL_TR (MLEVEL_TL + 1) + #define MLEVEL_BR (MLEVEL_TR + 1) + #define MLEVEL_C (MLEVEL_BR + 1) + #define MLEVEL_ZPOS (MLEVEL_C + 1) + #define MLEVEL_TOTAL MLEVEL_ZPOS + + static float mlev_z_pos = 0; + static bool use_probe = false; + + switch (item) { + case MLEVEL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else { + TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); + Draw_Menu(Prepare, PREPARE_MANUALLEVEL); + } + break; + #if HAS_BED_PROBE + case MLEVEL_PROBE: + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, "Use Probe"); + Draw_Checkbox(row, use_probe); + } + else { + use_probe = !use_probe; + Draw_Checkbox(row, use_probe); + if (use_probe) { + Popup_Handler(Level); + corner_avg = 0; + #define PROBE_X_MIN _MAX(0 + corner_pos, X_MIN_POS + probe.offset.x, X_MIN_POS + PROBING_MARGIN) - probe.offset.x + #define PROBE_X_MAX _MIN((X_BED_SIZE + X_MIN_POS) - corner_pos, X_MAX_POS + probe.offset.x, X_MAX_POS - PROBING_MARGIN) - probe.offset.x + #define PROBE_Y_MIN _MAX(0 + corner_pos, Y_MIN_POS + probe.offset.y, Y_MIN_POS + PROBING_MARGIN) - probe.offset.y + #define PROBE_Y_MAX _MIN((Y_BED_SIZE + Y_MIN_POS) - corner_pos, Y_MAX_POS + probe.offset.y, Y_MAX_POS - PROBING_MARGIN) - probe.offset.y + corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MIN, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MIN, PROBE_PT_STOW, 0, false); + corner_avg /= 4; + Redraw_Menu(); + } + } + break; + #endif + case MLEVEL_BL: + if (draw) + Draw_Menu_Item(row, ICON_AxisBL, "Bottom Left"); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_TL: + if (draw) + Draw_Menu_Item(row, ICON_AxisTL, "Top Left"); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_TR: + if (draw) + Draw_Menu_Item(row, ICON_AxisTR, "Top Right"); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_BR: + if (draw) + Draw_Menu_Item(row, ICON_AxisBR, "Bottom Right"); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_C: + if (draw) + Draw_Menu_Item(row, ICON_AxisC, "Center"); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(X_MAX_POS / 2.0f - probe.offset.x, 1, 3, str_1), dtostrf(Y_MAX_POS / 2.0f - probe.offset.y, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_ZPOS: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, "Z Position"); + Draw_Float(mlev_z_pos, row, false, 100); + } + else + Modify_Value(mlev_z_pos, 0, MAX_Z_OFFSET, 100); + break; + } + break; + #if HAS_ZOFFSET_ITEM + case ZOffset: + + #define ZOFFSET_BACK 0 + #define ZOFFSET_HOME (ZOFFSET_BACK + 1) + #define ZOFFSET_MODE (ZOFFSET_HOME + 1) + #define ZOFFSET_OFFSET (ZOFFSET_MODE + 1) + #define ZOFFSET_UP (ZOFFSET_OFFSET + 1) + #define ZOFFSET_DOWN (ZOFFSET_UP + 1) + #define ZOFFSET_SAVE (ZOFFSET_DOWN + ENABLED(EEPROM_SETTINGS)) + #define ZOFFSET_TOTAL ZOFFSET_SAVE + + switch (item) { + case ZOFFSET_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else { + liveadjust = false; + TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); + Draw_Menu(Prepare, PREPARE_ZOFFSET); + } + break; + case ZOFFSET_HOME: + if (draw) + Draw_Menu_Item(row, ICON_Homing, "Home Z Axis"); + else { + Popup_Handler(Home); + gcode.process_subcommands_now_P(PSTR("G28 Z")); + Popup_Handler(MoveWait); + #if ENABLED(Z_SAFE_HOMING) + planner.synchronize(); + sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + #else + gcode.process_subcommands_now_P(PSTR("G0 F4000 X117.5 Y117.5")); + #endif + gcode.process_subcommands_now_P(PSTR("G0 F300 Z0")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case ZOFFSET_MODE: + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, "Live Adjustment"); + Draw_Checkbox(row, liveadjust); + } + else { + if (!liveadjust) { + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + Popup_Handler(MoveWait); + #if ENABLED(Z_SAFE_HOMING) + planner.synchronize(); + sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); + gcode.process_subcommands_now_P(cmd); + #else + gcode.process_subcommands_now_P(PSTR("G0 F4000 X117.5 Y117.5")); + #endif + gcode.process_subcommands_now_P(PSTR("G0 F300 Z0")); + planner.synchronize(); + Redraw_Menu(); + } + liveadjust = !liveadjust; + Draw_Checkbox(row, liveadjust); + } + break; + case ZOFFSET_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, "Z Offset"); + Draw_Float(zoffsetvalue, row, false, 100); + } + else + Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case ZOFFSET_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + else { + if (zoffsetvalue < MAX_Z_OFFSET) { + if (liveadjust) { + gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + planner.synchronize(); + } + zoffsetvalue += 0.01; + Draw_Float(zoffsetvalue, row - 1, false, 100); + } + } + break; + case ZOFFSET_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + else { + if (zoffsetvalue > MIN_Z_OFFSET) { + if (liveadjust) { + gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + planner.synchronize(); + } + zoffsetvalue -= 0.01; + Draw_Float(zoffsetvalue, row - 2, false, 100); + } + } + break; + #if ENABLED(EEPROM_SETTINGS) + case ZOFFSET_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, "Save"); + else + AudioFeedback(settings.save()); + break; + #endif + } + break; + #endif + #if HAS_PREHEAT + case Preheat: + + #define PREHEAT_BACK 0 + #define PREHEAT_MODE (PREHEAT_BACK + 1) + #define PREHEAT_1 (PREHEAT_MODE + (PREHEAT_COUNT >= 1)) + #define PREHEAT_2 (PREHEAT_1 + (PREHEAT_COUNT >= 2)) + #define PREHEAT_3 (PREHEAT_2 + (PREHEAT_COUNT >= 3)) + #define PREHEAT_4 (PREHEAT_3 + (PREHEAT_COUNT >= 4)) + #define PREHEAT_5 (PREHEAT_4 + (PREHEAT_COUNT >= 5)) + #define PREHEAT_TOTAL PREHEAT_5 + + switch (item) { + case PREHEAT_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Prepare, PREPARE_PREHEAT); + break; + case PREHEAT_MODE: + if (draw) { + Draw_Menu_Item(row, ICON_Homing, "Preheat Mode"); + Draw_Option(preheatmode, preheat_modes, row); + } + else + Modify_Option(preheatmode, preheat_modes, 2); + break; + + #if PREHEAT_COUNT >= 1 + case PREHEAT_1: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_1_LABEL); + else { + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + if (preheatmode == 0 || preheatmode == 1) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed)); + } + #if HAS_HEATED_BED + if (preheatmode == 0 || preheatmode == 2) thermalManager.setTargetBed(ui.material_preset[0].bed_temp); + #endif + } + break; + #endif + + #if PREHEAT_COUNT >= 2 + case PREHEAT_2: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_2_LABEL); + else { + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + if (preheatmode == 0 || preheatmode == 1) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed)); + } + #if HAS_HEATED_BED + if (preheatmode == 0 || preheatmode == 2) thermalManager.setTargetBed(ui.material_preset[1].bed_temp); + #endif + } + break; + #endif + + #if PREHEAT_COUNT >= 3 + case PREHEAT_3: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_3_LABEL); + else { + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + if (preheatmode == 0 || preheatmode == 1) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[2].hotend_temp, 0)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[2].fan_speed)); + } + #if HAS_HEATED_BED + if (preheatmode == 0 || preheatmode == 2) thermalManager.setTargetBed(ui.material_preset[2].bed_temp); + #endif + } + break; + #endif + + #if PREHEAT_COUNT >= 4 + case PREHEAT_4: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_4_LABEL); + else { + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + if (preheatmode == 0 || preheatmode == 1) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[3].hotend_temp, 0)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[3].fan_speed)); + } + #if HAS_HEATED_BED + if (preheatmode == 0 || preheatmode == 2) thermalManager.setTargetBed(ui.material_preset[3].bed_temp); + #endif + } + break; + #endif + + #if PREHEAT_COUNT >= 5 + case PREHEAT_5: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_5_LABEL); + else { + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + if (preheatmode == 0 || preheatmode == 1) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[4].hotend_temp, 0)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[4].fan_speed)); + } + #if HAS_HEATED_BED + if (preheatmode == 0 || preheatmode == 2) thermalManager.setTargetBed(ui.material_preset[4].bed_temp); + #endif + } + break; + #endif + } + break; + #endif + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: + + #define CHANGEFIL_BACK 0 + #define CHANGEFIL_LOAD (CHANGEFIL_BACK + 1) + #define CHANGEFIL_UNLOAD (CHANGEFIL_LOAD + 1) + #define CHANGEFIL_CHANGE (CHANGEFIL_UNLOAD + 1) + #define CHANGEFIL_TOTAL CHANGEFIL_CHANGE + + switch (item) { + case CHANGEFIL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Prepare, PREPARE_CHANGEFIL); + break; + case CHANGEFIL_LOAD: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, "Load Filament"); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilLoad); + gcode.process_subcommands_now_P(PSTR("M701")); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case CHANGEFIL_UNLOAD: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, "Unload Filament"); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { + Popup_Handler(ETemp); + } + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilLoad, true); + gcode.process_subcommands_now_P(PSTR("M702")); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case CHANGEFIL_CHANGE: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament"); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now_P(cmd); + } + } + break; + } + break; + #endif // FILAMENT_LOAD_UNLOAD_GCODES + + case Control: + + #define CONTROL_BACK 0 + #define CONTROL_TEMP (CONTROL_BACK + 1) + #define CONTROL_MOTION (CONTROL_TEMP + 1) + #define CONTROL_VISUAL (CONTROL_MOTION + 1) + #define CONTROL_ADVANCED (CONTROL_VISUAL + 1) + #define CONTROL_SAVE (CONTROL_ADVANCED + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_RESTORE (CONTROL_SAVE + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_RESET (CONTROL_RESTORE + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_INFO (CONTROL_RESET + 1) + #define CONTROL_TOTAL CONTROL_INFO + + switch (item) { + case CONTROL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Main_Menu(2); + break; + case CONTROL_TEMP: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, "Temperature", nullptr, true); + else + Draw_Menu(TempMenu); + break; + case CONTROL_MOTION: + if (draw) + Draw_Menu_Item(row, ICON_Motion, "Motion", nullptr, true); + else + Draw_Menu(Motion); + break; + case CONTROL_VISUAL: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, "Visual", nullptr, true); + else + Draw_Menu(Visual); + break; + case CONTROL_ADVANCED: + if (draw) + Draw_Menu_Item(row, ICON_Version, "Advanced", nullptr, true); + else + Draw_Menu(Advanced); + break; + #if ENABLED(EEPROM_SETTINGS) + case CONTROL_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, "Store Settings"); + else + AudioFeedback(settings.save()); + break; + case CONTROL_RESTORE: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, "Restore Settings"); + else + AudioFeedback(settings.load()); + break; + case CONTROL_RESET: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, "Reset to Defaults"); + else { + settings.reset(); + AudioFeedback(); + } + break; + #endif + case CONTROL_INFO: + if (draw) + Draw_Menu_Item(row, ICON_Info, "Info"); + else + Draw_Menu(Info); + break; + } + break; + + case TempMenu: + + #define TEMP_BACK 0 + #define TEMP_HOTEND (TEMP_BACK + ENABLED(HAS_HOTEND)) + #define TEMP_BED (TEMP_HOTEND + ENABLED(HAS_HEATED_BED)) + #define TEMP_FAN (TEMP_BED + ENABLED(HAS_FAN)) + #define TEMP_PID (TEMP_FAN + ANY(HAS_HOTEND, HAS_HEATED_BED)) + #define TEMP_PREHEAT1 (TEMP_PID + (PREHEAT_COUNT >= 1)) + #define TEMP_PREHEAT2 (TEMP_PREHEAT1 + (PREHEAT_COUNT >= 2)) + #define TEMP_PREHEAT3 (TEMP_PREHEAT2 + (PREHEAT_COUNT >= 3)) + #define TEMP_PREHEAT4 (TEMP_PREHEAT3 + (PREHEAT_COUNT >= 4)) + #define TEMP_PREHEAT5 (TEMP_PREHEAT4 + (PREHEAT_COUNT >= 5)) + #define TEMP_TOTAL TEMP_PREHEAT5 + + switch (item) { + case TEMP_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Control, CONTROL_TEMP); + break; + #if HAS_HOTEND + case TEMP_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case TEMP_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(thermalManager.temp_bed.target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case TEMP_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(thermalManager.fan_speed[0], row, false, 1); + } + else + Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + #if HAS_HOTEND || HAS_HEATED_BED + case TEMP_PID: + if (draw) + Draw_Menu_Item(row, ICON_Step, "PID", nullptr, true); + else + Draw_Menu(PID); + break; + #endif + #if PREHEAT_COUNT >= 1 + case TEMP_PREHEAT1: + if (draw) + Draw_Menu_Item(row, ICON_Step, PREHEAT_1_LABEL, nullptr, true); + else + Draw_Menu(Preheat1); + break; + #endif + #if PREHEAT_COUNT >= 2 + case TEMP_PREHEAT2: + if (draw) + Draw_Menu_Item(row, ICON_Step, PREHEAT_2_LABEL, nullptr, true); + else + Draw_Menu(Preheat2); + break; + #endif + #if PREHEAT_COUNT >= 3 + case TEMP_PREHEAT3: + if (draw) + Draw_Menu_Item(row, ICON_Step, PREHEAT_3_LABEL, nullptr, true); + else + Draw_Menu(Preheat3); + break; + #endif + #if PREHEAT_COUNT >= 4 + case TEMP_PREHEAT4: + if (draw) + Draw_Menu_Item(row, ICON_Step, PREHEAT_4_LABEL, nullptr, true); + else + Draw_Menu(Preheat4); + break; + #endif + #if PREHEAT_COUNT >= 5 + case TEMP_PREHEAT5: + if (draw) + Draw_Menu_Item(row, ICON_Step, PREHEAT_5_LABEL, nullptr, true); + else + Draw_Menu(Preheat5); + break; + #endif + } + break; + + #if HAS_HOTEND || HAS_HEATED_BED + case PID: + + #define PID_BACK 0 + #define PID_HOTEND (PID_BACK + ENABLED(HAS_HOTEND)) + #define PID_BED (PID_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PID_CYCLES (PID_BED + 1) + #define PID_TOTAL PID_CYCLES + + static uint8_t PID_cycles = 5; + + switch (item) { + case PID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PID); + break; + #if HAS_HOTEND + case PID_HOTEND: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, "Hotend", nullptr, true); + else + Draw_Menu(HotendPID); + break; + #endif + #if HAS_HEATED_BED + case PID_BED: + if (draw) + Draw_Menu_Item(row, ICON_BedTemp, "Bed", nullptr, true); + else + Draw_Menu(BedPID); + break; + #endif + case PID_CYCLES: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Cycles"); + Draw_Float(PID_cycles, row, false, 1); + } + else + Modify_Value(PID_cycles, 3, 50, 1); + break; + } + break; + #endif // HAS_HOTEND || HAS_HEATED_BED + + #if HAS_HOTEND + case HotendPID: + + #define HOTENDPID_BACK 0 + #define HOTENDPID_TUNE (HOTENDPID_BACK + 1) + #define HOTENDPID_TEMP (HOTENDPID_TUNE + 1) + #define HOTENDPID_KP (HOTENDPID_TEMP + 1) + #define HOTENDPID_KI (HOTENDPID_KP + 1) + #define HOTENDPID_KD (HOTENDPID_KI + 1) + #define HOTENDPID_TOTAL HOTENDPID_KD + + static uint16_t PID_e_temp = 180; + + switch (item) { + case HOTENDPID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(PID, PID_HOTEND); + break; + case HOTENDPID_TUNE: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, "Autotune"); + else { + Popup_Handler(PIDWait); + sprintf_P(cmd, PSTR("M303 E0 C%i S%i U1"), PID_cycles, PID_e_temp); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOTENDPID_TEMP: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, "Temperature"); + Draw_Float(PID_e_temp, row, false, 1); + } + else + Modify_Value(PID_e_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + case HOTENDPID_KP: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Kp Value"); + Draw_Float(thermalManager.temp_hotend[0].pid.Kp, row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Kp, 0, 5000, 100, thermalManager.updatePID); + break; + case HOTENDPID_KI: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Ki Value"); + Draw_Float(unscalePID_i(thermalManager.temp_hotend[0].pid.Ki), row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Ki, 0, 5000, 100, thermalManager.updatePID); + break; + case HOTENDPID_KD: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Kd Value"); + Draw_Float(unscalePID_d(thermalManager.temp_hotend[0].pid.Kd), row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Kd, 0, 5000, 100, thermalManager.updatePID); + break; + } + break; + #endif // HAS_HOTEND + + #if HAS_HEATED_BED + case BedPID: + + #define BEDPID_BACK 0 + #define BEDPID_TUNE (BEDPID_BACK + 1) + #define BEDPID_TEMP (BEDPID_TUNE + 1) + #define BEDPID_KP (BEDPID_TEMP + 1) + #define BEDPID_KI (BEDPID_KP + 1) + #define BEDPID_KD (BEDPID_KI + 1) + #define BEDPID_TOTAL BEDPID_KD + + static uint16_t PID_bed_temp = 60; + + switch (item) { + case BEDPID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(PID, PID_BED); + break; + case BEDPID_TUNE: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, "Autotune"); + else { + Popup_Handler(PIDWait); + sprintf_P(cmd, PSTR("M303 E-1 C%i S%i U1"), PID_cycles, PID_bed_temp); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + break; + case BEDPID_TEMP: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, "Temperature"); + Draw_Float(PID_bed_temp, row, false, 1); + } + else + Modify_Value(PID_bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + case BEDPID_KP: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Kp Value"); + Draw_Float(thermalManager.temp_bed.pid.Kp, row, false, 100); + } + else { + Modify_Value(thermalManager.temp_bed.pid.Kp, 0, 5000, 100, thermalManager.updatePID); + } + break; + case BEDPID_KI: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Ki Value"); + Draw_Float(unscalePID_i(thermalManager.temp_bed.pid.Ki), row, false, 100); + } + else + Modify_Value(thermalManager.temp_bed.pid.Ki, 0, 5000, 100, thermalManager.updatePID); + break; + case BEDPID_KD: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "Kd Value"); + Draw_Float(unscalePID_d(thermalManager.temp_bed.pid.Kd), row, false, 100); + } + else + Modify_Value(thermalManager.temp_bed.pid.Kd, 0, 5000, 100, thermalManager.updatePID); + break; + } + break; + #endif // HAS_HEATED_BED + + #if PREHEAT_COUNT >= 1 + case Preheat1: + + #define PREHEAT1_BACK 0 + #define PREHEAT1_HOTEND (PREHEAT1_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT1_BED (PREHEAT1_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT1_FAN (PREHEAT1_BED + ENABLED(HAS_FAN)) + #define PREHEAT1_TOTAL PREHEAT1_FAN + + switch (item) { + case PREHEAT1_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PREHEAT1); + break; + #if HAS_HOTEND + case PREHEAT1_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(ui.material_preset[0].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[0].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT1_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(ui.material_preset[0].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[0].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT1_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(ui.material_preset[0].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[0].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + break; + #endif // PREHEAT_COUNT >= 1 + + #if PREHEAT_COUNT >= 2 + case Preheat2: + + #define PREHEAT2_BACK 0 + #define PREHEAT2_HOTEND (PREHEAT2_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT2_BED (PREHEAT2_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT2_FAN (PREHEAT2_BED + ENABLED(HAS_FAN)) + #define PREHEAT2_TOTAL PREHEAT2_FAN + + switch (item) { + case PREHEAT2_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PREHEAT2); + break; + #if HAS_HOTEND + case PREHEAT2_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(ui.material_preset[1].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[1].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT2_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(ui.material_preset[1].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[1].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT2_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(ui.material_preset[1].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[1].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + break; + #endif // PREHEAT_COUNT >= 2 + + #if PREHEAT_COUNT >= 3 + case Preheat3: + + #define PREHEAT3_BACK 0 + #define PREHEAT3_HOTEND (PREHEAT3_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT3_BED (PREHEAT3_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT3_FAN (PREHEAT3_BED + ENABLED(HAS_FAN)) + #define PREHEAT3_TOTAL PREHEAT3_FAN + + switch (item) { + case PREHEAT3_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PREHEAT3); + break; + #if HAS_HOTEND + case PREHEAT3_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(ui.material_preset[2].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[2].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT3_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(ui.material_preset[2].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[2].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT3_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(ui.material_preset[2].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[2].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + break; + #endif // PREHEAT_COUNT >= 3 + + #if PREHEAT_COUNT >= 4 + case Preheat4: + + #define PREHEAT4_BACK 0 + #define PREHEAT4_HOTEND (PREHEAT4_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT4_BED (PREHEAT4_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT4_FAN (PREHEAT4_BED + ENABLED(HAS_FAN)) + #define PREHEAT4_TOTAL PREHEAT4_FAN + + switch (item) { + case PREHEAT4_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PREHEAT4); + break; + #if HAS_HOTEND + case PREHEAT4_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(ui.material_preset[3].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[3].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT4_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(ui.material_preset[3].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[3].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT4_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(ui.material_preset[3].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[3].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + break; + #endif // PREHEAT_COUNT >= 4 + + #if PREHEAT_COUNT >= 5 + case Preheat5: + + #define PREHEAT5_BACK 0 + #define PREHEAT5_HOTEND (PREHEAT5_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT5_BED (PREHEAT5_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT5_FAN (PREHEAT5_BED + ENABLED(HAS_FAN)) + #define PREHEAT5_TOTAL PREHEAT5_FAN + + switch (item) { + case PREHEAT5_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(TempMenu, TEMP_PREHEAT5); + break; + #if HAS_HOTEND + case PREHEAT5_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(ui.material_preset[4].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[4].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT5_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(ui.material_preset[4].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[4].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT5_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(ui.material_preset[4].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[4].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + break; + #endif // PREHEAT_COUNT >= 5 + + case Motion: + + #define MOTION_BACK 0 + #define MOTION_HOMEOFFSETS (MOTION_BACK + 1) + #define MOTION_SPEED (MOTION_HOMEOFFSETS + 1) + #define MOTION_ACCEL (MOTION_SPEED + 1) + #define MOTION_JERK (MOTION_ACCEL + ENABLED(HAS_CLASSIC_JERK)) + #define MOTION_STEPS (MOTION_JERK + 1) + #define MOTION_FLOW (MOTION_STEPS + ENABLED(HAS_HOTEND)) + #define MOTION_TOTAL MOTION_FLOW + + switch (item) { + case MOTION_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Control, CONTROL_MOTION); + break; + case MOTION_HOMEOFFSETS: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, "Home Offsets", nullptr, true); + else + Draw_Menu(HomeOffsets); + break; + case MOTION_SPEED: + if (draw) + Draw_Menu_Item(row, ICON_MaxSpeed, "Max Speed", nullptr, true); + else + Draw_Menu(MaxSpeed); + break; + case MOTION_ACCEL: + if (draw) + Draw_Menu_Item(row, ICON_MaxAccelerated, "Max Acceleration", nullptr, true); + else + Draw_Menu(MaxAcceleration); + break; + #if HAS_CLASSIC_JERK + case MOTION_JERK: + if (draw) + Draw_Menu_Item(row, ICON_MaxJerk, "Max Jerk", nullptr, true); + else + Draw_Menu(MaxJerk); + break; + #endif + case MOTION_STEPS: + if (draw) + Draw_Menu_Item(row, ICON_Step, "Steps/mm", nullptr, true); + else + Draw_Menu(Steps); + break; + #if HAS_HOTEND + case MOTION_FLOW: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, "Flow Rate"); + Draw_Float(planner.flow_percentage[0], row, false, 1); + } + else + Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); + break; + #endif + } + break; + + case HomeOffsets: + + #define HOMEOFFSETS_BACK 0 + #define HOMEOFFSETS_XOFFSET (HOMEOFFSETS_BACK + 1) + #define HOMEOFFSETS_YOFFSET (HOMEOFFSETS_XOFFSET + 1) + #define HOMEOFFSETS_TOTAL HOMEOFFSETS_YOFFSET + + switch (item) { + case HOMEOFFSETS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Motion, MOTION_HOMEOFFSETS); + break; + case HOMEOFFSETS_XOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, "X Offset"); + Draw_Float(home_offset.x, row, false, 100); + } + else + Modify_Value(home_offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); + break; + case HOMEOFFSETS_YOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, "Y Offset"); + Draw_Float(home_offset.y, row, false, 100); + } + else + Modify_Value(home_offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); + break; + } + break; + case MaxSpeed: + + #define SPEED_BACK 0 + #define SPEED_X (SPEED_BACK + 1) + #define SPEED_Y (SPEED_X + 1) + #define SPEED_Z (SPEED_Y + 1) + #define SPEED_E (SPEED_Z + ENABLED(HAS_HOTEND)) + #define SPEED_TOTAL SPEED_E + + switch (item) { + case SPEED_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Motion, MOTION_SPEED); + break; + case SPEED_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedX, "X Axis"); + Draw_Float(planner.settings.max_feedrate_mm_s[X_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[X_AXIS], 0, default_max_feedrate[X_AXIS] * 2, 1); + break; + + #if HAS_Y_AXIS + case SPEED_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedY, "Y Axis"); + Draw_Float(planner.settings.max_feedrate_mm_s[Y_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[Y_AXIS], 0, default_max_feedrate[Y_AXIS] * 2, 1); + break; + #endif + + #if HAS_Z_AXIS + case SPEED_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedZ, "Z Axis"); + Draw_Float(planner.settings.max_feedrate_mm_s[Z_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[Z_AXIS], 0, default_max_feedrate[Z_AXIS] * 2, 1); + break; + #endif + + #if HAS_HOTEND + case SPEED_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedE, "Extruder"); + Draw_Float(planner.settings.max_feedrate_mm_s[E_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[E_AXIS], 0, default_max_feedrate[E_AXIS] * 2, 1); + break; + #endif + } + break; + + case MaxAcceleration: + + #define ACCEL_BACK 0 + #define ACCEL_X (ACCEL_BACK + 1) + #define ACCEL_Y (ACCEL_X + 1) + #define ACCEL_Z (ACCEL_Y + 1) + #define ACCEL_E (ACCEL_Z + ENABLED(HAS_HOTEND)) + #define ACCEL_TOTAL ACCEL_E + + switch (item) { + case ACCEL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Motion, MOTION_ACCEL); + break; + case ACCEL_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccX, "X Axis"); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[X_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[X_AXIS], 0, default_max_acceleration[X_AXIS] * 2, 1); + break; + case ACCEL_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccY, "Y Axis"); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], 0, default_max_acceleration[Y_AXIS] * 2, 1); + break; + case ACCEL_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccZ, "Z Axis"); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], 0, default_max_acceleration[Z_AXIS] * 2, 1); + break; + #if HAS_HOTEND + case ACCEL_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccE, "Extruder"); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[E_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[E_AXIS], 0, default_max_acceleration[E_AXIS] * 2, 1); + break; + #endif + } + break; + #if HAS_CLASSIC_JERK + case MaxJerk: + + #define JERK_BACK 0 + #define JERK_X (JERK_BACK + 1) + #define JERK_Y (JERK_X + 1) + #define JERK_Z (JERK_Y + 1) + #define JERK_E (JERK_Z + ENABLED(HAS_HOTEND)) + #define JERK_TOTAL JERK_E + + switch (item) { + case JERK_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Motion, MOTION_JERK); + break; + case JERK_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkX, "X Axis"); + Draw_Float(planner.max_jerk[X_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[X_AXIS], 0, default_max_jerk[X_AXIS] * 2, 10); + break; + case JERK_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkY, "Y Axis"); + Draw_Float(planner.max_jerk[Y_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[Y_AXIS], 0, default_max_jerk[Y_AXIS] * 2, 10); + break; + case JERK_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkZ, "Z Axis"); + Draw_Float(planner.max_jerk[Z_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[Z_AXIS], 0, default_max_jerk[Z_AXIS] * 2, 10); + break; + #if HAS_HOTEND + case JERK_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkE, "Extruder"); + Draw_Float(planner.max_jerk[E_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[E_AXIS], 0, default_max_jerk[E_AXIS] * 2, 10); + break; + #endif + } + break; + #endif + case Steps: + + #define STEPS_BACK 0 + #define STEPS_X (STEPS_BACK + 1) + #define STEPS_Y (STEPS_X + 1) + #define STEPS_Z (STEPS_Y + 1) + #define STEPS_E (STEPS_Z + ENABLED(HAS_HOTEND)) + #define STEPS_TOTAL STEPS_E + + switch (item) { + case STEPS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Motion, MOTION_STEPS); + break; + case STEPS_X: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, "X Axis"); + Draw_Float(planner.settings.axis_steps_per_mm[X_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[X_AXIS], 0, default_steps[X_AXIS] * 2, 10); + break; + case STEPS_Y: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, "Y Axis"); + Draw_Float(planner.settings.axis_steps_per_mm[Y_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[Y_AXIS], 0, default_steps[Y_AXIS] * 2, 10); + break; + case STEPS_Z: + if (draw) { + Draw_Menu_Item(row, ICON_StepZ, "Z Axis"); + Draw_Float(planner.settings.axis_steps_per_mm[Z_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[Z_AXIS], 0, default_steps[Z_AXIS] * 2, 10); + break; + #if HAS_HOTEND + case STEPS_E: + if (draw) { + Draw_Menu_Item(row, ICON_StepE, "Extruder"); + Draw_Float(planner.settings.axis_steps_per_mm[E_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[E_AXIS], 0, 1000, 10); + break; + #endif + } + break; + + case Visual: + + #define VISUAL_BACK 0 + #define VISUAL_BACKLIGHT (VISUAL_BACK + 1) + #define VISUAL_BRIGHTNESS (VISUAL_BACKLIGHT + 1) + #define VISUAL_TIME_FORMAT (VISUAL_BRIGHTNESS + 1) + #define VISUAL_COLOR_THEMES (VISUAL_TIME_FORMAT + 1) + #define VISUAL_TOTAL VISUAL_COLOR_THEMES + + switch (item) { + case VISUAL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Control, CONTROL_VISUAL); + break; + case VISUAL_BACKLIGHT: + if (draw) + Draw_Menu_Item(row, ICON_Brightness, "Display Off"); + else + ui.set_brightness(0); + break; + case VISUAL_BRIGHTNESS: + if (draw) { + Draw_Menu_Item(row, ICON_Brightness, "LCD Brightness"); + Draw_Float(ui.brightness, row, false, 1); + } + else + Modify_Value(ui.brightness, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, 1, ui.refresh_brightness); + break; + case VISUAL_TIME_FORMAT: + if (draw) { + Draw_Menu_Item(row, ICON_PrintTime, "Progress as __h__m"); + Draw_Checkbox(row, eeprom_settings.time_format_textual); + } + else { + eeprom_settings.time_format_textual = !eeprom_settings.time_format_textual; + Draw_Checkbox(row, eeprom_settings.time_format_textual); + } + break; + case VISUAL_COLOR_THEMES: + if (draw) + Draw_Menu_Item(row, ICON_MaxSpeed, "UI Color Settings", nullptr, true); + else + Draw_Menu(ColorSettings); + break; + } + break; + + case ColorSettings: + + #define COLORSETTINGS_BACK 0 + #define COLORSETTINGS_CURSOR (COLORSETTINGS_BACK + 1) + #define COLORSETTINGS_SPLIT_LINE (COLORSETTINGS_CURSOR + 1) + #define COLORSETTINGS_MENU_TOP_TXT (COLORSETTINGS_SPLIT_LINE + 1) + #define COLORSETTINGS_MENU_TOP_BG (COLORSETTINGS_MENU_TOP_TXT + 1) + #define COLORSETTINGS_HIGHLIGHT_BORDER (COLORSETTINGS_MENU_TOP_BG + 1) + #define COLORSETTINGS_PROGRESS_PERCENT (COLORSETTINGS_HIGHLIGHT_BORDER + 1) + #define COLORSETTINGS_PROGRESS_TIME (COLORSETTINGS_PROGRESS_PERCENT + 1) + #define COLORSETTINGS_PROGRESS_STATUS_BAR (COLORSETTINGS_PROGRESS_TIME + 1) + #define COLORSETTINGS_PROGRESS_STATUS_AREA (COLORSETTINGS_PROGRESS_STATUS_BAR + 1) + #define COLORSETTINGS_PROGRESS_COORDINATES (COLORSETTINGS_PROGRESS_STATUS_AREA + 1) + #define COLORSETTINGS_PROGRESS_COORDINATES_LINE (COLORSETTINGS_PROGRESS_COORDINATES + 1) + #define COLORSETTINGS_TOTAL COLORSETTINGS_PROGRESS_COORDINATES_LINE + + switch (item) { + case COLORSETTINGS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Visual, VISUAL_COLOR_THEMES); + break; + case COLORSETTINGS_CURSOR: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Cursor"); + Draw_Option(eeprom_settings.cursor_color, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.cursor_color, color_names, Custom_Colors); + break; + case COLORSETTINGS_SPLIT_LINE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Split Line"); + Draw_Option(eeprom_settings.menu_split_line, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_split_line, color_names, Custom_Colors); + break; + case COLORSETTINGS_MENU_TOP_TXT: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Header Text"); + Draw_Option(eeprom_settings.menu_top_txt, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_top_txt, color_names, Custom_Colors); + break; + case COLORSETTINGS_MENU_TOP_BG: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Header Bg"); + Draw_Option(eeprom_settings.menu_top_bg, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_top_bg, color_names, Custom_Colors); + break; + case COLORSETTINGS_HIGHLIGHT_BORDER: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Highlight Box"); + Draw_Option(eeprom_settings.highlight_box, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.highlight_box, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_PERCENT: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Progress Percent"); + Draw_Option(eeprom_settings.progress_percent, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.progress_percent, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_TIME: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Progress Time"); + Draw_Option(eeprom_settings.progress_time, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.progress_time, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_STATUS_BAR: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Status Bar Text"); + Draw_Option(eeprom_settings.status_bar_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.status_bar_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_STATUS_AREA: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Status Area Text"); + Draw_Option(eeprom_settings.status_area_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.status_area_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_COORDINATES: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Coordinates Text"); + Draw_Option(eeprom_settings.coordinates_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.coordinates_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_COORDINATES_LINE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, "Coordinates Line"); + Draw_Option(eeprom_settings.coordinates_split_line, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.coordinates_split_line, color_names, Custom_Colors); + break; + } // switch (item) + break; + + case Advanced: + + #define ADVANCED_BACK 0 + #define ADVANCED_BEEPER (ADVANCED_BACK + 1) + #define ADVANCED_PROBE (ADVANCED_BEEPER + ENABLED(HAS_BED_PROBE)) + #define ADVANCED_CORNER (ADVANCED_PROBE + 1) + #define ADVANCED_LA (ADVANCED_CORNER + ENABLED(LIN_ADVANCE)) + #define ADVANCED_LOAD (ADVANCED_LA + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define ADVANCED_UNLOAD (ADVANCED_LOAD + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define ADVANCED_COLD_EXTRUDE (ADVANCED_UNLOAD + ENABLED(PREVENT_COLD_EXTRUSION)) + #define ADVANCED_FILSENSORENABLED (ADVANCED_COLD_EXTRUDE + ENABLED(FILAMENT_RUNOUT_SENSOR)) + #define ADVANCED_FILSENSORDISTANCE (ADVANCED_FILSENSORENABLED + ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE)) + #define ADVANCED_POWER_LOSS (ADVANCED_FILSENSORDISTANCE + ENABLED(POWER_LOSS_RECOVERY)) + #define ADVANCED_TOTAL ADVANCED_POWER_LOSS + + switch (item) { + case ADVANCED_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Control, CONTROL_ADVANCED); + break; + + case ADVANCED_BEEPER: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "LCD Beeper"); + Draw_Checkbox(row, eeprom_settings.beeperenable); + } + else { + eeprom_settings.beeperenable = !eeprom_settings.beeperenable; + Draw_Checkbox(row, eeprom_settings.beeperenable); + } + break; + + #if HAS_BED_PROBE + case ADVANCED_PROBE: + if (draw) + Draw_Menu_Item(row, ICON_StepX, "Probe", nullptr, true); + else + Draw_Menu(ProbeMenu); + break; + #endif + + case ADVANCED_CORNER: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccelerated, "Bed Screw Inset"); + Draw_Float(corner_pos, row, false, 10); + } + else + Modify_Value(corner_pos, 1, 100, 10); + break; + + #if ENABLED(LIN_ADVANCE) + case ADVANCED_LA: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccelerated, "Lin Advance Kp"); + Draw_Float(planner.extruder_advance_K[0], row, false, 100); + } + else + Modify_Value(planner.extruder_advance_K[0], 0, 10, 100); + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case ADVANCED_LOAD: + if (draw) { + Draw_Menu_Item(row, ICON_WriteEEPROM, "Load Length"); + Draw_Float(fc_settings[0].load_length, row, false, 1); + } + else + Modify_Value(fc_settings[0].load_length, 0, EXTRUDE_MAXLENGTH, 1); + break; + case ADVANCED_UNLOAD: + if (draw) { + Draw_Menu_Item(row, ICON_ReadEEPROM, "Unload Length"); + Draw_Float(fc_settings[0].unload_length, row, false, 1); + } + else + Modify_Value(fc_settings[0].unload_length, 0, EXTRUDE_MAXLENGTH, 1); + break; + #endif // ADVANCED_PAUSE_FEATURE + + #if ENABLED(PREVENT_COLD_EXTRUSION) + case ADVANCED_COLD_EXTRUDE: + if (draw) { + Draw_Menu_Item(row, ICON_Cool, "Min Extrusion T"); + Draw_Float(thermalManager.extrude_min_temp, row, false, 1); + } + else { + Modify_Value(thermalManager.extrude_min_temp, 0, MAX_E_TEMP, 1); + thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); + } + break; + #endif + + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + case ADVANCED_FILSENSORENABLED: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, "Filament Sensor"); + Draw_Checkbox(row, runout.enabled); + } + else { + runout.enabled = !runout.enabled; + Draw_Checkbox(row, runout.enabled); + } + break; + + #if ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE) + case ADVANCED_FILSENSORDISTANCE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccE, "Runout Distance"); + Draw_Float(runout.runout_distance(), row, false, 10); + } + else + Modify_Value(runout.runout_distance(), 0, 999, 10); + break; + #endif + #endif // FILAMENT_RUNOUT_SENSOR + + #if ENABLED(POWER_LOSS_RECOVERY) + case ADVANCED_POWER_LOSS: + if (draw) { + Draw_Menu_Item(row, ICON_Motion, "Power-loss recovery"); + Draw_Checkbox(row, recovery.enabled); + } + else { + recovery.enable(!recovery.enabled); + Draw_Checkbox(row, recovery.enabled); + } + break; + #endif + } + break; + + #if HAS_BED_PROBE + case ProbeMenu: + + #define PROBE_BACK 0 + #define PROBE_XOFFSET (PROBE_BACK + 1) + #define PROBE_YOFFSET (PROBE_XOFFSET + 1) + #define PROBE_TEST (PROBE_YOFFSET + 1) + #define PROBE_TEST_COUNT (PROBE_TEST + 1) + #define PROBE_TOTAL PROBE_TEST_COUNT + + static uint8_t testcount = 4; + + switch (item) { + case PROBE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Advanced, ADVANCED_PROBE); + break; + + case PROBE_XOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, "Probe X Offset"); + Draw_Float(probe.offset.x, row, false, 10); + } + else + Modify_Value(probe.offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); + break; + case PROBE_YOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, "Probe Y Offset"); + Draw_Float(probe.offset.y, row, false, 10); + } + else + Modify_Value(probe.offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); + break; + case PROBE_TEST: + if (draw) + Draw_Menu_Item(row, ICON_StepY, "M48 Probe Test"); + else { + sprintf_P(cmd, PSTR("G28O\nM48 X%s Y%s P%i"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), testcount); + gcode.process_subcommands_now_P(cmd); + } + break; + case PROBE_TEST_COUNT: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, "Probe Test Count"); + Draw_Float(testcount, row, false, 1); + } + else + Modify_Value(testcount, 4, 50, 1); + break; + } + break; + #endif + + case InfoMain: + case Info: + + #define INFO_BACK 0 + #define INFO_PRINTCOUNT (INFO_BACK + ENABLED(PRINTCOUNTER)) + #define INFO_PRINTTIME (INFO_PRINTCOUNT + ENABLED(PRINTCOUNTER)) + #define INFO_SIZE (INFO_PRINTTIME + 1) + #define INFO_VERSION (INFO_SIZE + 1) + #define INFO_CONTACT (INFO_VERSION + 1) + #define INFO_TOTAL INFO_BACK + + switch (item) { + case INFO_BACK: + if (draw) { + Draw_Menu_Item(row, ICON_Back, "Back"); + + #if ENABLED(PRINTCOUNTER) + char row1[50], row2[50], buf[32]; + printStatistics ps = print_job_timer.getStats(); + + sprintf_P(row1, PSTR("%i prints, %i finished"), ps.totalPrints, ps.finishedPrints); + sprintf_P(row2, PSTR("%s m filament used"), dtostrf(ps.filamentUsed / 1000, 1, 2, str_1)); + Draw_Menu_Item(INFO_PRINTCOUNT, ICON_HotendTemp, row1, row2, false, true); + + duration_t(print_job_timer.getStats().printTime).toString(buf); + sprintf_P(row1, PSTR("Printed: %s"), buf); + duration_t(print_job_timer.getStats().longestPrint).toString(buf); + sprintf_P(row2, PSTR("Longest: %s"), buf); + Draw_Menu_Item(INFO_PRINTTIME, ICON_PrintTime, row1, row2, false, true); + #endif + + Draw_Menu_Item(INFO_SIZE, ICON_PrintSize, MACHINE_SIZE, nullptr, false, true); + Draw_Menu_Item(INFO_VERSION, ICON_Version, SHORT_BUILD_VERSION, nullptr, false, true); + Draw_Menu_Item(INFO_CONTACT, ICON_Contact, CORP_WEBSITE, nullptr, false, true); + } + else { + if (menu == Info) + Draw_Menu(Control, CONTROL_INFO); + else + Draw_Main_Menu(3); + } + break; + } + break; + + #if HAS_MESH + case Leveling: + + #define LEVELING_BACK 0 + #define LEVELING_ACTIVE (LEVELING_BACK + 1) + #define LEVELING_GET_TILT (LEVELING_ACTIVE + BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) + #define LEVELING_GET_MESH (LEVELING_GET_TILT + 1) + #define LEVELING_MANUAL (LEVELING_GET_MESH + 1) + #define LEVELING_VIEW (LEVELING_MANUAL + 1) + #define LEVELING_SETTINGS (LEVELING_VIEW + 1) + #define LEVELING_SLOT (LEVELING_SETTINGS + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_LOAD (LEVELING_SLOT + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SAVE (LEVELING_LOAD + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_TOTAL LEVELING_SAVE + + switch (item) { + case LEVELING_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Main_Menu(3); + break; + case LEVELING_ACTIVE: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguraton, "Leveling Active"); + Draw_Checkbox(row, planner.leveling_active); + } + else { + if (!planner.leveling_active) { + set_bed_leveling_enabled(!planner.leveling_active); + if (!planner.leveling_active) { + Confirm_Handler(LevelError); + break; + } + } + else + set_bed_leveling_enabled(!planner.leveling_active); + Draw_Checkbox(row, planner.leveling_active); + } + break; + #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) + case LEVELING_GET_TILT: + if (draw) + Draw_Menu_Item(row, ICON_Tilt, "Autotilt Current Mesh"); + else { + if (ubl.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + Popup_Handler(Home); + gcode.home_all_axes(true); + Popup_Handler(Level); + if (mesh_conf.tilt_grid > 1) + sprintf_P(cmd, PSTR("G29 J%i"), mesh_conf.tilt_grid); + else + sprintf_P(cmd, PSTR("G29 J")); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + Redraw_Menu(); + } + break; + #endif + case LEVELING_GET_MESH: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, "Create New Mesh"); + else { + Popup_Handler(Home); + gcode.home_all_axes(true); + #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(PREHEAT_BEFORE_LEVELING) + Popup_Handler(Heating); + #if HAS_HOTEND + if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) + thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); + #endif + #if HAS_HEATED_BED + if (thermalManager.degTargetBed() < LEVELING_BED_TEMP) + thermalManager.setTargetBed(LEVELING_BED_TEMP); + #endif + thermalManager.wait_for_hotend(0); + TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating()); + #endif + #if HAS_BED_PROBE + Popup_Handler(Level); + gcode.process_subcommands_now_P(PSTR("G29 P0\nG29 P1")); + gcode.process_subcommands_now_P(PSTR("G29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nM420 S1")); + planner.synchronize(); + Update_Status("Probed all reachable points"); + Popup_Handler(SaveLevel); + #else + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + mesh_conf.goto_mesh_value = true; + mesh_conf.mesh_x = mesh_conf.mesh_y = 0; + Popup_Handler(MoveWait); + mesh_conf.manual_move();; + Draw_Menu(UBLMesh); + #endif + #elif HAS_BED_PROBE + Popup_Handler(Level); + gcode.process_subcommands_now_P(PSTR("G29")); + planner.synchronize(); + Popup_Handler(SaveLevel); + #else + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + gridpoint = 1; + Popup_Handler(MoveWait); + gcode.process_subcommands_now_P(PSTR("G29")); + planner.synchronize(); + Draw_Menu(ManualMesh); + #endif + } + break; + case LEVELING_MANUAL: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, "Manual Tuning", nullptr, true); + else { + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + if (!leveling_is_valid()) { + Confirm_Handler(InvalidMesh); + break; + } + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (ubl.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + #endif + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + mesh_conf.goto_mesh_value = false; + #if ENABLED(PREHEAT_BEFORE_LEVELING) + Popup_Handler(Heating); + #if HAS_HOTEND + if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) + thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); + #endif + #if HAS_HEATED_BED + if (thermalManager.degTargetBed() < LEVELING_BED_TEMP) + thermalManager.setTargetBed(LEVELING_BED_TEMP); + #endif + TERN_(HAS_HOTEND, thermalManager.wait_for_hotend(0)); + TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating()); + #endif + Popup_Handler(MoveWait); + mesh_conf.manual_move(); + Draw_Menu(LevelManual); + } + break; + case LEVELING_VIEW: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, "Mesh Viewer", nullptr, true); + else { + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (ubl.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + #endif + Draw_Menu(LevelView); + } + break; + case LEVELING_SETTINGS: + if (draw) + Draw_Menu_Item(row, ICON_Step, "Leveling Settings", nullptr, true); + else + Draw_Menu(LevelSettings); + break; + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_SLOT: + if (draw) { + Draw_Menu_Item(row, ICON_PrintSize, "Mesh Slot"); + Draw_Float(ubl.storage_slot, row, false, 1); + } + else + Modify_Value(ubl.storage_slot, 0, settings.calc_num_meshes() - 1, 1); + break; + case LEVELING_LOAD: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, "Load Mesh"); + else { + if (ubl.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + gcode.process_subcommands_now_P(PSTR("G29 L")); + planner.synchronize(); + AudioFeedback(true); + } + break; + case LEVELING_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, "Save Mesh"); + else { + if (ubl.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + gcode.process_subcommands_now_P(PSTR("G29 S")); + planner.synchronize(); + AudioFeedback(true); + } + break; + #endif + } + break; + + case LevelView: + + #define LEVELING_VIEW_BACK 0 + #define LEVELING_VIEW_MESH (LEVELING_VIEW_BACK + 1) + #define LEVELING_VIEW_TEXT (LEVELING_VIEW_MESH + 1) + #define LEVELING_VIEW_ASYMMETRIC (LEVELING_VIEW_TEXT + 1) + #define LEVELING_VIEW_TOTAL LEVELING_VIEW_ASYMMETRIC + + switch (item) { + case LEVELING_VIEW_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Leveling, LEVELING_VIEW); + break; + case LEVELING_VIEW_MESH: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, "Mesh Viewer", nullptr, true); + else + Draw_Menu(MeshViewer); + break; + case LEVELING_VIEW_TEXT: + if (draw) { + Draw_Menu_Item(row, ICON_Contact, "Viewer Show Values"); + Draw_Checkbox(row, mesh_conf.viewer_print_value); + } + else { + mesh_conf.viewer_print_value = !mesh_conf.viewer_print_value; + Draw_Checkbox(row, mesh_conf.viewer_print_value); + } + break; + case LEVELING_VIEW_ASYMMETRIC: + if (draw) { + Draw_Menu_Item(row, ICON_Axis, "Viewer Asymmetric"); + Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); + } + else { + mesh_conf.viewer_asymmetric_range = !mesh_conf.viewer_asymmetric_range; + Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); + } + break; + } + break; + + case LevelSettings: + + #define LEVELING_SETTINGS_BACK 0 + #define LEVELING_SETTINGS_FADE (LEVELING_SETTINGS_BACK + 1) + #define LEVELING_SETTINGS_TILT (LEVELING_SETTINGS_FADE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_PLANE (LEVELING_SETTINGS_TILT + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_ZERO (LEVELING_SETTINGS_PLANE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_UNDEF (LEVELING_SETTINGS_ZERO + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_TOTAL LEVELING_SETTINGS_UNDEF + + switch (item) { + case LEVELING_SETTINGS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Menu(Leveling, LEVELING_SETTINGS); + break; + case LEVELING_SETTINGS_FADE: + if (draw) { + Draw_Menu_Item(row, ICON_Fade, "Fade Mesh within"); + Draw_Float(planner.z_fade_height, row, false, 1); + } + else { + Modify_Value(planner.z_fade_height, 0, Z_MAX_POS, 1); + planner.z_fade_height = -1; + set_z_fade_height(planner.z_fade_height); + } + break; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_SETTINGS_TILT: + if (draw) { + Draw_Menu_Item(row, ICON_Tilt, "Tilting Grid Size"); + Draw_Float(mesh_conf.tilt_grid, row, false, 1); + } + else + Modify_Value(mesh_conf.tilt_grid, 1, 8, 1); + break; + case LEVELING_SETTINGS_PLANE: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, "Convert Mesh to Plane"); + else { + if (mesh_conf.create_plane_from_mesh()) break; + gcode.process_subcommands_now_P(PSTR("M420 S1")); + planner.synchronize(); + AudioFeedback(true); + } + break; + case LEVELING_SETTINGS_ZERO: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, "Zero Current Mesh"); + else + ZERO(mesh_conf.mesh_z_values); + break; + case LEVELING_SETTINGS_UNDEF: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, "Clear Current Mesh"); + else + ubl.invalidate(); + break; + #endif // AUTO_BED_LEVELING_UBL + } + break; + + case MeshViewer: + #define MESHVIEW_BACK 0 + #define MESHVIEW_TOTAL MESHVIEW_BACK + + if (item == MESHVIEW_BACK) { + if (draw) { + Draw_Menu_Item(0, ICON_Back, "Back"); + mesh_conf.Draw_Bed_Mesh(); + mesh_conf.Set_Mesh_Viewer_Status(); + } + else if (!mesh_conf.drawing_mesh) { + Draw_Menu(LevelView, LEVELING_VIEW_MESH); + Update_Status(""); + } + } + break; + + case LevelManual: + + #define LEVELING_M_BACK 0 + #define LEVELING_M_X (LEVELING_M_BACK + 1) + #define LEVELING_M_Y (LEVELING_M_X + 1) + #define LEVELING_M_NEXT (LEVELING_M_Y + 1) + #define LEVELING_M_OFFSET (LEVELING_M_NEXT + 1) + #define LEVELING_M_UP (LEVELING_M_OFFSET + 1) + #define LEVELING_M_DOWN (LEVELING_M_UP + 1) + #define LEVELING_M_GOTO_VALUE (LEVELING_M_DOWN + 1) + #define LEVELING_M_UNDEF (LEVELING_M_GOTO_VALUE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_M_TOTAL LEVELING_M_UNDEF + + switch (item) { + case LEVELING_M_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else { + set_bed_leveling_enabled(level_state); + TERN_(AUTO_BED_LEVELING_BILINEAR, refresh_bed_level()); + Draw_Menu(Leveling, LEVELING_MANUAL); + } + break; + case LEVELING_M_X: + if (draw) { + Draw_Menu_Item(row, ICON_MoveX, "Mesh Point X"); + Draw_Float(mesh_conf.mesh_x, row, 0, 1); + } + else + Modify_Value(mesh_conf.mesh_x, 0, GRID_MAX_POINTS_X - 1, 1); + break; + case LEVELING_M_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MoveY, "Mesh Point Y"); + Draw_Float(mesh_conf.mesh_y, row, 0, 1); + } + else + Modify_Value(mesh_conf.mesh_y, 0, GRID_MAX_POINTS_Y - 1, 1); + break; + case LEVELING_M_NEXT: + if (draw) + Draw_Menu_Item(row, ICON_More, "Next Point"); + else { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) + mesh_conf.mesh_y++; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x++; + else + mesh_conf.mesh_x--; + mesh_conf.manual_move(); + } + } + break; + case LEVELING_M_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + } + else { + if (isnan(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + } + break; + case LEVELING_M_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + } + break; + case LEVELING_M_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + } + break; + case LEVELING_M_GOTO_VALUE: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguraton, "Go to Mesh Z Value"); + Draw_Checkbox(row, mesh_conf.goto_mesh_value); + } + else { + mesh_conf.goto_mesh_value = !mesh_conf.goto_mesh_value; + current_position.z = 0; + mesh_conf.manual_move(true); + Draw_Checkbox(row, mesh_conf.goto_mesh_value); + } + break; + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_M_UNDEF: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, "Clear Point Value"); + else { + mesh_conf.manual_value_update(true); + Redraw_Menu(false); + } + break; + #endif + } + break; + #endif // HAS_MESH + + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: + + #define UBL_M_BACK 0 + #define UBL_M_NEXT (UBL_M_BACK + 1) + #define UBL_M_PREV (UBL_M_NEXT + 1) + #define UBL_M_OFFSET (UBL_M_PREV + 1) + #define UBL_M_UP (UBL_M_OFFSET + 1) + #define UBL_M_DOWN (UBL_M_UP + 1) + #define UBL_M_TOTAL UBL_M_DOWN + + switch (item) { + case UBL_M_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else { + set_bed_leveling_enabled(level_state); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case UBL_M_NEXT: + if (draw) { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) + Draw_Menu_Item(row, ICON_More, "Next Point"); + else + Draw_Menu_Item(row, ICON_More, "Save Mesh"); + } + else { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) + mesh_conf.mesh_y++; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x++; + else + mesh_conf.mesh_x--; + mesh_conf.manual_move(); + } + else { + gcode.process_subcommands_now_P(PSTR("G29 S")); + planner.synchronize(); + AudioFeedback(true); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + } + break; + case UBL_M_PREV: + if (draw) + Draw_Menu_Item(row, ICON_More, "Previous Point"); + else { + if (mesh_conf.mesh_x != 0 || mesh_conf.mesh_y != 0) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 1) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 0)) + mesh_conf.mesh_y--; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x--; + else + mesh_conf.mesh_x++; + mesh_conf.manual_move(); + } + } + break; + case UBL_M_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + } + else { + if (isnan(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + } + break; + case UBL_M_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + } + break; + case UBL_M_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Microstep Down"); + else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + } + break; + } + break; + #endif // AUTO_BED_LEVELING_UBL && !HAS_BED_PROBE + + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: + + #define MMESH_BACK 0 + #define MMESH_NEXT (MMESH_BACK + 1) + #define MMESH_OFFSET (MMESH_NEXT + 1) + #define MMESH_UP (MMESH_OFFSET + 1) + #define MMESH_DOWN (MMESH_UP + 1) + #define MMESH_OLD (MMESH_DOWN + 1) + #define MMESH_TOTAL MMESH_OLD + + switch (item) { + case MMESH_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Cancel"); + else { + gcode.process_subcommands_now_P(PSTR("G29 A")); + planner.synchronize(); + set_bed_leveling_enabled(level_state); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case MMESH_NEXT: + if (draw) { + if (gridpoint < GRID_MAX_POINTS) + Draw_Menu_Item(row, ICON_More, "Next Point"); + else + Draw_Menu_Item(row, ICON_More, "Save Mesh"); + } + else if (gridpoint < GRID_MAX_POINTS) { + Popup_Handler(MoveWait); + gcode.process_subcommands_now_P(PSTR("G29")); + planner.synchronize(); + gridpoint++; + Redraw_Menu(); + } + else { + gcode.process_subcommands_now_P(PSTR("G29")); + planner.synchronize(); + AudioFeedback(settings.save()); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case MMESH_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, "Z Position"); + current_position.z = MANUAL_PROBE_START_Z; + Draw_Float(current_position.z, row, false, 100); + } + else + Modify_Value(current_position.z, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case MMESH_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + else if (current_position.z < MAX_Z_OFFSET) { + gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(current_position.z, row - 1, false, 100); + } + break; + case MMESH_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + else if (current_position.z > MIN_Z_OFFSET) { + gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(current_position.z, row - 2, false, 100); + } + break; + case MMESH_OLD: + uint8_t mesh_x, mesh_y; + // 0,0 -> 1,0 -> 2,0 -> 2,1 -> 1,1 -> 0,1 -> 0,2 -> 1,2 -> 2,2 + mesh_y = (gridpoint - 1) / GRID_MAX_POINTS_Y; + mesh_x = (gridpoint - 1) % GRID_MAX_POINTS_X; + + if (mesh_y % 2 == 1) + mesh_x = GRID_MAX_POINTS_X - mesh_x - 1; + + const float currval = mesh_conf.mesh_z_values[mesh_x][mesh_y]; + + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, "Goto Mesh Value"); + Draw_Float(currval, row, false, 100); + } + else if (!isnan(currval)) { + current_position.z = currval; + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + Draw_Float(current_position.z, row - 3, false, 100); + } + break; + } + break; + #endif // PROBE_MANUALLY + + case Tune: + + #define TUNE_BACK 0 + #define TUNE_SPEED (TUNE_BACK + 1) + #define TUNE_FLOW (TUNE_SPEED + ENABLED(HAS_HOTEND)) + #define TUNE_HOTEND (TUNE_FLOW + ENABLED(HAS_HOTEND)) + #define TUNE_BED (TUNE_HOTEND + ENABLED(HAS_HEATED_BED)) + #define TUNE_FAN (TUNE_BED + ENABLED(HAS_FAN)) + #define TUNE_ZOFFSET (TUNE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_ZUP (TUNE_ZOFFSET + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_ZDOWN (TUNE_ZUP + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_CHANGEFIL (TUNE_ZDOWN + ENABLED(FILAMENT_LOAD_UNLOAD_GCODES)) + #define TUNE_FILSENSORENABLED (TUNE_CHANGEFIL + ENABLED(FILAMENT_RUNOUT_SENSOR)) + #define TUNE_BACKLIGHT_OFF (TUNE_FILSENSORENABLED + 1) + #define TUNE_BACKLIGHT (TUNE_BACKLIGHT_OFF + 1) + #define TUNE_TOTAL TUNE_BACKLIGHT + + switch (item) { + case TUNE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Back"); + else + Draw_Print_Screen(); + break; + case TUNE_SPEED: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, "Print Speed"); + Draw_Float(feedrate_percentage, row, false, 1); + } + else + Modify_Value(feedrate_percentage, MIN_PRINT_SPEED, MAX_PRINT_SPEED, 1); + break; + + #if HAS_HOTEND + case TUNE_FLOW: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, "Flow Rate"); + Draw_Float(planner.flow_percentage[0], row, false, 1); + } + else + Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); + break; + case TUNE_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + + #if HAS_HEATED_BED + case TUNE_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Float(thermalManager.temp_bed.target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + + #if HAS_FAN + case TUNE_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Float(thermalManager.fan_speed[0], row, false, 1); + } + else + Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + + #if HAS_ZOFFSET_ITEM + case TUNE_ZOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, "Z-Offset"); + Draw_Float(zoffsetvalue, row, false, 100); + } + else + Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case TUNE_ZUP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, "Z-Offset Up"); + else if (zoffsetvalue < MAX_Z_OFFSET) { + gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + zoffsetvalue += 0.01; + Draw_Float(zoffsetvalue, row - 1, false, 100); + } + break; + case TUNE_ZDOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, "Z-Offset Down"); + else if (zoffsetvalue > MIN_Z_OFFSET) { + gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + zoffsetvalue -= 0.01; + Draw_Float(zoffsetvalue, row - 2, false, 100); + } + break; + #endif + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case TUNE_CHANGEFIL: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament"); + else + Popup_Handler(ConfFilChange); + break; + #endif + + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + case TUNE_FILSENSORENABLED: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, "Filament Sensor"); + Draw_Checkbox(row, runout.enabled); + } + else { + runout.enabled = !runout.enabled; + Draw_Checkbox(row, runout.enabled); + } + break; + #endif + + case TUNE_BACKLIGHT_OFF: + if (draw) + Draw_Menu_Item(row, ICON_Brightness, "Display Off"); + else + ui.set_brightness(0); + break; + case TUNE_BACKLIGHT: + if (draw) { + Draw_Menu_Item(row, ICON_Brightness, "LCD Brightness"); + Draw_Float(ui.brightness, row, false, 1); + } + else + Modify_Value(ui.brightness, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, 1, ui.refresh_brightness); + break; + } + break; + + case PreheatHotend: + + #define PREHEATHOTEND_BACK 0 + #define PREHEATHOTEND_CONTINUE (PREHEATHOTEND_BACK + 1) + #define PREHEATHOTEND_1 (PREHEATHOTEND_CONTINUE + (PREHEAT_COUNT >= 1)) + #define PREHEATHOTEND_2 (PREHEATHOTEND_1 + (PREHEAT_COUNT >= 2)) + #define PREHEATHOTEND_3 (PREHEATHOTEND_2 + (PREHEAT_COUNT >= 3)) + #define PREHEATHOTEND_4 (PREHEATHOTEND_3 + (PREHEAT_COUNT >= 4)) + #define PREHEATHOTEND_5 (PREHEATHOTEND_4 + (PREHEAT_COUNT >= 5)) + #define PREHEATHOTEND_CUSTOM (PREHEATHOTEND_5 + 1) + #define PREHEATHOTEND_TOTAL PREHEATHOTEND_CUSTOM + + switch (item) { + case PREHEATHOTEND_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, "Cancel"); + else { + thermalManager.setTargetHotend(0, 0); + thermalManager.set_fan_speed(0, 0); + Redraw_Menu(false, true, true); + } + break; + case PREHEATHOTEND_CONTINUE: + if (draw) + Draw_Menu_Item(row, ICON_SetEndTemp, "Continue"); + else { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + switch (last_menu) { + case Prepare: + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now_P(cmd); + break; + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: + switch (last_selection) { + case CHANGEFIL_LOAD: + Popup_Handler(FilLoad); + gcode.process_subcommands_now_P("M701"); + planner.synchronize(); + Redraw_Menu(true, true, true); + break; + case CHANGEFIL_UNLOAD: + Popup_Handler(FilLoad, true); + gcode.process_subcommands_now_P("M702"); + planner.synchronize(); + Redraw_Menu(true, true, true); + break; + case CHANGEFIL_CHANGE: + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now_P(cmd); + break; + } + break; + #endif + default: + Redraw_Menu(true, true, true); + break; + } + } + break; + #if PREHEAT_COUNT >= 1 + case PREHEATHOTEND_1: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_1_LABEL); + else { + thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); + thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); + } + break; + #endif + #if PREHEAT_COUNT >= 2 + case PREHEATHOTEND_2: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_2_LABEL); + else { + thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); + thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); + } + break; + #endif + #if PREHEAT_COUNT >= 3 + case PREHEATHOTEND_3: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_3_LABEL); + else { + thermalManager.setTargetHotend(ui.material_preset[2].hotend_temp, 0); + thermalManager.set_fan_speed(0, ui.material_preset[2].fan_speed); + } + break; + #endif + #if PREHEAT_COUNT >= 4 + case PREHEATHOTEND_4: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_4_LABEL); + else { + thermalManager.setTargetHotend(ui.material_preset[3].hotend_temp, 0); + thermalManager.set_fan_speed(0, ui.material_preset[3].fan_speed); + } + break; + #endif + #if PREHEAT_COUNT >= 5 + case PREHEATHOTEND_5: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, PREHEAT_5_LABEL); + else { + thermalManager.setTargetHotend(ui.material_preset[4].hotend_temp, 0); + thermalManager.set_fan_speed(0, ui.material_preset[4].fan_speed); + } + break; + #endif + case PREHEATHOTEND_CUSTOM: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, "Custom"); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, EXTRUDE_MINTEMP, MAX_E_TEMP, 1); + break; + } + break; + } +} + +const char * CrealityDWINClass::Get_Menu_Title(uint8_t menu) { + switch (menu) { + case MainMenu: return "Main Menu"; + case Prepare: return "Prepare"; + case HomeMenu: return "Homing Menu"; + case Move: return "Move"; + case ManualLevel: return "Manual Leveling"; + #if HAS_ZOFFSET_ITEM + case ZOffset: return "Z Offset"; + #endif + #if HAS_PREHEAT + case Preheat: return "Preheat"; + #endif + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: return "Change Filament"; + #endif + case Control: return "Control"; + case TempMenu: return "Temperature"; + #if HAS_HOTEND || HAS_HEATED_BED + case PID: return "PID Menu"; + #endif + #if HAS_HOTEND + case HotendPID: return "Hotend PID Settings"; + #endif + #if HAS_HEATED_BED + case BedPID: return "Bed PID Settings"; + #endif + #if PREHEAT_COUNT >= 1 + case Preheat1: return (PREHEAT_1_LABEL " Settings"); + #endif + #if PREHEAT_COUNT >= 2 + case Preheat2: return (PREHEAT_2_LABEL " Settings"); + #endif + #if PREHEAT_COUNT >= 3 + case Preheat3: return (PREHEAT_3_LABEL " Settings"); + #endif + #if PREHEAT_COUNT >= 4 + case Preheat4: return (PREHEAT_4_LABEL " Settings"); + #endif + #if PREHEAT_COUNT >= 5 + case Preheat5: return (PREHEAT_5_LABEL " Settings"); + #endif + case Motion: return "Motion Settings"; + case HomeOffsets: return "Home Offsets"; + case MaxSpeed: return "Max Speed"; + case MaxAcceleration: return "Max Acceleration"; + #if HAS_CLASSIC_JERK + case MaxJerk: return "Max Jerk"; + #endif + case Steps: return "Steps/mm"; + case Visual: return "Visual Settings"; + case Advanced: return "Advanced Settings"; + #if HAS_BED_PROBE + case ProbeMenu: return "Probe Menu"; + #endif + case ColorSettings: return "UI Color Settings"; + case Info: return "Info"; + case InfoMain: return "Info"; + #if HAS_MESH + case Leveling: return "Leveling"; + case LevelView: return "Mesh View"; + case LevelSettings: return "Leveling Settings"; + case MeshViewer: return "Mesh Viewer"; + case LevelManual: return "Manual Tuning"; + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: return "UBL Bed Leveling"; + #endif + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: return "Mesh Bed Leveling"; + #endif + case Tune: return "Tune"; + case PreheatHotend: return "Preheat Hotend"; + } + return ""; +} + +uint8_t CrealityDWINClass::Get_Menu_Size(uint8_t menu) { + switch (menu) { + case Prepare: return PREPARE_TOTAL; + case HomeMenu: return HOME_TOTAL; + case Move: return MOVE_TOTAL; + case ManualLevel: return MLEVEL_TOTAL; + #if HAS_ZOFFSET_ITEM + case ZOffset: return ZOFFSET_TOTAL; + #endif + #if HAS_PREHEAT + case Preheat: return PREHEAT_TOTAL; + #endif + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: return CHANGEFIL_TOTAL; + #endif + case Control: return CONTROL_TOTAL; + case TempMenu: return TEMP_TOTAL; + #if HAS_HOTEND || HAS_HEATED_BED + case PID: return PID_TOTAL; + #endif + #if HAS_HOTEND + case HotendPID: return HOTENDPID_TOTAL; + #endif + #if HAS_HEATED_BED + case BedPID: return BEDPID_TOTAL; + #endif + #if PREHEAT_COUNT >= 1 + case Preheat1: return PREHEAT1_TOTAL; + #endif + #if PREHEAT_COUNT >= 2 + case Preheat2: return PREHEAT2_TOTAL; + #endif + #if PREHEAT_COUNT >= 3 + case Preheat3: return PREHEAT3_TOTAL; + #endif + #if PREHEAT_COUNT >= 4 + case Preheat4: return PREHEAT4_TOTAL; + #endif + #if PREHEAT_COUNT >= 5 + case Preheat5: return PREHEAT5_TOTAL; + #endif + case Motion: return MOTION_TOTAL; + case HomeOffsets: return HOMEOFFSETS_TOTAL; + case MaxSpeed: return SPEED_TOTAL; + case MaxAcceleration: return ACCEL_TOTAL; + #if HAS_CLASSIC_JERK + case MaxJerk: return JERK_TOTAL; + #endif + case Steps: return STEPS_TOTAL; + case Visual: return VISUAL_TOTAL; + case Advanced: return ADVANCED_TOTAL; + #if HAS_BED_PROBE + case ProbeMenu: return PROBE_TOTAL; + #endif + case Info: return INFO_TOTAL; + case InfoMain: return INFO_TOTAL; + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: return UBL_M_TOTAL; + #endif + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: return MMESH_TOTAL; + #endif + #if HAS_MESH + case Leveling: return LEVELING_TOTAL; + case LevelView: return LEVELING_VIEW_TOTAL; + case LevelSettings: return LEVELING_SETTINGS_TOTAL; + case MeshViewer: return MESHVIEW_TOTAL; + case LevelManual: return LEVELING_M_TOTAL; + #endif + case Tune: return TUNE_TOTAL; + case PreheatHotend: return PREHEATHOTEND_TOTAL; + case ColorSettings: return COLORSETTINGS_TOTAL; + } + return 0; +} + +/* Popup Config */ + +void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { + popup = last_popup = popupid; + switch (popupid) { + case Pause: Draw_Popup(PSTR("Pause Print"), PSTR(""), PSTR(""), Popup); break; + case Stop: Draw_Popup(PSTR("Stop Print"), PSTR(""), PSTR(""), Popup); break; + case Resume: Draw_Popup(PSTR("Resume Print?"), PSTR("Looks Like the last"), PSTR("print was interupted."), Popup); break; + case ConfFilChange: Draw_Popup(PSTR("Confirm Filament Change"), PSTR(""), PSTR(""), Popup); break; + case PurgeMore: Draw_Popup(PSTR("Purge more filament?"), PSTR("(Cancel to finish process)"), PSTR(""), Popup); break; + case SaveLevel: Draw_Popup(PSTR("Leveling Complete"), PSTR("Save to EEPROM?"), PSTR(""), Popup); break; + case MeshSlot: Draw_Popup(PSTR("Mesh slot not selected"), PSTR("(Confirm to select slot 0)"), PSTR(""), Popup); break; + case ETemp: Draw_Popup(PSTR("Nozzle is too cold"), PSTR("Open Preheat Menu?"), PSTR(""), Popup); break; + case ManualProbing: Draw_Popup(PSTR("Manual Probing"), PSTR("(Confirm to probe)"), PSTR("(cancel to exit)"), Popup); break; + case Level: Draw_Popup(PSTR("Auto Bed Leveling"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_AutoLeveling); break; + case Home: Draw_Popup(option ? PSTR("Parking") : PSTR("Homing"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + case MoveWait: Draw_Popup(PSTR("Moving to Point"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + case Heating: Draw_Popup(PSTR("Heating"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + case FilLoad: Draw_Popup(option ? PSTR("Unloading Filament") : PSTR("Loading Filament"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + case FilChange: Draw_Popup(PSTR("Filament Change"), PSTR("Please wait for prompt."), PSTR(""), Wait, ICON_BLTouch); break; + case TempWarn: Draw_Popup(option ? PSTR("Nozzle temp too low!") : PSTR("Nozzle temp too high!"), PSTR(""), PSTR(""), Wait, option ? ICON_TempTooLow : ICON_TempTooHigh); break; + case Runout: Draw_Popup(PSTR("Filament Runout"), PSTR(""), PSTR(""), Wait, ICON_BLTouch); break; + case PIDWait: Draw_Popup(PSTR("PID Autotune"), PSTR("in process"), PSTR("Please wait until done."), Wait, ICON_BLTouch); break; + case Resuming: Draw_Popup(PSTR("Resuming Print"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + default: break; + } +} + +void CrealityDWINClass::Confirm_Handler(PopupID popupid) { + popup = popupid; + switch (popupid) { + case FilInsert: Draw_Popup(PSTR("Insert Filament"), PSTR("Press to Continue"), PSTR(""), Confirm); break; + case HeaterTime: Draw_Popup(PSTR("Heater Timed Out"), PSTR("Press to Reheat"), PSTR(""), Confirm); break; + case UserInput: Draw_Popup(PSTR("Waiting for Input"), PSTR("Press to Continue"), PSTR(""), Confirm); break; + case LevelError: Draw_Popup(PSTR("Couldn't enable Leveling"), PSTR("(Valid mesh must exist)"), PSTR(""), Confirm); break; + case InvalidMesh: Draw_Popup(PSTR("Valid mesh must exist"), PSTR("before tuning can be"), PSTR("performed"), Confirm); break; + default: break; + } +} + +/* Navigation and Control */ + +void CrealityDWINClass::Main_Menu_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < 3) { + selection++; // Select Down + Main_Menu_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; // Select Up + Main_Menu_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) + switch (selection) { + case 0: card.mount(); Draw_SD_List(); break; + case 1: Draw_Menu(Prepare); break; + case 2: Draw_Menu(Control); break; + case 3: Draw_Menu(TERN(HAS_MESH, Leveling, InfoMain)); break; + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Menu_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + selection++; // Select Down + if (selection > scrollpos+MROWS) { + scrollpos++; + DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Menu_Item_Handler(active_menu, selection); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + selection--; // Select Up + if (selection < scrollpos) { + scrollpos--; + DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Menu_Item_Handler(active_menu, selection); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) + Menu_Item_Handler(active_menu, selection, false); + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Value_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW) + tempvalue += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + tempvalue -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + process = Menu; + EncoderRate.enabled = false; + Draw_Float(tempvalue / valueunit, selection - scrollpos, false, valueunit); + DWIN_UpdateLCD(); + if (active_menu == ZOffset && liveadjust) { + planner.synchronize(); + current_position.z += (tempvalue / valueunit - zoffsetvalue); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + current_position.z = 0; + sync_plan_position(); + } + else if (active_menu == Tune && selection == TUNE_ZOFFSET) { + sprintf_P(cmd, PSTR("M290 Z%s"), dtostrf((tempvalue / valueunit - zoffsetvalue), 1, 3, str_1)); + gcode.process_subcommands_now_P(cmd); + } + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) + tempvalue = scalePID_i(tempvalue); + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) + tempvalue = scalePID_d(tempvalue); + switch (valuetype) { + case 0: *(float*)valuepointer = tempvalue / valueunit; break; + case 1: *(uint8_t*)valuepointer = tempvalue / valueunit; break; + case 2: *(uint16_t*)valuepointer = tempvalue / valueunit; break; + case 3: *(int16_t*)valuepointer = tempvalue / valueunit; break; + case 4: *(uint32_t*)valuepointer = tempvalue / valueunit; break; + case 5: *(int8_t*)valuepointer = tempvalue / valueunit; break; + } + switch (active_menu) { + case Move: + planner.synchronize(); + planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); + break; + #if HAS_MESH + case ManualMesh: + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + break; + case UBLMesh: mesh_conf.manual_move(true); break; + case LevelManual: mesh_conf.manual_move(selection == LEVELING_M_OFFSET); break; + #endif + } + if (valuepointer == &planner.flow_percentage[0]) + planner.refresh_e_factor(0); + if (funcpointer) funcpointer(); + return; + } + NOLESS(tempvalue, (valuemin * valueunit)); + NOMORE(tempvalue, (valuemax * valueunit)); + Draw_Float(tempvalue / valueunit, selection - scrollpos, true, valueunit); + DWIN_UpdateLCD(); + if (active_menu == Move && livemove) { + *(float*)valuepointer = tempvalue / valueunit; + planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); + } +} + +void CrealityDWINClass::Option_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW) + tempvalue += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + tempvalue -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + process = Menu; + EncoderRate.enabled = false; + if (valuepointer == &color_names) { + switch (selection) { + case COLORSETTINGS_CURSOR: eeprom_settings.cursor_color = tempvalue; break; + case COLORSETTINGS_SPLIT_LINE: eeprom_settings.menu_split_line = tempvalue; break; + case COLORSETTINGS_MENU_TOP_BG: eeprom_settings.menu_top_bg = tempvalue; break; + case COLORSETTINGS_MENU_TOP_TXT: eeprom_settings.menu_top_txt = tempvalue; break; + case COLORSETTINGS_HIGHLIGHT_BORDER: eeprom_settings.highlight_box = tempvalue; break; + case COLORSETTINGS_PROGRESS_PERCENT: eeprom_settings.progress_percent = tempvalue; break; + case COLORSETTINGS_PROGRESS_TIME: eeprom_settings.progress_time = tempvalue; break; + case COLORSETTINGS_PROGRESS_STATUS_BAR: eeprom_settings.status_bar_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_STATUS_AREA: eeprom_settings.status_area_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_COORDINATES: eeprom_settings.coordinates_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_COORDINATES_LINE: eeprom_settings.coordinates_split_line = tempvalue; break; + } + Redraw_Screen(); + } + else if (valuepointer == &preheat_modes) + preheatmode = tempvalue; + + Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, false, (valuepointer == &color_names)); + DWIN_UpdateLCD(); + return; + } + NOLESS(tempvalue, valuemin); + NOMORE(tempvalue, valuemax); + Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, true); + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::File_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + static uint8_t filescrl = 0; + if (encoder_diffState == ENCODER_DIFF_NO) { + if (selection > 0) { + card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + char * const filename = card.longest_filename(); + size_t len = strlen(filename); + int8_t pos = len; + if (!card.flag.filenameIsDir) + while (pos && filename[pos] != '.') pos--; + if (pos > MENU_CHAR_LIMIT) { + static millis_t time = 0; + if (PENDING(millis(), time)) return; + time = millis() + 200; + pos -= filescrl; + len = _MIN(pos, MENU_CHAR_LIMIT); + char name[len + 1]; + if (pos >= 0) { + LOOP_L_N(i, len) name[i] = filename[i + filescrl]; + } + else { + LOOP_L_N(i, MENU_CHAR_LIMIT + pos) name[i] = ' '; + LOOP_S_L_N(i, MENU_CHAR_LIMIT + pos, MENU_CHAR_LIMIT) name[i] = filename[i - (MENU_CHAR_LIMIT + pos)]; + } + name[len] = '\0'; + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_Menu_Item(selection - scrollpos, card.flag.filenameIsDir ? ICON_More : ICON_File, name); + if (-pos >= MENU_CHAR_LIMIT) filescrl = 0; + filescrl++; + DWIN_UpdateLCD(); + } + } + return; + } + if (encoder_diffState == ENCODER_DIFF_CW && selection < card.get_num_Files()) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + if (selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_SD_Item(selection, selection - scrollpos); + } + filescrl = 0; + selection++; // Select Down + if (selection > scrollpos + MROWS) { + scrollpos++; + DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Draw_SD_Item(selection, selection - scrollpos); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_SD_Item(selection, selection - scrollpos); + filescrl = 0; + selection--; // Select Up + if (selection < scrollpos) { + scrollpos--; + DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Draw_SD_Item(selection, selection - scrollpos); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (selection == 0) { + if (card.flag.workDirIsRoot) { + process = Main; + Draw_Main_Menu(); + } + else { + card.cdup(); + Draw_SD_List(); + } + } + else { + card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + if (card.flag.filenameIsDir) { + card.cd(card.filename); + Draw_SD_List(); + } + else { + card.openAndPrintFile(card.filename); + } + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Print_Screen_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < 2) { + selection++; // Select Down + Print_Screen_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; // Select Up + Print_Screen_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (selection) { + case 0: + Draw_Menu(Tune); + Update_Status_Bar(true); + break; + case 1: + if (paused) { + if (sdprint) { + wait_for_user = false; + #if ENABLED(PARK_HEAD_ON_PAUSE) + card.startOrResumeFilePrinting(); + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); + #else + char cmnd[20]; + #if HAS_HEATED_BED + cmnd[sprintf_P(cmnd, PSTR("M140 S%i"), pausebed)] = '\0'; + gcode.process_subcommands_now_P(PSTR(cmnd)); + #endif + #if HAS_EXTRUDERS + cmnd[sprintf_P(cmnd, PSTR("M109 S%i"), pausetemp)] = '\0'; + gcode.process_subcommands_now_P(PSTR(cmnd)); + #endif + TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); + planner.synchronize(); + TERN_(SDSUPPORT, queue.inject_P(PSTR("M24"))); + #endif + } + else { + TERN_(HOST_ACTION_COMMANDS, host_action_resume()); + } + Draw_Print_Screen(); + } + else + Popup_Handler(Pause); + break; + case 2: + Popup_Handler(Stop); + break; + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Popup_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < 1) { + selection++; + Popup_Select(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; + Popup_Select(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (popup) { + case Pause: + if (selection == 0) { + if (sdprint) { + #if ENABLED(POWER_LOSS_RECOVERY) + if (recovery.enabled) recovery.save(true); + #endif + #if ENABLED(PARK_HEAD_ON_PAUSE) + Popup_Handler(Home, true); + #if ENABLED(SDSUPPORT) + if (IS_SD_PRINTING()) card.pauseSDPrint(); + #endif + planner.synchronize(); + queue.inject_P(PSTR("M125")); + planner.synchronize(); + #else + queue.inject_P(PSTR("M25")); + TERN_(HAS_HOTEND, pausetemp = thermalManager.temp_hotend[0].target); + TERN_(HAS_HEATED_BED, pausebed = thermalManager.temp_bed.target); + TERN_(HAS_FAN, pausefan = thermalManager.fan_speed[0]); + thermalManager.disable_all_heaters(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + #endif + } + else { + TERN_(HOST_ACTION_COMMANDS, host_action_pause()); + } + } + Draw_Print_Screen(); + break; + case Stop: + if (selection == 0) { + if (sdprint) { + ui.abort_print(); + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + thermalManager.disable_all_heaters(); + } + else { + TERN_(HOST_ACTION_COMMANDS, host_action_cancel()); + } + } + else + Draw_Print_Screen(); + break; + case Resume: + if (selection == 0) + queue.inject_P(PSTR("M1000")); + else { + queue.inject_P(PSTR("M1000 C")); + Draw_Main_Menu(); + } + break; + + #if HAS_HOTEND + case ETemp: + if (selection == 0) { + thermalManager.setTargetHotend(EXTRUDE_MINTEMP, 0); + thermalManager.set_fan_speed(0, MAX_FAN_SPEED); + Draw_Menu(PreheatHotend); + } + else + Redraw_Menu(true, true, false); + break; + #endif + + #if HAS_BED_PROBE + case ManualProbing: + if (selection == 0) { + char buf[80]; + const float dif = probe.probe_at_point(current_position.x, current_position.y, PROBE_PT_STOW, 0, false) - corner_avg; + sprintf_P(buf, dif > 0 ? PSTR("Corner is %smm high") : PSTR("Corner is %smm low"), dtostrf(abs(dif), 1, 3, str_1)); + Update_Status(buf); + } + else { + Redraw_Menu(true, true, false); + Update_Status(""); + } + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case ConfFilChange: + if (selection == 0) { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].celsius < thermalManager.temp_hotend[0].target - 2) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now_P(cmd); + } + } + else + Redraw_Menu(true, true, false); + break; + case PurgeMore: + if (selection == 0) { + pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; + Popup_Handler(FilChange); + } + else { + pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; + if (printing) Popup_Handler(Resuming); + else Redraw_Menu(true, true, (active_menu==PreheatHotend)); + } + break; + #endif // ADVANCED_PAUSE_FEATURE + + #if HAS_MESH + case SaveLevel: + if (selection == 0) { + #if ENABLED(AUTO_BED_LEVELING_UBL) + gcode.process_subcommands_now_P(PSTR("G29 S")); + planner.synchronize(); + AudioFeedback(true); + #else + AudioFeedback(settings.save()); + #endif + } + Draw_Menu(Leveling, LEVELING_GET_MESH); + break; + #endif + + #if ENABLED(AUTO_BED_LEVELING_UBL) + case MeshSlot: + if (selection == 0) ubl.storage_slot = 0; + Redraw_Menu(true, true); + break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Confirm_Control() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (popup) { + case Complete: + Draw_Main_Menu(); + break; + case FilInsert: + Popup_Handler(FilChange); + wait_for_user = false; + break; + case HeaterTime: + Popup_Handler(Heating); + wait_for_user = false; + break; + default: + Redraw_Menu(true, true, false); + wait_for_user = false; + break; + } + } + DWIN_UpdateLCD(); +} + +/* In-Menu Value Modification */ + +void CrealityDWINClass::Setup_Value(float value, float min, float max, float unit, uint8_t type) { + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) + tempvalue = unscalePID_i(value) * unit; + else if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) + tempvalue = unscalePID_d(value) * unit; + else + tempvalue = value * unit; + valuemin = min; + valuemax = max; + valueunit = unit; + valuetype = type; + process = Value; + EncoderRate.enabled = true; + Draw_Float(tempvalue / unit, selection - scrollpos, true, valueunit); +} + +void CrealityDWINClass::Modify_Value(float &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 0); +} +void CrealityDWINClass::Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 1); +} +void CrealityDWINClass::Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 2); +} +void CrealityDWINClass::Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 3); +} +void CrealityDWINClass::Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 4); +} +void CrealityDWINClass::Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 5); +} + +void CrealityDWINClass::Modify_Option(uint8_t value, const char * const * options, uint8_t max) { + tempvalue = value; + valuepointer = const_cast(options); + valuemin = 0; + valuemax = max; + process = Option; + EncoderRate.enabled = true; + Draw_Option(value, options, selection - scrollpos, true); +} + +/* Main Functions */ + +void CrealityDWINClass::Update_Status(const char * const text) { + char header[4]; + LOOP_L_N(i, 3) header[i] = text[i]; + header[3] = '\0'; + if (strcmp_P(header,"") == 0) { + LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; + filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; + Draw_Print_Filename(true); + } + else { + LOOP_L_N(i, _MIN((size_t)64, strlen(text))) statusmsg[i] = text[i]; + statusmsg[_MIN((size_t)64, strlen(text))] = '\0'; + } +} + +void CrealityDWINClass::Start_Print(bool sd) { + sdprint = sd; + if (!printing) { + printing = true; + statusmsg[0] = '\0'; + if (sd) { + if (recovery.valid()) { + SdFile *diveDir = nullptr; + const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); + card.selectFileByName(fname); + } + strcpy_P(filename, card.longest_filename()); + } + else + strcpy_P(filename, "Host Print"); + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0)); + TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); + Draw_Print_Screen(); + } +} + +void CrealityDWINClass::Stop_Print() { + printing = false; + sdprint = false; + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + thermalManager.disable_all_heaters(); + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(100 * (PROGRESS_SCALE))); + TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); + Draw_Print_confirm(); +} + +void CrealityDWINClass::Update() { + State_Update(); + Screen_Update(); + switch (process) { + case Main: Main_Menu_Control(); break; + case Menu: Menu_Control(); break; + case Value: Value_Control(); break; + case Option: Option_Control(); break; + case File: File_Control(); break; + case Print: Print_Screen_Control(); break; + case Popup: Popup_Control(); break; + case Confirm: Confirm_Control(); break; + } +} + +void MarlinUI::update() { CrealityDWIN.Update(); } + +void CrealityDWINClass::State_Update() { + if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { + if (!printing) Start_Print((card.isFileOpen() || recovery.valid())); + else Stop_Print(); + } + if (print_job_timer.isPaused() != paused) { + paused = print_job_timer.isPaused(); + if (process == Print) Print_Screen_Icons(); + if (process == Wait && !paused) Redraw_Menu(true, true); + } + if (wait_for_user && !(process == Confirm) && !print_job_timer.isPaused()) + Confirm_Handler(UserInput); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (process == Popup && popup == PurgeMore) { + if (pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE) + Popup_Handler(FilChange); + else if (pause_menu_response == PAUSE_RESPONSE_RESUME_PRINT) { + if (printing) Popup_Handler(Resuming); + else Redraw_Menu(true, true, (active_menu==PreheatHotend)); + } + } + #endif + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + static bool ranout = false; + if (runout.filament_ran_out != ranout) { + ranout = runout.filament_ran_out; + if (ranout) Popup_Handler(Runout); + } + #endif +} + +void CrealityDWINClass::Screen_Update() { + static millis_t scrltime = 0; + if (ELAPSED(millis(), scrltime)) { + scrltime = millis() + 200; + Update_Status_Bar(); + if (process == Print) Draw_Print_Filename(); + } + + static millis_t statustime = 0; + if (ELAPSED(millis(), statustime)) { + statustime = millis() + 500; + Draw_Status_Area(); + } + + static millis_t printtime = 0; + if (ELAPSED(millis(), printtime)) { + printtime = millis() + 1000; + if (process == Print) { + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); + } + } + + static bool mounted = card.isMounted(); + if (mounted != card.isMounted()) { + mounted = card.isMounted(); + if (process == File) + Draw_SD_List(); + } + + #if HAS_HOTEND + static int16_t hotendtarget = -1; + #endif + #if HAS_HEATED_BED + static int16_t bedtarget = -1; + #endif + #if HAS_FAN + static int16_t fanspeed = -1; + #endif + + #if HAS_ZOFFSET_ITEM + static float lastzoffset = zoffsetvalue; + if (zoffsetvalue != lastzoffset) { + lastzoffset = zoffsetvalue; + #if HAS_BED_PROBE + probe.offset.z = zoffsetvalue; + #else + set_home_offset(Z_AXIS, -zoffsetvalue); + #endif + } + + #if HAS_BED_PROBE + if (probe.offset.z != lastzoffset) + zoffsetvalue = lastzoffset = probe.offset.z; + #else + if (-home_offset.z != lastzoffset) + zoffsetvalue = lastzoffset = -home_offset.z; + #endif + #endif // HAS_ZOFFSET_ITEM + + if (process == Menu || process == Value) { + switch (active_menu) { + case TempMenu: + #if HAS_HOTEND + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + if (scrollpos <= TEMP_HOTEND && TEMP_HOTEND <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_hotend[0].target, TEMP_HOTEND - scrollpos, false, 1); + } + } + #endif + #if HAS_HEATED_BED + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + if (scrollpos <= TEMP_BED && TEMP_BED <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_bed.target, TEMP_BED - scrollpos, false, 1); + } + } + #endif + #if HAS_FAN + if (thermalManager.fan_speed[0] != fanspeed) { + fanspeed = thermalManager.fan_speed[0]; + if (scrollpos <= TEMP_FAN && TEMP_FAN <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.fan_speed[0], TEMP_FAN - scrollpos, false, 1); + } + } + #endif + break; + case Tune: + #if HAS_HOTEND + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + if (scrollpos <= TUNE_HOTEND && TUNE_HOTEND <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_hotend[0].target, TUNE_HOTEND - scrollpos, false, 1); + } + } + #endif + #if HAS_HEATED_BED + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + if (scrollpos <= TUNE_BED && TUNE_BED <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_bed.target, TUNE_BED - scrollpos, false, 1); + } + } + #endif + #if HAS_FAN + if (thermalManager.fan_speed[0] != fanspeed) { + fanspeed = thermalManager.fan_speed[0]; + if (scrollpos <= TUNE_FAN && TUNE_FAN <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.fan_speed[0], TUNE_FAN - scrollpos, false, 1); + } + } + #endif + break; + } + } +} + +void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { + if (success) { + if (eeprom_settings.beeperenable) { + BUZZ(100, 659); + BUZZ( 10, 0); + BUZZ(100, 698); + } + else Update_Status("Success"); + } + else if (eeprom_settings.beeperenable) + BUZZ(40, 440); + else + Update_Status("Failed"); +} + +void CrealityDWINClass::Save_Settings(char *buff) { + TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = mesh_conf.tilt_grid - 1); + eeprom_settings.corner_pos = corner_pos * 10; + memcpy(buff, &eeprom_settings, min(sizeof(eeprom_settings), eeprom_data_size)); +} + +void CrealityDWINClass::Load_Settings(const char *buff) { + memcpy(&eeprom_settings, buff, min(sizeof(eeprom_settings), eeprom_data_size)); + TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); + if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; + corner_pos = eeprom_settings.corner_pos / 10.0f; + Redraw_Screen(); + #if ENABLED(POWER_LOSS_RECOVERY) + static bool init = true; + if (init) { + init = false; + queue.inject_P(PSTR("M1000 S")); + } + #endif +} + +void CrealityDWINClass::Reset_Settings() { + eeprom_settings.time_format_textual = false; + eeprom_settings.beeperenable = true; + TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = 0); + eeprom_settings.corner_pos = 325; + eeprom_settings.cursor_color = 0; + eeprom_settings.menu_split_line = 0; + eeprom_settings.menu_top_bg = 0; + eeprom_settings.menu_top_txt = 0; + eeprom_settings.highlight_box = 0; + eeprom_settings.progress_percent = 0; + eeprom_settings.progress_time = 0; + eeprom_settings.status_bar_text = 0; + eeprom_settings.status_area_text = 0; + eeprom_settings.coordinates_text = 0; + eeprom_settings.coordinates_split_line = 0; + TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); + corner_pos = eeprom_settings.corner_pos / 10.0f; + Redraw_Screen(); +} + +void MarlinUI::init() { + delay(800); + SERIAL_ECHOPGM("\nDWIN handshake "); + if (DWIN_Handshake()) SERIAL_ECHOLNPGM("ok."); else SERIAL_ECHOLNPGM("error."); + DWIN_Frame_SetDir(1); // Orientation 90° + DWIN_UpdateLCD(); // Show bootscreen (first image) + Encoder_Configuration(); + for (uint16_t t = 0; t <= 100; t += 2) { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); + DWIN_UpdateLCD(); + delay(20); + } + DWIN_JPG_CacheTo1(Language_English); + CrealityDWIN.Redraw_Screen(); +} + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { + switch (message) { + case PAUSE_MESSAGE_INSERT: CrealityDWIN.Confirm_Handler(FilInsert); break; + case PAUSE_MESSAGE_OPTION: CrealityDWIN.Popup_Handler(PurgeMore); break; + case PAUSE_MESSAGE_HEAT: CrealityDWIN.Confirm_Handler(HeaterTime); break; + case PAUSE_MESSAGE_WAITING: CrealityDWIN.Draw_Print_Screen(); break; + default: break; + } + } +#endif + +#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h new file mode 100644 index 0000000000..d6c8539cc6 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -0,0 +1,364 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * lcd/e3v2/jyersui/dwin.h + */ + +#include "dwin_lcd.h" +#include "rotary_encoder.h" +#include "../../../libs/BL24CXX.h" +#include "../../../inc/MarlinConfigPre.h" + +enum processID : uint8_t { + Main, Print, Menu, Value, Option, File, Popup, Confirm, Wait +}; + +enum PopupID : uint8_t { + Pause, Stop, Resume, SaveLevel, ETemp, ConfFilChange, PurgeMore, MeshSlot, + Level, Home, MoveWait, Heating, FilLoad, FilChange, TempWarn, Runout, PIDWait, Resuming, ManualProbing, + FilInsert, HeaterTime, UserInput, LevelError, InvalidMesh, UI, Complete +}; + +enum menuID : uint8_t { + MainMenu, + Prepare, + Move, + HomeMenu, + ManualLevel, + ZOffset, + Preheat, + ChangeFilament, + Control, + TempMenu, + PID, + HotendPID, + BedPID, + Preheat1, + Preheat2, + Preheat3, + Preheat4, + Preheat5, + Motion, + HomeOffsets, + MaxSpeed, + MaxAcceleration, + MaxJerk, + Steps, + Visual, + ColorSettings, + Advanced, + ProbeMenu, + Info, + Leveling, + LevelManual, + LevelView, + MeshViewer, + LevelSettings, + ManualMesh, + UBLMesh, + InfoMain, + Tune, + PreheatHotend +}; + +#define Start_Process 0 +#define Language_English 1 +#define Language_Chinese 2 + +#define ICON 7 // Icon set file 7.ICO + +#define ICON_LOGO 0 +#define ICON_Print_0 1 +#define ICON_Print_1 2 +#define ICON_Prepare_0 3 +#define ICON_Prepare_1 4 +#define ICON_Control_0 5 +#define ICON_Control_1 6 +#define ICON_Leveling_0 7 +#define ICON_Leveling_1 8 +#define ICON_HotendTemp 9 +#define ICON_BedTemp 10 +#define ICON_Speed 11 +#define ICON_Zoffset 12 +#define ICON_Back 13 +#define ICON_File 14 +#define ICON_PrintTime 15 +#define ICON_RemainTime 16 +#define ICON_Setup_0 17 +#define ICON_Setup_1 18 +#define ICON_Pause_0 19 +#define ICON_Pause_1 20 +#define ICON_Continue_0 21 +#define ICON_Continue_1 22 +#define ICON_Stop_0 23 +#define ICON_Stop_1 24 +#define ICON_Bar 25 +#define ICON_More 26 + +#define ICON_Axis 27 +#define ICON_CloseMotor 28 +#define ICON_Homing 29 +#define ICON_SetHome 30 +#define ICON_PLAPreheat 31 +#define ICON_ABSPreheat 32 +#define ICON_Cool 33 +#define ICON_Language 34 + +#define ICON_MoveX 35 +#define ICON_MoveY 36 +#define ICON_MoveZ 37 +#define ICON_Extruder 38 + +#define ICON_Temperature 40 +#define ICON_Motion 41 +#define ICON_WriteEEPROM 42 +#define ICON_ReadEEPROM 43 +#define ICON_ResumeEEPROM 44 +#define ICON_Info 45 + +#define ICON_SetEndTemp 46 +#define ICON_SetBedTemp 47 +#define ICON_FanSpeed 48 +#define ICON_SetPLAPreheat 49 +#define ICON_SetABSPreheat 50 + +#define ICON_MaxSpeed 51 +#define ICON_MaxAccelerated 52 +#define ICON_MaxJerk 53 +#define ICON_Step 54 +#define ICON_PrintSize 55 +#define ICON_Version 56 +#define ICON_Contact 57 +#define ICON_StockConfiguraton 58 +#define ICON_MaxSpeedX 59 +#define ICON_MaxSpeedY 60 +#define ICON_MaxSpeedZ 61 +#define ICON_MaxSpeedE 62 +#define ICON_MaxAccX 63 +#define ICON_MaxAccY 64 +#define ICON_MaxAccZ 65 +#define ICON_MaxAccE 66 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 +#define ICON_StepX 71 +#define ICON_StepY 72 +#define ICON_StepZ 73 +#define ICON_StepE 74 +#define ICON_Setspeed 75 +#define ICON_SetZOffset 76 +#define ICON_Rectangle 77 +#define ICON_BLTouch 78 +#define ICON_TempTooLow 79 +#define ICON_AutoLeveling 80 +#define ICON_TempTooHigh 81 +#define ICON_NoTips_C 82 +#define ICON_NoTips_E 83 +#define ICON_Continue_C 84 +#define ICON_Continue_E 85 +#define ICON_Cancel_C 86 +#define ICON_Cancel_E 87 +#define ICON_Confirm_C 88 +#define ICON_Confirm_E 89 +#define ICON_Info_0 90 +#define ICON_Info_1 91 + +// Custom icons +#if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) + // index of every custom icon should be >= CUSTOM_ICON_START + #define CUSTOM_ICON_START ICON_Checkbox_F + #define ICON_Checkbox_F 200 + #define ICON_Checkbox_T 201 + #define ICON_Fade 202 + #define ICON_Mesh 203 + #define ICON_Tilt 204 + #define ICON_Brightness 205 + #define ICON_AxisD 249 + #define ICON_AxisBR 250 + #define ICON_AxisTR 251 + #define ICON_AxisBL 252 + #define ICON_AxisTL 253 + #define ICON_AxisC 254 +#else + #define ICON_Fade ICON_Version + #define ICON_Mesh ICON_Version + #define ICON_Tilt ICON_Version + #define ICON_Brightness ICON_Version + #define ICON_AxisD ICON_Axis + #define ICON_AxisBR ICON_Axis + #define ICON_AxisTR ICON_Axis + #define ICON_AxisBL ICON_Axis + #define ICON_AxisTL ICON_Axis + #define ICON_AxisC ICON_Axis +#endif + +#define font6x12 0x00 +#define font8x16 0x01 +#define font10x20 0x02 +#define font12x24 0x03 +#define font14x28 0x04 +#define font16x32 0x05 +#define font20x40 0x06 +#define font24x48 0x07 +#define font28x56 0x08 +#define font32x64 0x09 + +enum colorID : uint8_t { + Default, White, Green, Cyan, Blue, Magenta, Red, Orange, Yellow, Brown, Black +}; + +#define Custom_Colors 10 +#define Color_White 0xFFFF +#define Color_Light_White 0xBDD7 +#define Color_Green 0x07E0 +#define Color_Light_Green 0x3460 +#define Color_Cyan 0x07FF +#define Color_Light_Cyan 0x04F3 +#define Color_Blue 0x015F +#define Color_Light_Blue 0x3A6A +#define Color_Magenta 0xF81F +#define Color_Light_Magenta 0x9813 +#define Color_Red 0xF800 +#define Color_Light_Red 0x8800 +#define Color_Orange 0xFA20 +#define Color_Light_Orange 0xFBC0 +#define Color_Yellow 0xFF0F +#define Color_Light_Yellow 0x8BE0 +#define Color_Brown 0xCC27 +#define Color_Light_Brown 0x6204 +#define Color_Black 0x0000 +#define Color_Grey 0x18E3 +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_Bg_Red 0xF00F // Red background color +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color +#define Check_Color 0x4E5C // Check-box check color +#define Confirm_Color 0x34B9 +#define Cancel_Color 0x3186 + +class CrealityDWINClass { +public: + static constexpr size_t eeprom_data_size = 48; + static struct EEPROM_Settings { // use bit fields to save space, max 48 bytes + bool time_format_textual : 1; + bool beeperenable : 1; + #if ENABLED(AUTO_BED_LEVELING_UBL) + uint8_t tilt_grid_size : 3; + #endif + uint16_t corner_pos : 10; + uint8_t cursor_color : 4; + uint8_t menu_split_line : 4; + uint8_t menu_top_bg : 4; + uint8_t menu_top_txt : 4; + uint8_t highlight_box : 4; + uint8_t progress_percent : 4; + uint8_t progress_time : 4; + uint8_t status_bar_text : 4; + uint8_t status_area_text : 4; + uint8_t coordinates_text : 4; + uint8_t coordinates_split_line : 4; + } eeprom_settings; + + static constexpr const char * const color_names[11] = { "Default", "White", "Green", "Cyan", "Blue", "Magenta", "Red", "Orange", "Yellow", "Brown", "Black" }; + static constexpr const char * const preheat_modes[3] = { "Both", "Hotend", "Bed" }; + + static void Clear_Screen(uint8_t e=3); + static void Draw_Float(float value, uint8_t row, bool selected=false, uint8_t minunit=10); + static void Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected=false, bool color=false); + static uint16_t GetColor(uint8_t color, uint16_t original, bool light=false); + static void Draw_Checkbox(uint8_t row, bool value); + static void Draw_Title(const char * title); + static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, const char * const label1=nullptr, const char * const label2=nullptr, bool more=false, bool centered=false); + static void Draw_Menu(uint8_t menu, uint8_t select=0, uint8_t scroll=0); + static void Redraw_Menu(bool lastprocess=true, bool lastselection=false, bool lastmenu=false); + static void Redraw_Screen(); + + static void Main_Menu_Icons(); + static void Draw_Main_Menu(uint8_t select=0); + static void Print_Screen_Icons(); + static void Draw_Print_Screen(); + static void Draw_Print_Filename(const bool reset=false); + static void Draw_Print_ProgressBar(); + #if ENABLED(USE_M73_REMAINING_TIME) + static void Draw_Print_ProgressRemain(); + #endif + static void Draw_Print_ProgressElapsed(); + static void Draw_Print_confirm(); + static void Draw_SD_Item(uint8_t item, uint8_t row); + static void Draw_SD_List(bool removed=false); + static void Draw_Status_Area(bool icons=false); + static void Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P const line3, uint8_t mode, uint8_t icon=0); + static void Popup_Select(); + static void Update_Status_Bar(bool refresh=false); + + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7); + static void Set_Mesh_Viewer_Status(); + #endif + + static const char * Get_Menu_Title(uint8_t menu); + static uint8_t Get_Menu_Size(uint8_t menu); + static void Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw=true); + + static void Popup_Handler(PopupID popupid, bool option = false); + static void Confirm_Handler(PopupID popupid); + + static void Main_Menu_Control(); + static void Menu_Control(); + static void Value_Control(); + static void Option_Control(); + static void File_Control(); + static void Print_Screen_Control(); + static void Popup_Control(); + static void Confirm_Control(); + + static void Setup_Value(float value, float min, float max, float unit, uint8_t type); + static void Modify_Value(float &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Option(uint8_t value, const char * const * options, uint8_t max); + + static void Update_Status(const char * const text); + static void Start_Print(bool sd); + static void Stop_Print(); + static void Update(); + static void State_Update(); + static void Screen_Update(); + static void AudioFeedback(const bool success=true); + static void Save_Settings(char *buff); + static void Load_Settings(const char *buff); + static void Reset_Settings(); +}; + +extern CrealityDWINClass CrealityDWIN; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp new file mode 100644 index 0000000000..5380d1b93e --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp @@ -0,0 +1,474 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/******************************************************************************** + * @file lcd/e3v2/jyersui/dwin_lcd.cpp + * @brief DWIN screen control functions + ********************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + +#include "../../../inc/MarlinConfig.h" + +#include "dwin_lcd.h" +#include // for memset + +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + +// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. +// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. +uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; +uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; +uint8_t databuf[26] = { 0 }; +uint8_t receivedType; + +int recnum = 0; + +inline void DWIN_Byte(size_t &i, const uint16_t bval) { + DWIN_SendBuf[++i] = bval; +} + +inline void DWIN_Word(size_t &i, const uint16_t wval) { + DWIN_SendBuf[++i] = wval >> 8; + DWIN_SendBuf[++i] = wval & 0xFF; +} + +inline void DWIN_Long(size_t &i, const uint32_t lval) { + DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; + DWIN_SendBuf[++i] = lval & 0xFF; +} + +inline void DWIN_String(size_t &i, const char * const string) { + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); + memcpy(&DWIN_SendBuf[i + 1], string, len); + i += len; +} + +inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { + if (!string) return; + const size_t len = strlen_P((PGM_P)string); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. + if (len == 0) return; + memcpy(&DWIN_SendBuf[i + 1], string, len); + i += len; +} + +// Send the data in the buffer and the packet end +inline void DWIN_Send(size_t &i) { + ++i; + LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } +} + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void) { + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + const millis_t serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + + size_t i = 0; + DWIN_Byte(i, 0x00); + DWIN_Send(i); + + while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { + databuf[recnum] = LCD_SERIAL.read(); + // ignore the invalid data + if (databuf[0] != FHONE) { // prevent the program from running. + if (recnum > 0) { + recnum = 0; + ZERO(databuf); + } + continue; + } + delay(10); + recnum++; + } + + return ( recnum >= 3 + && databuf[0] == FHONE + && databuf[1] == '\0' + && databuf[2] == 'O' + && databuf[3] == 'K' ); +} + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance) { + size_t i = 0; + DWIN_Byte(i, 0x30); + DWIN_Byte(i, luminance); + DWIN_Send(i); +} + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir) { + size_t i = 0; + DWIN_Byte(i, 0x34); + DWIN_Byte(i, 0x5A); + DWIN_Byte(i, 0xA5); + DWIN_Byte(i, dir); + DWIN_Send(i); +} + +// Update display +void DWIN_UpdateLCD(void) { + size_t i = 0; + DWIN_Byte(i, 0x3D); + DWIN_Send(i); +} + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color) { + size_t i = 0; + DWIN_Byte(i, 0x01); + DWIN_Word(i, color); + DWIN_Send(i); +} + +// Draw a point +// color: Pixel segment color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + DWIN_Word(i, color); + DWIN_Byte(i, width); + DWIN_Byte(i, height); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x03); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x05); + DWIN_Byte(i, mode); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +//Color: color +//x/y: Upper-left coordinate of the first pixel +void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y) { + DWIN_Draw_Point(Color, 1, 1, x + 1, y); + DWIN_Draw_Point(Color, 1, 1, x + 2, y); + DWIN_Draw_Point(Color, 1, 1, x, y + 1); + DWIN_Draw_Point(Color, 1, 1, x + 3, y + 1); + DWIN_Draw_Point(Color, 1, 1, x, y + 2); + DWIN_Draw_Point(Color, 1, 1, x + 3, y + 2); + DWIN_Draw_Point(Color, 1, 1, x + 1, y + 3); + DWIN_Draw_Point(Color, 1, 1, x + 2, y + 3); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x09); + DWIN_Byte(i, (mode << 7) | dir); + DWIN_Word(i, dis); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, + uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * string) { + size_t i = 0; + DWIN_Byte(i, 0x11); + // Bit 7: widthAdjust + // Bit 6: bShow + // Bit 5-4: Unused (0) + // Bit 3-0: size + DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_String(i, string); + DWIN_Send(i); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + size_t i = 0; + DWIN_Byte(i, 0x14); + // Bit 7: bshow + // Bit 6: 1 = signed; 0 = unsigned number; + // Bit 5: zeroFill + // Bit 4: zeroMode + // Bit 3-0: size + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, 0); // fNum + DWIN_Word(i, x); + DWIN_Word(i, y); + #if 0 + for (char count = 0; count < 8; count++) { + DWIN_Byte(i, value); + value >>= 8; + if (!(value & 0xFF)) break; + } + #else + // Write a big-endian 64 bit integer + const size_t p = i + 1; + for (char count = 8; count--;) { // 7..0 + ++i; + DWIN_SendBuf[p + count] = value; + value >>= 8; + } + #endif + + DWIN_Send(i); +} + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + //uint8_t *fvalue = (uint8_t*)&value; + size_t i = 0; + DWIN_Byte(i, 0x14); + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, fNum); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Long(i, value); + /* + DWIN_Byte(i, fvalue[3]); + DWIN_Byte(i, fvalue[2]); + DWIN_Byte(i, fvalue[1]); + DWIN_Byte(i, fvalue[0]); + */ + DWIN_Send(i); +} + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id) { + size_t i = 0; + DWIN_Word(i, 0x2200); + DWIN_Byte(i, id); + DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C +} + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x23); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, 0x80 | libID); + DWIN_Byte(i, picID); + DWIN_Send(i); +} + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { + size_t i = 0; + DWIN_Byte(i, 0x25); + DWIN_Byte(i, n); + DWIN_Byte(i, id); + DWIN_Send(i); +} + +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x27); + DWIN_Byte(i, 0x80 | cacheID); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Animate a series of icons +// animID: Animation ID; 0x00-0x0F +// animate: true on; false off; +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Bit 7: animation on or off + // Bit 6: start from begin or end + // Bit 5-4: unused (0) + // Bit 3-0: animID + DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); + DWIN_Byte(i, libID); + DWIN_Byte(i, picIDs); + DWIN_Byte(i, picIDe); + DWIN_Byte(i, interval); + DWIN_Send(i); +} + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state) { + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, state); + DWIN_Send(i); +} + +/*---------------------------------------- Memory functions ----------------------------------------*/ +// The LCD has an additional 32KB SRAM and 16KB Flash + +// Data can be written to the sram and save to one of the jpeg page files + +// Write Data Memory +// command 0x31 +// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Data: data +// +// Flash writing returns 0xA5 0x4F 0x4B + +// Read Data Memory +// command 0x32 +// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Length: leangth of data to read; 0x01-0xF0 +// +// Response: +// Type, Address, Length, Data + +// Write Picture Memory +// Write the contents of the 32KB SRAM data memory into the designated image memory space +// Issued: 0x5A, 0xA5, PIC_ID +// Response: 0xA5 0x4F 0x4B +// +// command 0x33 +// 0x5A, 0xA5 +// PicId: Picture Memory location, 0x00-0x0F +// +// Flash writing returns 0xA5 0x4F 0x4B + +#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h new file mode 100644 index 0000000000..18b7c34744 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -0,0 +1,218 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/******************************************************************************** + * @file lcd/e3v2/jyersui/dwin_lcd.h + * @brief DWIN screen control functions + ********************************************************************************/ + +#include + +#define RECEIVED_NO_DATA 0x00 +#define RECEIVED_SHAKE_HAND_ACK 0x01 + +#define FHONE 0xAA + +#define DWIN_SCROLL_UP 2 +#define DWIN_SCROLL_DOWN 3 + +#define DWIN_WIDTH 272 +#define DWIN_HEIGHT 480 + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void); + +// Common DWIN startup +void DWIN_Startup(void); + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance); + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir); + +// Update display +void DWIN_UpdateLCD(void); + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color); + +// Draw a point +// color: Line segment color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +//Color: color +//x: upper left point +//y: bottom right point +void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y); + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, + uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * string); + +class __FlashStringHelper; + +inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + // Note that this won't work on AVR. This is for 32-bit systems only! + // Are __FlashStringHelper versions worth keeping? + DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, reinterpret_cast(title)); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); + +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID +inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } + +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, + uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp new file mode 100644 index 0000000000..47ddc90184 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp @@ -0,0 +1,261 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/***************************************************************************** + * @file lcd/e3v2/jyersui/rotary_encoder.cpp + * @brief Rotary encoder functions + *****************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + +#include "rotary_encoder.h" +#include "../../buttons.h" + +#include "../../../MarlinCore.h" +#include "../../marlinui.h" +#include "../../../HAL/shared/Delay.h" + +#if HAS_BUZZER + #include "../../../libs/buzzer.h" + #include "dwin.h" +#endif + +#include + +#ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP 4 +#endif + +ENCODER_Rate EncoderRate; + +// Buzzer +void Encoder_tick() { + #if PIN_EXISTS(BEEPER) + if (CrealityDWIN.eeprom_settings.beeperenable) { + WRITE(BEEPER_PIN, HIGH); + delay(10); + WRITE(BEEPER_PIN, LOW); + } + #endif +} + +// Encoder initialization +void Encoder_Configuration() { + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if PIN_EXISTS(BEEPER) + SET_OUTPUT(BEEPER_PIN); + #endif +} + +// Analyze encoder value and return state +ENCODER_DiffState Encoder_ReceiveAnalyze() { + const millis_t now = millis(); + static uint8_t lastEncoderBits; + uint8_t newbutton = 0; + static signed char temp_diff = 0; + + ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (BUTTON_PRESSED(ENC)) { + static millis_t next_click_update_ms; + if (ELAPSED(now, next_click_update_ms)) { + next_click_update_ms = millis() + 300; + Encoder_tick(); + #if PIN_EXISTS(LCD_LED) + //LED_Action(); + #endif + if (ui.backlight) return ENCODER_DIFF_ENTER; + ui.refresh_brightness(); + } + else return ENCODER_DIFF_NO; + } + if (newbutton != lastEncoderBits) { + switch (newbutton) { + case ENCODER_PHASE_0: + if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; + break; + case ENCODER_PHASE_1: + if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; + break; + case ENCODER_PHASE_2: + if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; + break; + case ENCODER_PHASE_3: + if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; + break; + } + lastEncoderBits = newbutton; + } + + if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { + #if ENABLED(REVERSE_ENCODER_DIRECTION) + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CCW; + else temp_diffState = ENCODER_DIFF_CW; + #else + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; + else temp_diffState = ENCODER_DIFF_CCW; + #endif + + #if ENABLED(ENCODER_RATE_MULTIPLIER) + + millis_t ms = millis(); + int32_t encoderMultiplier = 1; + + // if must encoder rati multiplier + if (EncoderRate.enabled) { + const float abs_diff = ABS(temp_diff), + encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.lastEncoderTime) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the temp_diff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + } + EncoderRate.lastEncoderTime = ms; + } + + #else + + constexpr int32_t encoderMultiplier = 1; + + #endif + + // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; + + temp_diff = 0; + } + return temp_diffState; +} + +#if PIN_EXISTS(LCD_LED) + + // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 + uint16_t LED_DataArray[LED_NUM]; + + // LED light operation + void LED_Action() { + LED_Control(RGB_SCALE_WARM_WHITE,0x0F); + delay(30); + LED_Control(RGB_SCALE_WARM_WHITE,0x00); + } + + // LED initialization + void LED_Configuration() { + SET_OUTPUT(LCD_LED_PIN); + } + + // LED write data + void LED_WriteData() { + uint8_t tempCounter_LED, tempCounter_Bit; + for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { + for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { + if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { + LED_DATA_HIGH; + DELAY_NS(300); + LED_DATA_LOW; + DELAY_NS(200); + } + else { + LED_DATA_HIGH; + LED_DATA_LOW; + DELAY_NS(200); + } + } + } + } + + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance) { + for (uint8_t i = 0; i < LED_NUM; i++) { + LED_DataArray[i] = 0; + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 5/10; break; + case RGB_SCALE_R10_G7_B4: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 4/10; break; + case RGB_SCALE_R10_G8_B7: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 8/10) << 16 | luminance * 7/10; break; + } + } + LED_WriteData(); + } + + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval) { + struct { uint8_t g, r, b; } led_data[LED_NUM]; + for (uint8_t i = 0; i < LED_NUM; i++) { + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 5/10 }; + break; + case RGB_SCALE_R10_G7_B4: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 4/10 }; + break; + case RGB_SCALE_R10_G8_B7: + led_data[i] = { luminance * 8/10, luminance * 10/10, luminance * 7/10 }; + break; + } + } + + struct { bool g, r, b; } led_flag = { false, false, false }; + for (uint8_t i = 0; i < LED_NUM; i++) { + while (1) { + const uint8_t g = uint8_t(LED_DataArray[i] >> 16), + r = uint8_t(LED_DataArray[i] >> 8), + b = uint8_t(LED_DataArray[i]); + if (g == led_data[i].g) led_flag.g = true; + else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; + if (r == led_data[i].r) led_flag.r = true; + else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; + if (b == led_data[i].b) led_flag.b = true; + else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; + LED_WriteData(); + if (led_flag.r && led_flag.g && led_flag.b) break; + delay(change_Interval); + } + } + } + +#endif // LCD_LED + +#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h new file mode 100644 index 0000000000..0febe6bd35 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h @@ -0,0 +1,91 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/***************************************************************************** + * @file lcd/e3v2/jyersui/rotary_encoder.h + * @brief Rotary encoder functions + ****************************************************************************/ + +#include "../../../inc/MarlinConfig.h" + +/*********************** Encoder Set ***********************/ + +typedef struct { + bool enabled = false; + int encoderMoveValue = 0; + millis_t lastEncoderTime = 0; +} ENCODER_Rate; + +extern ENCODER_Rate EncoderRate; + +typedef enum { + ENCODER_DIFF_NO = 0, // no state + ENCODER_DIFF_CW = 1, // clockwise rotation + ENCODER_DIFF_CCW = 2, // counterclockwise rotation + ENCODER_DIFF_ENTER = 3 // click +} ENCODER_DiffState; + +// Encoder initialization +void Encoder_Configuration(); + +// Analyze encoder value and return state +ENCODER_DiffState Encoder_ReceiveAnalyze(); + +/*********************** Encoder LED ***********************/ + +#if PIN_EXISTS(LCD_LED) + + #define LED_NUM 4 + #define LED_DATA_HIGH WRITE(LCD_LED_PIN, 1) + #define LED_DATA_LOW WRITE(LCD_LED_PIN, 0) + + #define RGB_SCALE_R10_G7_B5 1 + #define RGB_SCALE_R10_G7_B4 2 + #define RGB_SCALE_R10_G8_B7 3 + #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 + #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 + #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 + + extern unsigned int LED_DataArray[LED_NUM]; + + // LED light operation + void LED_Action(); + + // LED initialization + void LED_Configuration(); + + // LED write data + void LED_WriteData(); + + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance); + + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval); + +#endif // LCD_LED diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index faa6c8f41a..59759319be 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -195,7 +195,7 @@ namespace ExtUI { #endif inline void simulateUserClick() { - #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + #if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) ui.lcd_clicked = true; #endif } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 8911941ee0..51cbf4534f 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -48,6 +48,8 @@ MarlinUI ui; #if ENABLED(DWIN_CREALITY_LCD) #include "e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "e3v2/jyersui/dwin.h" #endif #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL @@ -99,6 +101,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; backlight = !!value; if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); // Set brightness on enabled LCD here + TERN_(DWIN_CREALITY_LCD_JYERSUI, DWIN_Backlight_SetLuminance(backlight ? brightness : 0)); } #endif @@ -136,6 +139,21 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::lcd_clicked; #endif +#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) + + bool MarlinUI::get_blink() { + static uint8_t blink = 0; + static millis_t next_blink_ms = 0; + millis_t ms = millis(); + if (ELAPSED(ms, next_blink_ms)) { + blink ^= 0xFF; + next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; + } + return blink != 0; + } + +#endif + #if HAS_WIRED_LCD #if HAS_MARLINUI_U8GLIB @@ -415,17 +433,6 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); } - bool MarlinUI::get_blink() { - static uint8_t blink = 0; - static millis_t next_blink_ms = 0; - millis_t ms = millis(); - if (ELAPSED(ms, next_blink_ms)) { - blink ^= 0xFF; - next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; - } - return blink != 0; - } - //////////////////////////////////////////// ///////////// Keypad Handling ////////////// //////////////////////////////////////////// @@ -1468,6 +1475,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); + TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } #if ENABLED(STATUS_MESSAGE_SCROLLING) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index edee8f0cc2..268d018508 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -55,7 +55,7 @@ #include "../module/printcounter.h" #endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) +#if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) #include "../feature/pause.h" #include "../module/motion.h" // for active_extruder #endif @@ -76,8 +76,6 @@ uint8_t get_ADC_keyValue(); #endif - #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) - #if HAS_LCD_MENU #include "lcdprint.h" @@ -95,6 +93,10 @@ #endif // HAS_WIRED_LCD +#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) + #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) +#endif + #if HAS_MARLINUI_U8GLIB enum MarlinFont : uint8_t { FONT_STATUSMENU = 1, @@ -363,6 +365,10 @@ public: static void poweroff(); #endif + #if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) + static bool get_blink(); + #endif + #if HAS_WIRED_LCD static millis_t next_button_update_ms; @@ -451,7 +457,6 @@ public: static bool did_first_redraw; #endif - static bool get_blink(); static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); static void draw_kill_screen(); @@ -580,7 +585,7 @@ public: static inline bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static inline void _pause_show_message() {} diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 632f95558d..f2d2aeee92 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -73,6 +73,10 @@ #include "../lcd/extui/ui_api.h" #endif +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "../lcd/e3v2/jyersui/dwin.h" +#endif + #if HAS_SERVOS #include "servo.h" #endif @@ -441,6 +445,13 @@ typedef struct SettingsDataStruct { uint8_t extui_data[ExtUI::eeprom_data_size]; #endif + // + // DWIN_CREALITY_LCD_JYERSUI + // + #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + uint8_t dwin_settings[CrealityDWIN.eeprom_data_size]; + #endif + // // CASELIGHT_USES_BRIGHTNESS // @@ -1346,6 +1357,18 @@ void MarlinSettings::postprocess() { } #endif + // + // Creality UI Settings + // + #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + { + char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; + CrealityDWIN.Save_Settings(dwin_settings); + _FIELD_TEST(dwin_settings); + EEPROM_WRITE(dwin_settings); + } + #endif + // // Case Light Brightness // @@ -2225,6 +2248,18 @@ void MarlinSettings::postprocess() { } #endif + // + // Creality UI Settings + // + #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + { + const char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; + _FIELD_TEST(dwin_settings); + EEPROM_READ(dwin_settings); + if (!validating) CrealityDWIN.Load_Settings(dwin_settings); + } + #endif + // // Case Light Brightness // @@ -2622,6 +2657,8 @@ void MarlinSettings::reset() { TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); + TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Reset_Settings()); + // // Case Light Brightness // 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 58f2ac2808..56d548847c 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -266,7 +266,7 @@ #define EXP2_09_PIN P0_15 #define EXP2_10_PIN P0_17 -#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD #define BTN_ENC EXP1_06_PIN diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index af7b7d7e58..8b855e8d01 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -197,8 +197,8 @@ #define EXP1_09_PIN P0_16 #define EXP1_10_PIN P2_08 -#if ENABLED(DWIN_CREALITY_LCD) - #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) + #error "Ender-3 V2 display requires a custom cable with TX = P0_15, RX = P0_16. Comment out this line to continue." /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index fe4fd3a4a7..9f923b4ea9 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -134,7 +134,7 @@ #define EXP1_3 PB7 #endif -#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) /** * ------ ------ ------ * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 65d3fe731d..2aa48b7499 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -186,7 +186,7 @@ #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." #endif -#elif EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#elif EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD #define BTN_ENC PB14 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 6062755d3c..52ebdecc35 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -216,7 +216,7 @@ #define BTN_EN1 EXP1_08_PIN #define BTN_EN2 EXP1_06_PIN -#elif EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#elif EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) // RET6 DWIN ENCODER LCD #define BTN_ENC PB14 diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index a941eb906a..0ad66bfdb9 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -13,6 +13,11 @@ use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" +use_example_configs "Creality/Ender-3 V2/CrealityUI" +opt_disable DWIN_CREALITY_LCD +opt_enable DWIN_CREALITY_LCD_JYERSUI +exec_test $1 $2 "Ender 3 v2 with JyersUI" "$3" + use_example_configs "Creality/Ender-3 V2/MarlinUI" opt_add SDCARD_EEPROM_EMULATION exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" diff --git a/ini/features.ini b/ini/features.ini index 4a1c638de2..acadd7763a 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -45,6 +45,7 @@ I2C_EEPROM = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ +DWIN_CREALITY_LCD_JYERSUI = src_filter=+ DWIN_MARLINUI_.+ = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 55c7577e37..23ee15d98b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -49,8 +49,8 @@ extra_scripts = lib_deps = default_src_filter = + - - + - - - - - - - - - - + - - - - - - - - - From 0f61d9e4dd4d4e4f27e5c688ab2c5dbd0f03af84 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Tue, 7 Sep 2021 02:15:24 -0500 Subject: [PATCH 0645/2168] =?UTF-8?q?=E2=9C=A8=20Ender-3=20V2=20CrealityUI?= =?UTF-8?q?=20Enhanced=20(#21942)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 5 + Marlin/src/MarlinCore.cpp | 13 +- Marlin/src/feature/pause.cpp | 13 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/feature/powerloss.h | 2 +- Marlin/src/feature/runout.cpp | 3 + Marlin/src/gcode/bedlevel/abl/G29.cpp | 17 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 3 + Marlin/src/gcode/bedlevel/ubl/M421.cpp | 3 + Marlin/src/gcode/calibrate/G28.cpp | 11 +- Marlin/src/gcode/control/M997.cpp | 6 + Marlin/src/gcode/feature/powerloss/M1000.cpp | 7 +- Marlin/src/gcode/lcd/M0_M1.cpp | 4 + Marlin/src/gcode/lcd/M73.cpp | 28 +- Marlin/src/gcode/sd/M1001.cpp | 3 + Marlin/src/gcode/stats/M75-M78.cpp | 23 +- Marlin/src/gcode/temp/M303.cpp | 3 + Marlin/src/inc/Conditionals_LCD.h | 5 +- Marlin/src/inc/SanityCheck.h | 18 +- Marlin/src/lcd/e3v2/{creality => }/README.md | 0 Marlin/src/lcd/e3v2/creality/rotary_encoder.h | 12 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 3529 +++++++++++++++++ Marlin/src/lcd/e3v2/enhanced/dwin.h | 268 ++ Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp | 564 +++ Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 282 ++ Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 452 +++ Marlin/src/lcd/e3v2/enhanced/dwinui.h | 623 +++ Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp | 69 + Marlin/src/lcd/e3v2/enhanced/lockscreen.h | 35 + .../src/lcd/e3v2/enhanced/rotary_encoder.cpp | 261 ++ Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h | 93 + Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 3 - Marlin/src/lcd/language/language_en.h | 17 +- Marlin/src/lcd/marlinui.cpp | 5 +- Marlin/src/lcd/marlinui.h | 21 +- Marlin/src/lcd/tft/ui_common.h | 2 +- Marlin/src/module/probe.cpp | 4 +- Marlin/src/module/settings.cpp | 40 +- Marlin/src/module/temperature.cpp | 29 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 2 +- Marlin/src/sd/cardreader.cpp | 4 +- buildroot/tests/STM32F103RET6_creality | 5 + ini/features.ini | 1 + platformio.ini | 2 +- 44 files changed, 6408 insertions(+), 84 deletions(-) rename Marlin/src/lcd/e3v2/{creality => }/README.md (100%) create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwinui.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwinui.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/lockscreen.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a424b1967e..6a96411863 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2756,6 +2756,11 @@ // //#define DWIN_CREALITY_LCD +// +// Ender-3 v2 OEM display, enhanced. +// +//#define DWIN_CREALITY_LCD_ENHANCED + // // Ender-3 v2 OEM display with enhancements by Jacob Myers // diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index d68e87eb89..49db8c61b9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -77,6 +77,9 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "lcd/e3v2/creality/dwin.h" #include "lcd/e3v2/creality/rotary_encoder.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "lcd/e3v2/enhanced/dwin.h" + #include "lcd/e3v2/enhanced/rotary_encoder.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "lcd/e3v2/jyersui/dwin.h" #include "lcd/e3v2/jyersui/rotary_encoder.h" @@ -849,7 +852,7 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(USE_BEEPER, buzzer.tick()); // Handle UI input / draw events - TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); + TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) @@ -904,7 +907,7 @@ void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr // Echo the LCD message to serial for extra context if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P(lcd_error); } - #if HAS_DISPLAY + #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) ui.kill_screen(lcd_error ?: GET_TEXT(MSG_KILLED), lcd_component ?: NUL_STR); #else UNUSED(lcd_error); UNUSED(lcd_component); @@ -1315,7 +1318,7 @@ void setup() { // UI must be initialized before EEPROM // (because EEPROM code calls the UI). - #if ENABLED(DWIN_CREALITY_LCD) + #if HAS_DWIN_E3V2_BASIC SETUP_RUN(DWIN_Startup()); #else SETUP_RUN(ui.init()); @@ -1590,7 +1593,7 @@ void setup() { SERIAL_ECHO_TERNARY(err, "BL24CXX Check ", "failed", "succeeded", "!\n"); #endif - #if ENABLED(DWIN_CREALITY_LCD) + #if HAS_DWIN_E3V2_BASIC Encoder_Configuration(); HMI_Init(); HMI_SetLanguageCache(); @@ -1598,7 +1601,7 @@ void setup() { DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG)); #endif - #if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD) + #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC ui.reset_status(true); // Show service messages or keep current status #endif diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 9a402141e6..f1d6dbb985 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -53,6 +53,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" #endif #include "../lcd/marlinui.h" @@ -242,6 +244,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); @@ -265,7 +268,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; - #if HAS_LCD_MENU + #if EITHER(HAS_LCD_MENU, DWIN_CREALITY_LCD_ENHANCED) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR #else pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; @@ -525,6 +528,8 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status_P(GET_TEXT(MSG_REHEATING))); + // Re-enable the heaters if they timed out HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e); @@ -538,8 +543,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); + + TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status_P(GET_TEXT(MSG_REHEATDONE))); + wait_for_user = true; nozzle_timed_out = false; @@ -675,6 +685,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); TERN_(HAS_LCD_MENU, ui.return_to_status()); + TERN_(DWIN_CREALITY_LCD_ENHANCED, HMI_ReturnScreen()); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 3409e6714d..c86cb4f0d6 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -40,7 +40,7 @@ uint8_t PrintJobRecovery::queue_index_r; uint32_t PrintJobRecovery::cmd_sdpos, // = 0 PrintJobRecovery::sdpos[BUFSIZE]; -#if ENABLED(DWIN_CREALITY_LCD) +#if HAS_DWIN_E3V2_BASIC bool PrintJobRecovery::dwin_flag; // = false #endif diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index d3ecc6c9cc..6a13c92df7 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -145,7 +145,7 @@ class PrintJobRecovery { static uint32_t cmd_sdpos, //!< SD position of the next command sdpos[BUFSIZE]; //!< SD positions of queued commands - #if ENABLED(DWIN_CREALITY_LCD) + #if HAS_DWIN_E3V2_BASIC static bool dwin_flag; #endif diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 531ca1081f..ef1f876bdf 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -68,6 +68,8 @@ bool FilamentMonitorBase::enabled = true, #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" #endif void event_filament_runout(const uint8_t extruder) { @@ -86,6 +88,7 @@ void event_filament_runout(const uint8_t extruder) { #endif TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getTool(extruder))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_FilamentRunout(extruder)); #if ANY(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS, MULTI_FILAMENT_SENSOR) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, extruder); diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index ca36f6d46e..f756aa89df 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -58,10 +58,10 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" -#endif - -#if ENABLED(DWIN_CREALITY_LCD) +#elif ENABLED(DWIN_CREALITY_LCD) #include "../../../lcd/e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../../lcd/e3v2/enhanced/dwin.h" #endif #if HAS_MULTI_HOTEND @@ -403,10 +403,9 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(AUTO_BED_LEVELING_3POINT) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points - #endif - - #if BOTH(AUTO_BED_LEVELING_BILINEAR, EXTENSIBLE_UI) - ExtUI::onMeshLevelingStart(); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshLevelingStart()); #endif if (!faux) { @@ -886,9 +885,7 @@ G29_TYPE GcodeSuite::G29() { process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); #endif - #if ENABLED(DWIN_CREALITY_LCD) - DWIN_CompletedLeveling(); - #endif + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedLeveling()); report_current_position(); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index b8ca8bdee5..adfe61d3d2 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -40,6 +40,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../../lcd/e3v2/enhanced/dwin.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) @@ -191,6 +193,7 @@ void GcodeSuite::G29() { if (parser.seenval('Z')) { mbl.z_values[ix][iy] = parser.value_linear_units(); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy])); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ix, iy, mbl.z_values[ix][iy])); } else return echo_not_entered('Z'); diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index f1e1b76126..e6f0ef1f89 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -33,6 +33,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../../lcd/e3v2/enhanced/dwin.h" #endif /** @@ -67,6 +69,7 @@ void GcodeSuite::M421() { float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ij.x, ij.y, zval)); } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 89ad20d906..d85c0306d4 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -46,12 +46,13 @@ #endif #include "../../lcd/marlinui.h" -#if ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/e3v2/creality/dwin.h" -#endif #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD) + #include "../../lcd/e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" #endif #if HAS_L64XX // set L6470 absolute position registers to counts @@ -238,7 +239,7 @@ void GcodeSuite::G28() { return; } - TERN_(DWIN_CREALITY_LCD, DWIN_StartHoming()); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_StartHoming()); TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart()); planner.synchronize(); // Wait for planner moves to finish! @@ -522,7 +523,7 @@ void GcodeSuite::G28() { ui.refresh(); - TERN_(DWIN_CREALITY_LCD, DWIN_CompletedHoming()); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedHoming()); TERN_(EXTENSIBLE_UI, ExtUI::onHomingComplete()); report_current_position(); diff --git a/Marlin/src/gcode/control/M997.cpp b/Marlin/src/gcode/control/M997.cpp index cdff96f1ac..73d795bcef 100644 --- a/Marlin/src/gcode/control/M997.cpp +++ b/Marlin/src/gcode/control/M997.cpp @@ -24,11 +24,17 @@ #if ENABLED(PLATFORM_M997_SUPPORT) +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" +#endif + /** * M997: Perform in-application firmware update */ void GcodeSuite::M997() { + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_RebootScreen()); + flashFirmware(parser.intval('S')); } diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 0e731016dd..3ebb286b57 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -27,9 +27,14 @@ #include "../../gcode.h" #include "../../../feature/powerloss.h" #include "../../../module/motion.h" + #include "../../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD) + #include "../../../lcd/e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../../lcd/e3v2/enhanced/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented #endif @@ -64,7 +69,7 @@ void GcodeSuite::M1000() { if (parser.seen_test('S')) { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); - #elif ENABLED(DWIN_CREALITY_LCD) + #elif HAS_DWIN_E3V2_BASIC recovery.dwin_flag = true; #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) // Temporary fix until it can be better implemented CrealityDWIN.Popup_Handler(Resume); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 414c4ce023..cb37bfec24 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -35,6 +35,8 @@ #include "../../lcd/marlinui.h" #elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -68,6 +70,8 @@ void GcodeSuite::M0_M1() { ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? else ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); + #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg ?: GET_TEXT(MSG_STOPPED), GET_TEXT(MSG_USERWAIT)); #else if (parser.string_arg) { diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index 8996e5c88e..b7a9b3459e 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -28,6 +28,10 @@ #include "../../lcd/marlinui.h" #include "../../sd/cardreader.h" +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" +#endif + /** * M73: Set percentage complete (for display on LCD) * @@ -35,13 +39,23 @@ * M73 P25 ; Set progress to 25% */ void GcodeSuite::M73() { - if (parser.seenval('P')) - ui.set_progress((PROGRESS_SCALE) > 1 - ? parser.value_float() * (PROGRESS_SCALE) - : parser.value_byte() - ); - #if ENABLED(USE_M73_REMAINING_TIME) - if (parser.seenval('R')) ui.set_remaining_time(60 * parser.value_ulong()); + + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + + DWIN_Progress_Update(); + + #else + + if (parser.seenval('P')) + ui.set_progress((PROGRESS_SCALE) > 1 + ? parser.value_float() * (PROGRESS_SCALE) + : parser.value_byte() + ); + + #if ENABLED(USE_M73_REMAINING_TIME) + if (parser.seenval('R')) ui.set_remaining_time(60 * parser.value_ulong()); + #endif + #endif } diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index cd4933ff27..14bd712d27 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -48,6 +48,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" #endif #if ENABLED(HOST_ACTION_COMMANDS) @@ -106,6 +108,7 @@ void GcodeSuite::M1001() { #endif TERN_(EXTENSIBLE_UI, ExtUI::onPrintFinished()); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Print_Finished()); // Re-select the last printed file in the UI TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file()); diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 66f9f8eb8d..b55409946e 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -29,11 +29,19 @@ #include "../../MarlinCore.h" // for startOrResumeJob +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" +#endif + /** * M75: Start print timer */ void GcodeSuite::M75() { startOrResumeJob(); + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + DWIN_Print_Header(parser.string_arg && parser.string_arg[0] ? parser.string_arg : GET_TEXT(MSG_HOST_START_PRINT)); + DWIN_Print_Started(false); + #endif } /** @@ -49,29 +57,30 @@ void GcodeSuite::M76() { */ void GcodeSuite::M77() { print_job_timer.stop(); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Print_Finished()); } #if ENABLED(PRINTCOUNTER) -/** + /** * M78: Show print statistics */ -void GcodeSuite::M78() { - if (parser.intval('S') == 78) { // "M78 S78" will reset the statistics + void GcodeSuite::M78() { + if (parser.intval('S') == 78) { // "M78 S78" will reset the statistics print_job_timer.initStats(); ui.reset_status(); - return; + return; } #if HAS_SERVICE_INTERVALS - if (parser.seenval('R')) { + if (parser.seenval('R')) { print_job_timer.resetServiceInterval(parser.value_int()); ui.reset_status(); - return; + return; } #endif print_job_timer.showStats(); -} + } #endif // PRINTCOUNTER diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index ad3afe6e46..0d0ce478ee 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -30,6 +30,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin.h" #endif /** @@ -71,6 +73,7 @@ void GcodeSuite::M303() { default: SERIAL_ECHOLNPGM(STR_PID_BAD_HEATER_ID); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_BAD_EXTRUDER_NUM)); return; } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 825ad58f9a..a7bde803ba 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -493,7 +493,10 @@ #endif // Aliases for LCD features -#if ANY(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI) +#if EITHER(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED) + #define HAS_DWIN_E3V2_BASIC 1 +#endif +#if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DWIN_E3V2 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 59b4a68ff1..3c00d84142 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -808,7 +808,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, or EXTENSIBLE_UI." + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." #endif #if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) @@ -1748,7 +1748,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * LCD_BED_LEVELING requirements */ #if ENABLED(LCD_BED_LEVELING) - #if NONE(HAS_LCD_MENU, DWIN_CREALITY_LCD) + #if NONE(HAS_LCD_MENU, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED) #error "LCD_BED_LEVELING is not supported by the selected LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." @@ -2655,7 +2655,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ - + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ @@ -2763,6 +2763,18 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if DISABLED(SDSUPPORT) + #error "DWIN_CREALITY_LCD_ENHANCED requires SDSUPPORT to be enabled." + #elif ENABLED(PID_EDIT_MENU) + #error "DWIN_CREALITY_LCD_ENHANCED does not support PID_EDIT_MENU." + #elif ENABLED(PID_AUTOTUNE_MENU) + #error "DWIN_CREALITY_LCD_ENHANCED does not support PID_AUTOTUNE_MENU." + #elif ENABLED(LEVEL_BED_CORNERS) + #error "DWIN_CREALITY_LCD_ENHANCED does not support LEVEL_BED_CORNERS." + #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #error "DWIN_CREALITY_LCD_ENHANCED does not support LCD_BED_LEVELING with PROBE_MANUALLY." + #endif #endif /** diff --git a/Marlin/src/lcd/e3v2/creality/README.md b/Marlin/src/lcd/e3v2/README.md similarity index 100% rename from Marlin/src/lcd/e3v2/creality/README.md rename to Marlin/src/lcd/e3v2/README.md diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.h b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h index f73577b3b0..48e13b7ece 100644 --- a/Marlin/src/lcd/e3v2/creality/rotary_encoder.h +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h @@ -22,12 +22,12 @@ #pragma once /***************************************************************************** - * @file lcd/e3v2/creality/rotary_encoder.h - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - ****************************************************************************/ + * @file lcd/e3v2/creality/rotary_encoder.h + * @author LEO / Creality3D + * @date 2019/07/06 + * @version 2.0.1 + * @brief Rotary encoder functions + ****************************************************************************/ #include "../../../inc/MarlinConfig.h" diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp new file mode 100644 index 0000000000..e446733d9b --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -0,0 +1,3529 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + +#include "dwin.h" + +#include "../../fontutils.h" +#include "../../marlinui.h" + +#include "../../../sd/cardreader.h" + +#include "../../../MarlinCore.h" +#include "../../../core/serial.h" +#include "../../../core/macros.h" +#include "../../../gcode/queue.h" + +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" + +#if HAS_FILAMENT_SENSOR + #include "../../../feature/runout.h" +#endif + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../../feature/host_actions.h" +#endif + +#if HAS_ONESTEP_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #include "../../../feature/babystep.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#include +#include +#include + +#ifndef MACHINE_SIZE + #define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) +#endif + +#include "lockscreen.h" + +#ifndef CORP_WEBSITE + #define CORP_WEBSITE WEBSITE_URL +#endif + +#define PAUSE_HEAT + +#define USE_STRING_HEADINGS +#define USE_STRING_TITLES + +#define MENU_CHAR_LIMIT 24 + +// Print speed limit +#define MIN_PRINT_SPEED 10 +#define MAX_PRINT_SPEED 999 + +// Print flow limit +#define MIN_PRINT_FLOW 10 +#define MAX_PRINT_FLOW 299 + +// Load and Unload limits +#define MAX_LOAD_UNLOAD 500 + +// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) +#define MIN_MAXFEEDSPEED 1 +#define MIN_MAXACCELERATION 1 +#define MIN_MAXJERK 0.1 +#define MIN_STEP 1 +#define MAX_STEP 999.9 + +// Extruder's temperature limits +#define MIN_ETEMP HEATER_0_MINTEMP +#define MAX_ETEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) + +#define FEEDRATE_E (60) + +// Minimum unit (0.1) : multiple (10) +#define UNITFDIGITS 1 +#define MINUNITMULT POW(10, UNITFDIGITS) + +#define ENCODER_WAIT_MS 20 +#define DWIN_VAR_UPDATE_INTERVAL 1024 +#define DWIN_SCROLL_UPDATE_INTERVAL SEC_TO_MS(2) +#define DWIN_REMAIN_TIME_UPDATE_INTERVAL SEC_TO_MS(20) + +#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) + +// Structs +HMI_value_t HMI_value; +HMI_flag_t HMI_flag{0}; +HMI_data_t HMI_data; + +millis_t dwin_heat_time = 0; + +uint8_t checkkey = MainMenu; +uint8_t last_checkkey = MainMenu; + +typedef struct { + uint8_t now, last; + void set(uint8_t v) { now = last = v; } + void reset() { set(0); } + bool changed() { bool c = (now != last); if (c) last = now; return c; } + bool dec() { if (now) now--; return changed(); } + bool inc(uint8_t v) { if (now < (v - 1)) now++; else now = (v - 1); return changed(); } +} select_t; + +select_t select_page{0}, select_file{0}, select_print{0}; +uint8_t index_file = MROWS; + +bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home + +constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; +constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; + +#if HAS_CLASSIC_JERK + constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; +#endif + +static uint8_t _percent_done = 0; +static uint32_t _remain_time = 0; + +// Additional Aux Host Support +static bool sdprint = false; + +#if ENABLED(PAUSE_HEAT) + #if HAS_HOTEND + uint16_t resume_hotend_temp = 0; + #endif + #if HAS_HEATED_BED + uint16_t resume_bed_temp = 0; + #endif + #if HAS_FAN + uint16_t resume_fan = 0; + #endif +#endif + +#if HAS_ZOFFSET_ITEM + float dwin_zoffset = 0, last_zoffset = 0; +#endif + +#if HAS_HOTEND + float last_E = 0; +#endif + +// New menu system pointers +MenuClass *PrepareMenu = nullptr; +MenuClass *LevBedMenu = nullptr; +MenuClass *MoveMenu = nullptr; +MenuClass *ControlMenu = nullptr; +MenuClass *AdvancedSettings = nullptr; +TERN_(HAS_HOME_OFFSET, MenuClass *HomeOffMenu = nullptr); +TERN_(HAS_BED_PROBE, MenuClass *ProbeSetMenu = nullptr); +MenuClass *FilSetMenu = nullptr; +MenuClass *SelectColorMenu = nullptr; +MenuClass *GetColorMenu = nullptr; +MenuClass *TuneMenu = nullptr; +MenuClass *MotionMenu = nullptr; +MenuClass *FilamentMenu = nullptr; +TERN_(MESH_BED_LEVELING, MenuClass *ManualMesh = nullptr); +TERN_(HAS_HOTEND, MenuClass *PreheatMenu = nullptr); +MenuClass *TemperatureMenu = nullptr; +MenuClass *MaxSpeedMenu = nullptr; +MenuClass *MaxAccelMenu = nullptr; +MenuClass *MaxJerkMenu = nullptr; +MenuClass *StepsMenu = nullptr; +MenuClass *HotendPIDMenu = nullptr; +MenuClass *BedPIDMenu = nullptr; +#if EITHER(HAS_BED_PROBE, BABYSTEPPING) + MenuClass *ZOffsetWizMenu = nullptr; +#endif + +// Updatable menuitems pointers +MenuItemClass *HotendTargetItem = nullptr; +MenuItemClass *BedTargetItem = nullptr; +MenuItemClass *FanSpeedItem = nullptr; +MenuItemClass *MMeshMoveZItem = nullptr; + +#define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) + // BL24CXX::check() uses 0x00 + +inline bool HMI_IsChinese() { return HMI_flag.language == DWIN_CHINESE; } + +void HMI_SetLanguageCache() { + DWIN_JPG_CacheTo1(HMI_IsChinese() ? Language_Chinese : Language_English); +} + +void HMI_SetLanguage() { + #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif + HMI_SetLanguageCache(); +} + +void HMI_ToggleLanguage() { + HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; + HMI_SetLanguageCache(); + #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif +} + +typedef struct { uint16_t x, y[2], w, h; } text_info_t; + +void ICON_Button(const bool here, const int iconid, const frame_rect_t &ico, const text_info_t (&txt)[2]) { + const bool cn = HMI_IsChinese(); + DWIN_ICON_Show(1, 0, 0, ICON, iconid + here, ico.x, ico.y); + if (here) DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ico.x, ico.y, ico.x + ico.w - 1, ico.y + ico.h - 1); + DWIN_Frame_AreaCopy(1, txt[cn].x, txt[cn].y[here], txt[cn].x + txt[cn].w - 1, txt[cn].y[here] + txt[cn].h - 1, ico.x + (ico.w - txt[cn].w) / 2, (ico.y + ico.h - 28) - txt[cn].h/2); +} + +// +// Main Menu: "Print" +// +void ICON_Print() { + constexpr frame_rect_t ico = { 17, 110, 110, 100 }; + constexpr text_info_t txt[2] = { + { 1, { 417, 449 }, 30, 14 }, + { 1, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 0, ICON_Print_0, ico, txt); +} + +// +// Main Menu: "Prepare" +// +void ICON_Prepare() { + constexpr frame_rect_t ico = { 145, 110, 110, 100 }; + constexpr text_info_t txt[2] = { + { 33, { 417, 449 }, 51, 14 }, + { 31, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 1, ICON_Prepare_0, ico, txt); +} + +// +// Main Menu: "Control" +// +void ICON_Control() { + constexpr frame_rect_t ico = { 17, 226, 110, 100 }; + constexpr text_info_t txt[2] = { + { 85, { 417, 449 }, 46, 14 }, + { 61, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 2, ICON_Control_0, ico, txt); +} + +// +// Main Menu: "Info" +// +void ICON_StartInfo() { + constexpr frame_rect_t ico = { 145, 226, 110, 100 }; + constexpr text_info_t txt[2] = { + { 133, { 417, 449 }, 23, 14 }, + { 91, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 3, ICON_Info_0, ico, txt); +} + +// +// Main Menu: "Level" +// +void ICON_Leveling() { + constexpr frame_rect_t ico = { 145, 226, 110, 100 }; + constexpr text_info_t txt[2] = { + { 88, { 433, 464 }, 36, 14 }, + { 211, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_page.now == 3, ICON_Leveling_0, ico, txt); +} + +// +// Printing: "Tune" +// +void ICON_Tune() { + constexpr frame_rect_t ico = { 8, 232, 80, 100 }; + constexpr text_info_t txt[2] = { + { 0, { 433, 464 }, 32, 14 }, + { 121, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 0, ICON_Setup_0, ico, txt); +} + +// +// Printing: "Pause" +// +void ICON_Pause() { + constexpr frame_rect_t ico = { 96, 232, 80, 100 }; + constexpr text_info_t txt[2] = { + { 157, { 417, 449 }, 39, 14 }, + { 181, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 1, ICON_Pause_0, ico, txt); +} + +// +// Printing: "Resume" +// +void ICON_Resume() { + constexpr frame_rect_t ico = { 96, 232, 80, 100 }; + constexpr text_info_t txt[2] = { + { 33, { 433, 464 }, 53, 14 }, + { 1, { 405, 447 }, 27, 15 } + }; + ICON_Button(select_print.now == 1, ICON_Continue_0, ico, txt); +} + +// +// Printing: "Stop" +// +void ICON_Stop() { + constexpr frame_rect_t ico = { 184, 232, 80, 100 }; + constexpr text_info_t txt[2] = { + { 196, { 417, 449 }, 29, 14 }, + { 151, { 405, 447 }, 27, 12 } + }; + ICON_Button(select_print.now == 2, ICON_Stop_0, ico, txt); +} + +void Draw_Menu_Cursor(const uint8_t line) { + DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Erase_Menu_Cursor(const uint8_t line) { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Move_Highlight(const int16_t from, const uint16_t newline) { + Erase_Menu_Cursor(newline - from); + Draw_Menu_Cursor(newline); +} + +void Add_Menu_Line() { + Move_Highlight(1, MROWS); + DWIN_Draw_Line(HMI_data.SplitLine_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); +} + +void Scroll_Menu(const uint8_t dir) { + DWIN_Frame_AreaMove(1, dir, MLINE, HMI_data.Background_Color, 0, 31, DWIN_WIDTH, 349); + switch (dir) { + case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; + case DWIN_SCROLL_UP: Add_Menu_Line(); break; + } +} + +inline uint16_t nr_sd_menu_items() { + return card.get_num_Files() + !card.flag.workDirIsRoot; +} + +void Erase_Menu_Text(const uint8_t line) { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); +} + +void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { + if (label) DWINUI::Draw_String(LBLX, MBASE(line) - 1, (char*)label); + if (icon) DWINUI::Draw_Icon(icon, 26, MBASE(line) - 3); + if (more) DWINUI::Draw_Icon(ICON_More, 226, MBASE(line) - 3); + DWIN_Draw_Line(HMI_data.SplitLine_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 33); +} + +void Draw_Chkb_Line(const uint8_t line, const bool checked) { + DWINUI::Draw_Checkbox(HMI_data.Text_Color, HMI_data.Background_Color, VALX + 16, MBASE(line) - 1, checked); +} + +void Draw_Menu_IntValue(uint16_t bcolor, const uint8_t line, uint8_t iNum, const uint16_t value=0) { + DWINUI::Draw_Int(HMI_data.Text_Color, bcolor, iNum , VALX, MBASE(line) - 1, value); +} + +// The "Back" label is always on the first line +void Draw_Back_Label() { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); + else + DWIN_Frame_AreaCopy(1, 223, 179, 254, 189, LBLX, MBASE(0)); +} + +// Draw "Back" line at the top +void Draw_Back_First(const bool is_sel=true) { + Draw_Menu_Line(0, ICON_Back); + Draw_Back_Label(); + if (is_sel) Draw_Menu_Cursor(0); +} + +inline ENCODER_DiffState get_encoder_state() { + static millis_t Encoder_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; + const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); + if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; + return state; +} + +template +inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) { + if (encoder_diffState == ENCODER_DIFF_CW) + valref += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + valref -= EncoderRate.encoderMoveValue; + return encoder_diffState == ENCODER_DIFF_ENTER; +} + +// +// Draw Popup Windows +// + +inline void Draw_Popup_Bkgd_60() { + DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 60, 258, 330); + DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, 14, 60, 258, 330); +} + +inline void Draw_Popup_Bkgd_105() { + DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 105, 258, 374); + DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, 14, 105, 258, 374); +} + +void Clear_Popup_Area() { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); +} + +void DWIN_Draw_Popup(uint8_t icon=0, const char * const msg1=nullptr, const char * const msg2=nullptr, uint8_t button=0) { + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd_60(); + if (icon) DWINUI::Draw_Icon(icon, 101, 105); + if (msg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, msg1); + if (msg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, msg2); + if (button) DWINUI::Draw_Icon(button, 86, 280); +} + +void DWIN_Popup_Confirm(uint8_t icon, const char * const msg1, const char * const msg2) { + HMI_SaveProcessID(WaitResponse); + DWIN_Draw_Popup(icon, msg1, msg2, ICON_Confirm_E); // Button Confirm + DWIN_UpdateLCD(); +} + +void DWIN_Popup_Continue(uint8_t icon, const char * const msg1, const char * const msg2) { + HMI_SaveProcessID(WaitResponse); + DWIN_Draw_Popup(icon, msg1, msg2, ICON_Continue_E); // Button Continue + DWIN_UpdateLCD(); +} + +#if HAS_HOTEND + + void Popup_Window_ETempTooLow() { + if (HMI_IsChinese()) { + HMI_SaveProcessID(WaitResponse); + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd_60(); + DWINUI::Draw_Icon(ICON_TempTooLow, 102, 105); + DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); + DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); + DWINUI::Draw_Icon(ICON_Confirm_C, 86, 280); + DWIN_UpdateLCD(); + } + else + DWIN_Popup_Confirm(ICON_TempTooLow, "Nozzle is too cold", "Preheat the hotend"); + } + +#endif + +void Popup_Window_Resume() { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); + DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); + DWINUI::Draw_Icon(ICON_Cancel_C, 26, 307); + DWINUI::Draw_Icon(ICON_Continue_C, 146, 307); + } + else { + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 115, F("Continue Print")); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 192, F("It looks like the last")); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 212, F("file was interrupted.")); + DWINUI::Draw_Icon(ICON_Cancel_E, 26, 307); + DWINUI::Draw_Icon(ICON_Continue_E, 146, 307); + } +} + +void Draw_Select_Highlight(const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color, + c2 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void Popup_window_PauseOrStop() { + if (HMI_IsChinese()) { + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd_60(); + if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); + DWINUI::Draw_Icon(ICON_Confirm_C, 26, 280); + DWINUI::Draw_Icon(ICON_Cancel_C, 146, 280); + } + else { + DWIN_Draw_Popup(ICON_BLTouch, "Please confirm",(select_print.now == 1) ? GET_TEXT(MSG_PAUSE_PRINT) : GET_TEXT(MSG_STOP_PRINT)); + DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); + DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); + } + Draw_Select_Highlight(true); +} + +#if HAS_HOTEND || HAS_HEATED_BED + void DWIN_Popup_Temperature(const bool toohigh) { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (toohigh) { + DWINUI::Draw_Icon(ICON_TempTooHigh, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWINUI::Draw_String(HMI_data.PopupTxt_Color, 36, 300, F("Nozzle or Bed temperature")); + DWINUI::Draw_String(HMI_data.PopupTxt_Color, 92, 300, F("is too high")); + } + } + else { + DWINUI::Draw_Icon(ICON_TempTooLow, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWINUI::Draw_String(HMI_data.PopupTxt_Color, 36, 300, F("Nozzle or Bed temperature")); + DWINUI::Draw_String(HMI_data.PopupTxt_Color, 92, 300, F("is too low")); + } + } + } + +#endif + +void Draw_Print_Labels() { + if (HMI_IsChinese()) { + Title.FrameCopy(30, 1, 42, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 173); // Printing Time + DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain + } + else { + #ifdef USE_STRING_TITLES + Title.ShowCaption(GET_TEXT(MSG_PRINTING)); + DWINUI::Draw_String( 46, 173, F("Print Time")); + DWINUI::Draw_String(181, 173, F("Remain")); + #else + const uint16_t y = 168; + Title.FrameCopy(42, 0, 47, 14); // "Printing" + DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, y); // Printing Time + DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, y); // Remain + #endif + } +} + +void Draw_Print_ProgressBar() { + DWINUI::Draw_Icon(ICON_Bar, 15, 93); + DWIN_Draw_Rectangle(1, HMI_data.Barfill_Color, 16 + _percent_done * 240 / 100, 93, 256, 113); + DWINUI::Draw_Int(HMI_data.PercentTxt_Color, HMI_data.Background_Color, 3, 117, 133, _percent_done); + DWINUI::Draw_String(HMI_data.PercentTxt_Color, 142, 133, F("%")); +} + +void Draw_Print_ProgressElapsed() { + char buf[10]; + duration_t elapsed = print_job_timer.duration(); // print timer + sprintf_P(buf, PSTR("%02i:%02i"), (uint16_t)(elapsed.value / 3600), ((uint16_t)elapsed.value % 3600) / 60); + DWINUI::Draw_String(HMI_data.Text_Color, HMI_data.Background_Color, 47, 192, buf); +} + +void Draw_Print_ProgressRemain() { + char buf[10]; + sprintf_P(buf, PSTR("%02i:%02i"), (uint16_t)(_remain_time / 3600), ((uint16_t)_remain_time % 3600) / 60); + DWINUI::Draw_String(HMI_data.Text_Color, HMI_data.Background_Color, 181, 192, buf); +} + +void ICON_ResumeOrPause() { + if (printingIsPaused() || HMI_flag.pause_flag || HMI_flag.pause_action) + ICON_Resume(); + else + ICON_Pause(); +} + +void Draw_PrintProcess() { + DWINUI::ClearMenuArea(); + Draw_Print_Labels(); + + ICON_Tune(); + ICON_ResumeOrPause(); + ICON_Stop(); + + DWIN_Print_Header(sdprint ? card.longest_filename() : nullptr); + + DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); + DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); + + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + Draw_Print_ProgressRemain(); + + DWIN_UpdateLCD(); +} + +void Goto_PrintProcess() { + checkkey = PrintProcess; + Draw_PrintProcess(); +} + +void Draw_PrintDone() { + // show percent bar and value + _percent_done = 100; + _remain_time = 0; + + DWINUI::ClearMenuArea(); + DWIN_Print_Header(nullptr); + Draw_Print_Labels(); + DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); + DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + Draw_Print_ProgressRemain(); + + // show print done confirm + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 240, DWIN_WIDTH - 1, STATUS_Y - 1); + DWINUI::Draw_Icon(HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); +} + +void Draw_Main_Menu() { + DWINUI::ClearMenuArea(); + + if (HMI_IsChinese()) + Title.FrameCopy(2, 2, 26, 13); // "Home" etc + else { + #ifdef USE_STRING_HEADINGS + Title.ShowCaption(MACHINE_NAME); + #else + Title.FrameCopy(0, 2, 40, 11); // "Home" + #endif + } + + DWINUI::Draw_Icon(ICON_LOGO, 71, 52); // CREALITY logo + + ICON_Print(); + ICON_Prepare(); + ICON_Control(); + TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); + DWIN_UpdateLCD(); +} + +void Goto_Main_Menu() { + checkkey = MainMenu; + DWIN_StatusChanged(nullptr); + Draw_Main_Menu(); +} + +// Draw X, Y, Z and blink if in an un-homed or un-trusted state +void _update_axis_value(const AxisEnum axis, const uint16_t x, const uint16_t y, const bool blink, const bool force) { + const bool draw_qmark = axis_should_home(axis), + draw_empty = NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !draw_qmark && !axis_is_trusted(axis); + + // Check for a position change + static xyz_pos_t oldpos = { -1, -1, -1 }; + const float p = current_position[axis]; + const bool changed = oldpos[axis] != p; + if (changed) oldpos[axis] = p; + + if (force || changed || draw_qmark || draw_empty) { + if (blink && draw_qmark) + DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F("--?--")); + else if (blink && draw_empty) + DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" ")); + else + DWINUI::Draw_Signed_Float(HMI_data.Coordinate_Color, HMI_data.Background_Color, 3, 1, x, y, p * 10); + } +} + +void _draw_xyz_position(const bool force) { + //SERIAL_ECHOPGM("Draw XYZ:"); + static bool _blink = false; + const bool blink = !!(millis() & 0x400UL); + if (force || blink != _blink) { + _blink = blink; + //SERIAL_ECHOPGM(" (blink)"); + _update_axis_value(X_AXIS, 35, 459, blink, true); + _update_axis_value(Y_AXIS, 120, 459, blink, true); + _update_axis_value(Z_AXIS, 205, 459, blink, true); + } + //SERIAL_EOL(); +} + +void update_variable() { + #if HAS_HOTEND + static celsius_t _hotendtemp = 0, _hotendtarget = 0; + const celsius_t hc = thermalManager.wholeDegHotend(0), + ht = thermalManager.degTargetHotend(0); + const bool _new_hotend_temp = _hotendtemp != hc, + _new_hotend_target = _hotendtarget != ht; + if (_new_hotend_temp) _hotendtemp = hc; + if (_new_hotend_target) _hotendtarget = ht; + #endif + #if HAS_HEATED_BED + static celsius_t _bedtemp = 0, _bedtarget = 0; + const celsius_t bc = thermalManager.wholeDegBed(), + bt = thermalManager.degTargetBed(); + const bool _new_bed_temp = _bedtemp != bc, + _new_bed_target = _bedtarget != bt; + if (_new_bed_temp) _bedtemp = bc; + if (_new_bed_target) _bedtarget = bt; + #endif + #if HAS_FAN + static uint8_t _fanspeed = 0; + const bool _new_fanspeed = _fanspeed != thermalManager.fan_speed[0]; + if (_new_fanspeed) _fanspeed = thermalManager.fan_speed[0]; + #endif + + if (checkkey == Menu && (CurrentMenu == TuneMenu || CurrentMenu == TemperatureMenu)) { + // Tune page temperature update + #if HAS_HOTEND + if (_new_hotend_target) + HotendTargetItem->Draw(CurrentMenu->line(HotendTargetItem->pos)); + #endif + #if HAS_HEATED_BED + if (_new_bed_target) + BedTargetItem->Draw(CurrentMenu->line(BedTargetItem->pos)); + #endif + #if HAS_FAN + if (_new_fanspeed) + FanSpeedItem->Draw(CurrentMenu->line(FanSpeedItem->pos)); + #endif + } + + // Bottom temperature update + + #if HAS_HOTEND + if (_new_hotend_temp) + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 28, 384, _hotendtemp); + if (_new_hotend_target) + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 384, _hotendtarget); + + static int16_t _flow = planner.flow_percentage[0]; + if (_flow != planner.flow_percentage[0]) { + _flow = planner.flow_percentage[0]; + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 116 + 2 * STAT_CHR_W, 417, _flow); + } + #endif + + #if HAS_HEATED_BED + if (_new_bed_temp) + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 28, 417, _bedtemp); + if (_new_bed_target) + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 417, _bedtarget); + #endif + + static int16_t _feedrate = 100; + if (_feedrate != feedrate_percentage) { + _feedrate = feedrate_percentage; + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 116 + 2 * STAT_CHR_W, 384, _feedrate); + } + + #if HAS_FAN + if (_new_fanspeed) { + _fanspeed = thermalManager.fan_speed[0]; + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 195 + 2 * STAT_CHR_W, 384, _fanspeed); + } + #endif + + static float _offset = 0; + if (BABY_Z_VAR != _offset) { + _offset = BABY_Z_VAR; + DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, _offset * 100); + } + + _draw_xyz_position(false); +} + +/** + * Read and cache the working directory. + * + * TODO: New code can follow the pattern of menu_media.cpp + * and rely on Marlin caching for performance. No need to + * cache files here. + */ + +#ifndef strcasecmp_P + #define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif + +void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { + char * const name = card.longest_filename(); + size_t pos = strlen(name); // index of ending nul + + // For files, remove the extension + // which may be .gcode, .gco, or .g + if (!card.flag.filenameIsDir) + while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) + + size_t len = pos; // nul or '.' + if (len > maxlen) { // Keep the name short + pos = len = maxlen; // move nul down + dst[--pos] = '.'; // insert dots + dst[--pos] = '.'; + dst[--pos] = '.'; + } + + dst[len] = '\0'; // end it + + // Copy down to 0 + while (pos--) dst[pos] = src[pos]; +} + +void HMI_SDCardInit() { card.cdroot(); } + +void MarlinUI::refresh() { /* Nothing to see here */ } + +#define ICON_Folder ICON_More + +#if ENABLED(SCROLL_LONG_FILENAMES) + + char shift_name[LONG_FILENAME_LENGTH + 1]; + int8_t shift_amt; // = 0 + millis_t shift_ms; // = 0 + + // Init the shift name based on the highlighted item + void Init_Shift_Name() { + const bool is_subdir = !card.flag.workDirIsRoot; + const int8_t filenum = select_file.now - 1 - is_subdir; // Skip "Back" and ".." + const uint16_t fileCnt = card.get_num_Files(); + if (WITHIN(filenum, 0, fileCnt - 1)) { + card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); + char * const name = card.longest_filename(); + make_name_without_ext(shift_name, name, 100); + } + } + + void Init_SDItem_Shift() { + shift_amt = 0; + shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT ? millis() + 750UL : 0; + } + +#endif + +/** + * Display an SD item, adding a CDUP for subfolders. + */ +void Draw_SDItem(const uint16_t item, int16_t row=-1) { + if (row < 0) row = item + 1 + MROWS - index_file; + const bool is_subdir = !card.flag.workDirIsRoot; + if (is_subdir && item == 0) + return Draw_Menu_Line(row, ICON_Folder, ".."); + + card.getfilename_sorted(SD_ORDER(item - is_subdir, card.get_num_Files())); + char * const name = card.longest_filename(); + + #if ENABLED(SCROLL_LONG_FILENAMES) + // Init the current selected name + // This is used during scroll drawing + if (item == select_file.now - 1) { + make_name_without_ext(shift_name, name, 100); + Init_SDItem_Shift(); + } + #endif + + // Draw the file/folder with name aligned left + char str[strlen(name) + 1]; + make_name_without_ext(str, name); + Draw_Menu_Line(row, card.flag.filenameIsDir ? ICON_Folder : ICON_File, str); +} + +#if ENABLED(SCROLL_LONG_FILENAMES) + + void Draw_SDItem_Shifted(uint8_t &shift) { + // Limit to the number of chars past the cutoff + const size_t len = strlen(shift_name); + NOMORE(shift, _MAX(len - MENU_CHAR_LIMIT, 0U)); + + // Shorten to the available space + const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); + + const char c = shift_name[lastchar]; + shift_name[lastchar] = '\0'; + + const uint8_t row = select_file.now + MROWS - index_file; // skip "Back" and scroll + Erase_Menu_Text(row); + Draw_Menu_Line(row, 0, &shift_name[shift]); + + shift_name[lastchar] = c; + } + +#endif + +// Redraw the first set of SD Files +void Redraw_SD_List() { + select_file.reset(); + index_file = MROWS; + + DWINUI::ClearMenuArea(); // Leave title bar unchanged + + Draw_Back_First(); + + if (card.isMounted()) { + // As many files as will fit + LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) + Draw_SDItem(i, i + 1); + + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + else { + DWIN_Draw_Rectangle(1, HMI_data.AlertBg_Color, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); + DWINUI::Draw_CenteredString(font16x32, HMI_data.AlertTxt_Color, MBASE(3), F("No Media")); + } +} + +bool DWIN_lcd_sd_status = false; + +void SDCard_Up() { + card.cdup(); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +void SDCard_Folder(char * const dirname) { + card.cd(dirname); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +// +// Watch for media mount / unmount +// +void HMI_SDCardUpdate() { + if (HMI_flag.home_flag) return; + if (DWIN_lcd_sd_status != card.isMounted()) { + DWIN_lcd_sd_status = card.isMounted(); + //SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); + if (DWIN_lcd_sd_status) { + if (checkkey == SelectFile) + Redraw_SD_List(); + } + else { + // clean file icon + if (checkkey == SelectFile) { + Redraw_SD_List(); + } + else if (sdprint && card.isPrinting() && printingIsActive()) { + // TODO: Move card removed abort handling + // to CardReader::manage_media. + card.abortFilePrintSoon(); + wait_for_heatup = wait_for_user = false; + dwin_abort_flag = true; // Reset feedrate, return to Home + } + } + DWIN_UpdateLCD(); + } +} + +// +// The status area is always on-screen, except during +// full-screen modal dialogs. (TODO: Keep alive during dialogs) +// +void Draw_Status_Area(const bool with_update) { + + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, STATUS_Y + 21, DWIN_WIDTH, DWIN_HEIGHT - 1); + + #if HAS_HOTEND + DWINUI::Draw_Icon(ICON_HotendTemp, 10, 383); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 28, 384, thermalManager.wholeDegHotend(0)); + DWINUI::Draw_String(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.degTargetHotend(0)); + + DWINUI::Draw_Icon(ICON_StepE, 112, 417); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); + DWINUI::Draw_String(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + #endif + + #if HAS_HEATED_BED + DWINUI::Draw_Icon(ICON_BedTemp, 10, 416); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 28, 417, thermalManager.wholeDegBed()); + DWINUI::Draw_String(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + DWINUI::Draw_Int(true, true, 0, DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.degTargetBed()); + #endif + + DWINUI::Draw_Icon(ICON_Speed, 113, 383); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); + DWINUI::Draw_String(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + + #if HAS_FAN + DWINUI::Draw_Icon(ICON_FanSpeed, 187, 383); + DWINUI::Draw_Int(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); + #endif + + #if HAS_ZOFFSET_ITEM + DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); + #endif + + if (BABY_Z_VAR < 0) { + DWINUI::Draw_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 207, 417, -BABY_Z_VAR * 100); + DWINUI::Draw_String(HMI_data.Indicator_Color, 205, 419, F("-")); + } + else { + DWINUI::Draw_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 207, 417, BABY_Z_VAR * 100); + DWINUI::Draw_String(HMI_data.Indicator_Color, 205, 419, F(" ")); + } + + DWIN_Draw_Rectangle(1, HMI_data.SplitLine_Color, 0, 449, DWIN_WIDTH, 451); + + DWINUI::Draw_Icon(ICON_MaxSpeedX, 10, 456); + DWINUI::Draw_Icon(ICON_MaxSpeedY, 95, 456); + DWINUI::Draw_Icon(ICON_MaxSpeedZ, 180, 456); + _draw_xyz_position(true); + + if (with_update) { + DWIN_UpdateLCD(); + delay(5); + } +} + +void HMI_StartFrame(const bool with_update) { + Goto_Main_Menu(); + Draw_Status_Area(with_update); +} + +void Draw_Info_Menu() { + DWINUI::ClearMenuArea(); + Draw_Back_First(); + + DWINUI::Draw_CenteredString(122, F(MACHINE_SIZE)); + DWINUI::Draw_CenteredString(195, F(SHORT_BUILD_VERSION)); + + if (HMI_IsChinese()) { + Title.FrameCopy(30, 17, 28, 13); // "Info" + + DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); // "Size" + DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" + DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" + } + else { + #ifdef USE_STRING_HEADINGS + Title.ShowCaption(GET_TEXT_F(MSG_INFO_SCREEN)); + #else + Title.FrameCopy(192, 15, 23, 12); // "Info" + #endif + + DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); // "Size" + DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); // "Firmware Version" + DWIN_Frame_AreaCopy(1, 1, 164, 96, 175, 89, 248); // "Contact details" + } + DWINUI::Draw_CenteredString(268, F(CORP_WEBSITE)); + + LOOP_L_N(i, 3) { + DWINUI::Draw_Icon(ICON_PrintSize + i, 26, 99 + i * 73); + DWIN_Draw_Line(HMI_data.SplitLine_Color, 16, MBASE(2) + i * 73, 256, 156 + i * 73); + } + + DWIN_UpdateLCD(); +} + +void Draw_Print_File_Menu() { + if (HMI_IsChinese()) + Title.FrameCopy(0, 31, 56, 14); // "Print file" + else { + #ifdef USE_STRING_HEADINGS + Title.ShowCaption(GET_TEXT_F(MSG_MEDIA_MENU)); + #else + Title.FrameCopy(52, 31, 86, 11); // "Print file" + #endif + } + Redraw_SD_List(); +} + +// Main Process +void HMI_MainMenu() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_page.inc(4)) { + switch (select_page.now) { + case 0: ICON_Print(); break; + case 1: ICON_Print(); ICON_Prepare(); break; + case 2: ICON_Prepare(); ICON_Control(); break; + case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_page.dec()) { + switch (select_page.now) { + case 0: ICON_Print(); ICON_Prepare(); break; + case 1: ICON_Prepare(); ICON_Control(); break; + case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_page.now) { + case 0: // Print File + checkkey = SelectFile; + Draw_Print_File_Menu(); + break; + + case 1: // Prepare + Draw_Prepare_Menu(); + break; + + case 2: // Control + Draw_Control_Menu(); + break; + + case 3: // Leveling or Info + #if HAS_ONESTEP_LEVELING + queue.inject_P(PSTR("G28XYO\nG28Z\nG29")); + #else + checkkey = Info; + Draw_Info_Menu(); + #endif + break; + } + } + DWIN_UpdateLCD(); +} + +// Select (and Print) File +void HMI_SelectFile() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + + const uint16_t hasUpDir = !card.flag.workDirIsRoot; + + if (encoder_diffState == ENCODER_DIFF_NO) { + #if ENABLED(SCROLL_LONG_FILENAMES) + if (shift_ms && select_file.now >= 1 + hasUpDir) { + // Scroll selected filename every second + const millis_t ms = millis(); + if (ELAPSED(ms, shift_ms)) { + const bool was_reset = shift_amt < 0; + shift_ms = ms + 375UL + was_reset * 250UL; // ms per character + uint8_t shift_new = shift_amt + 1; // Try to shift by... + Draw_SDItem_Shifted(shift_new); // Draw the item + if (!was_reset && shift_new == 0) // Was it limited to 0? + shift_ms = 0; // No scrolling needed + else if (shift_new == shift_amt) // Scroll reached the end + shift_new = -1; // Reset + shift_amt = shift_new; // Set new scroll + } + } + #endif + return; + } + + // First pause is long. Easy. + // On reset, long pause must be after 0. + + const uint16_t fullCnt = nr_sd_menu_items(); + + if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { + if (select_file.inc(1 + fullCnt)) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(itemnum + MROWS - index_file); // Erase and + Draw_SDItem(itemnum - 1); // redraw + } + if (select_file.now > MROWS && select_file.now > index_file) { // Cursor past the bottom + index_file = select_file.now; // New bottom line + Scroll_Menu(DWIN_SCROLL_UP); + Draw_SDItem(itemnum, MROWS); // Draw and init the shift name + } + else { + Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW && fullCnt) { + if (select_file.dec()) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(select_file.now + 1 + MROWS - index_file); // Erase and + Draw_SDItem(itemnum + 1); // redraw + } + if (select_file.now < index_file - MROWS) { // Cursor past the top + index_file--; // New bottom line + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_file == MROWS) { + Draw_Back_First(); + TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); + } + else { + Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) + } + } + else { + Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); // Reset left. Init timer. + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_file.now == 0) { // Back + select_page.set(0); + Goto_Main_Menu(); + } + else if (hasUpDir && select_file.now == 1) { // CD-Up + SDCard_Up(); + goto HMI_SelectFileExit; + } + else { + const uint16_t filenum = select_file.now - 1 - hasUpDir; + card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + + // Enter that folder! + if (card.flag.filenameIsDir) { + SDCard_Folder(card.filename); + goto HMI_SelectFileExit; + } + + // Reset highlight for next entry + select_print.reset(); + select_file.reset(); + + // Start choice and print SD file + HMI_flag.heat_flag = true; + HMI_flag.print_finish = false; + + card.openAndPrintFile(card.filename); + + #if HAS_FAN + // All fans on for Ender 3 v2 ? + // The slicer should manage this for us. + //for (uint8_t i = 0; i < FAN_COUNT; i++) + // thermalManager.fan_speed[i] = 255; + #endif + + DWIN_Print_Started(true); + } + } +HMI_SelectFileExit: + DWIN_UpdateLCD(); +} + +// Printing +void HMI_Printing() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_print.inc(3)) { + switch (select_print.now) { + case 0: ICON_Tune(); break; + case 1: + ICON_Tune(); + ICON_ResumeOrPause(); + break; + case 2: + ICON_ResumeOrPause(); + ICON_Stop(); + break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_print.dec()) { + switch (select_print.now) { + case 0: + ICON_Tune(); + ICON_ResumeOrPause(); + break; + case 1: + ICON_ResumeOrPause(); + ICON_Stop(); + break; + case 2: ICON_Stop(); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_print.now) { + case 0: // Tune + Draw_Tune_Menu(); + break; + case 1: // Pause + if (HMI_flag.pause_flag) { + ICON_Pause(); + #ifndef ADVANCED_PAUSE_FEATURE + char cmd[40]; + cmd[0] = '\0'; + #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) + if (resume_bed_temp) sprintf_P(cmd, PSTR("M190 S%i\n"), resume_bed_temp); + #endif + #if BOTH(HAS_HOTEND, PAUSE_HEAT) + if (resume_hotend_temp) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), resume_hotend_temp); + #endif + #if HAS_FAN + if (resume_fan) thermalManager.fan_speed[0] = resume_fan; + #endif + strcat_P(cmd, M24_STR); + queue.inject(cmd); + #endif + } + else { + HMI_flag.select_flag = true; + checkkey = PauseOrStop; + Popup_window_PauseOrStop(); + } + break; + + case 2: // Stop + HMI_flag.select_flag = true; + checkkey = PauseOrStop; + Popup_window_PauseOrStop(); + break; + + default: break; + } + } + DWIN_UpdateLCD(); +} + +// Print done +void HMI_PrintDone() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + dwin_abort_flag = true; // Reset feedrate, return to Home + Goto_Main_Menu(); // Return to Main menu after print done + } +} + +// Pause or Stop popup +void HMI_PauseOrStop() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) + Draw_Select_Highlight(false); + else if (encoder_diffState == ENCODER_DIFF_CCW) + Draw_Select_Highlight(true); + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_print.now == 1) { // pause window + if (HMI_flag.select_flag) { + HMI_flag.pause_action = true; + ICON_Resume(); + queue.inject_P(PSTR("M25")); + } + else { + // cancel pause + } + Goto_PrintProcess(); + } + else if (select_print.now == 2) { // stop window + if (HMI_flag.select_flag) { + checkkey = MainMenu; + if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! + wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user + card.abortFilePrintSoon(); // Let the main loop handle SD abort + dwin_abort_flag = true; // Reset feedrate, return to Home + #ifdef ACTION_ON_CANCEL + host_action_cancel(); + #endif + DWIN_Draw_Popup(ICON_BLTouch, "Stopping..." , "Please wait until done."); + } + else + Goto_PrintProcess(); // cancel stop + } + } + DWIN_UpdateLCD(); +} + +#include "../../../libs/buzzer.h" + +void HMI_AudioFeedback(const bool success/*=true*/) { + #if HAS_BUZZER + if (success) { + BUZZ(100, 659); + BUZZ(10, 0); + BUZZ(100, 698); + } + else + BUZZ(40, 440); + #endif +} + +void Draw_Main_Area() { + switch (checkkey) { + case MainMenu: Draw_Main_Menu(); break; + case SelectFile: Draw_Print_File_Menu(); break; + case PrintProcess: Draw_PrintProcess(); break; + case PrintDone: Draw_PrintDone(); break; + case Info: Draw_Info_Menu(); break; + case PauseOrStop: Popup_window_PauseOrStop(); break; + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case FilamentPurge: Draw_Popup_FilamentPurge(); break; + #endif + case Locked: LockScreen.Draw(); break; + case Menu: + case SetInt: + case SetPInt: + case SetIntNoDraw: + case SetFloat: + case SetPFloat: CurrentMenu->Draw(); break; + default: break; + } +} + +void HMI_ReturnScreen() { + checkkey = last_checkkey; + Draw_Main_Area(); + DWIN_UpdateLCD(); + return; +} + +void HMI_Popup() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + wait_for_user = false; + HMI_ReturnScreen(); + } +} + +void HMI_Init() { + HMI_SDCardInit(); + + for (uint16_t t = 0; t <= 100; t += 2) { + DWINUI::Draw_Icon(ICON_Bar, 15, 260); + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 15 + t * 242 / 100, 260, 257, 280); + DWIN_UpdateLCD(); + delay(20); + } + + HMI_SetLanguage(); +} + +void DWIN_Update() { + EachMomentUpdate(); // Status update + HMI_SDCardUpdate(); // SD card update + DWIN_HandleScreen(); // Rotary encoder update +} + +void EachMomentUpdate() { + static millis_t next_var_update_ms = 0, next_rts_update_ms = 0; + + const millis_t ms = millis(); + if (ELAPSED(ms, next_var_update_ms)) { + next_var_update_ms = ms + DWIN_VAR_UPDATE_INTERVAL; + update_variable(); + } + + if (PENDING(ms, next_rts_update_ms)) return; + next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; + + if (checkkey == PrintProcess) { + // if print done + if (HMI_flag.print_finish) { + HMI_flag.print_finish = false; + TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); + planner.finish_and_disable(); + checkkey = PrintDone; + Draw_PrintDone(); + } + else if (HMI_flag.pause_flag != printingIsPaused()) { + // print status update + HMI_flag.pause_flag = printingIsPaused(); + ICON_ResumeOrPause(); + } + } + + // pause after homing + if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { + HMI_flag.pause_action = false; + #if ENABLED(PAUSE_HEAT) + if (sdprint) { + TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.degTargetHotend(0)); + TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.degTargetBed()); + } + else { + TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.wholeDegHotend(0)); + TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.wholeDegBed()); + } + TERN_(HAS_FAN, resume_fan = thermalManager.fan_speed[0]); + #endif + #if DISABLED(ADVANCED_PAUSE_FEATURE) + thermalManager.disable_all_heaters(); + #endif + #if DISABLED(PARK_HEAD_ON_PAUSE) + queue.inject_P(PSTR("G1 F1200 X0 Y0")); + #endif + } + + if (checkkey == PrintProcess) { // print process + + duration_t elapsed = print_job_timer.duration(); // print timer + + if (sdprint && card.isPrinting()) { + uint8_t percentDone = card.percentDone(); + static uint8_t last_percentValue = 101; + if (last_percentValue != percentDone) { // print percent + last_percentValue = percentDone; + if (percentDone) { + _percent_done = percentDone; + Draw_Print_ProgressBar(); + } + } + + // Estimate remaining time every 20 seconds + static millis_t next_remain_time_update = 0; + if (_percent_done > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { + _remain_time = (elapsed.value - dwin_heat_time) / (_percent_done * 0.01f) - (elapsed.value - dwin_heat_time); + next_remain_time_update += DWIN_REMAIN_TIME_UPDATE_INTERVAL; + Draw_Print_ProgressRemain(); + } + } + + // Print time so far + static uint16_t last_Printtime = 0; + const uint16_t min = (elapsed.value % 3600) / 60; + if (last_Printtime != min) { // 1 minute update + last_Printtime = min; + Draw_Print_ProgressElapsed(); + } + + } + else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop + dwin_abort_flag = false; + dwin_zoffset = BABY_Z_VAR; + select_page.set(0); + Goto_Main_Menu(); + } + #if ENABLED(POWER_LOSS_RECOVERY) + else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off + static bool recovery_flag = false; + + recovery.dwin_flag = false; + recovery_flag = true; + + auto update_selection = [&](const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; + DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); + DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); + const uint16_t c2 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color; + DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); + DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); + }; + + Popup_Window_Resume(); + update_selection(true); + + // TODO: Get the name of the current file from someplace + // + //(void)recovery.interrupted_file_exists(); + SdFile *dir = nullptr; + const char * const filename = card.diveToFile(true, dir, recovery.info.sd_filename); + card.selectFileByName(filename); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 252, card.longest_filename()); + DWIN_UpdateLCD(); + + while (recovery_flag) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + recovery_flag = false; + if (HMI_flag.select_flag) break; + TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); + return HMI_StartFrame(true); + } + else + update_selection(encoder_diffState == ENCODER_DIFF_CW); + + DWIN_UpdateLCD(); + } + watchdog_refresh(); + } + + select_print.set(0); + queue.inject_P(PSTR("M1000")); + sdprint = true; + Goto_PrintProcess(); + Draw_Status_Area(true); + } + #endif // POWER_LOSS_RECOVERY + + DWIN_UpdateLCD(); +} + +void DWIN_HandleScreen() { + switch (checkkey) { + case MainMenu: HMI_MainMenu(); break; + case Menu: HMI_Menu(); break; + case SetInt: HMI_SetInt(); break; + case SetPInt: HMI_SetPInt(); break; + case SetIntNoDraw: HMI_SetIntNoDraw(); break; + case SetFloat: HMI_SetFloat(); break; + case SetPFloat: HMI_SetPFloat(); break; + case SelectFile: HMI_SelectFile(); break; + case Homing: break; + case Leveling: break; + case PrintProcess: HMI_Printing(); break; + case PrintDone: HMI_PrintDone(); break; + case PauseOrStop: HMI_PauseOrStop(); break; + case Info: HMI_Popup(); break; + case WaitResponse: HMI_Popup(); break; + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case FilamentPurge: HMI_FilamentPurge(); break; + #endif + case NothingToDo: break; + case Locked: HMI_LockScreen(); break; + default: break; + } +} + +void HMI_SaveProcessID(const uint8_t id) { + if (checkkey != id) { + if ((checkkey != NothingToDo) && + (checkkey != WaitResponse) && + (checkkey != Homing) && + (checkkey != Leveling) && + (checkkey != PauseOrStop) && + (checkkey != FilamentPurge)) last_checkkey = checkkey; // if not a popup + checkkey = id; + } +} + +void DWIN_StartHoming() { + HMI_flag.home_flag = true; + HMI_SaveProcessID(Homing); + DWIN_Draw_Popup(ICON_BLTouch, "Axis Homing", "Please wait until done."); +} + +void DWIN_CompletedHoming() { + HMI_flag.home_flag = false; + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + if (dwin_abort_flag) { + planner.finish_and_disable(); + } + HMI_ReturnScreen(); +} + +void DWIN_MeshLevelingStart() { + #if HAS_ONESTEP_LEVELING + HMI_SaveProcessID(Leveling); + DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT(MSG_BED_LEVELING), "Please wait until done."); + #elif ENABLED(MESH_BED_LEVELING) + Draw_ManualMesh_Menu(); + #endif +} + +void DWIN_CompletedLeveling() { HMI_ReturnScreen(); } + +#if ENABLED(MESH_BED_LEVELING) + void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + char msg[33] = ""; + char str_1[6] = ""; + sprintf_P(msg, PSTR(S_FMT " %i/%i Z=%s"), GET_TEXT(MSG_PROBING_MESH), xpos, ypos, + dtostrf(zval, 1, 2, str_1)); + ui.set_status(msg); + } +#endif + +// PID process +void DWIN_PidTuning(pidresult_t result) { + switch (result) { + case PID_BED_START: + HMI_SaveProcessID(NothingToDo); + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT(MSG_PID_AUTOTUNE), "for BED is running."); + break; + case PID_EXTR_START: + HMI_SaveProcessID(NothingToDo); + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT(MSG_PID_AUTOTUNE), "for Nozzle is running."); + break; + case PID_BAD_EXTRUDER_NUM: + checkkey = last_checkkey; + DWIN_Popup_Confirm(ICON_TempTooLow, "PID Autotune failed!", "Bad extruder"); + break; + case PID_TUNING_TIMEOUT: + checkkey = last_checkkey; + DWIN_Popup_Confirm(ICON_TempTooHigh, "Error", GET_TEXT(MSG_PID_TIMEOUT)); + break; + case PID_TEMP_TOO_HIGH: + checkkey = last_checkkey; + DWIN_Popup_Confirm(ICON_TempTooHigh, "PID Autotune failed!", "Temperature too high"); + break; + case PID_DONE: + checkkey = last_checkkey; + DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT(MSG_PID_AUTOTUNE), GET_TEXT(MSG_BUTTON_DONE)); + break; + default: + checkkey = last_checkkey; + break; + } +} + +// Update filename on print +void DWIN_Print_Header(const char *text = nullptr) { + + static char headertxt[31] = ""; // Print header text + + if (text != nullptr) { + const int8_t size = _MIN((unsigned) 30, strlen_P(text)); + LOOP_L_N(i, size) headertxt[i] = text[i]; + headertxt[size] = '\0'; + } + if (checkkey == PrintProcess || checkkey == PrintDone) { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 60, DWIN_WIDTH, 60+16); + DWINUI::Draw_CenteredString(60, headertxt); + } +} + +void Draw_Title(TitleClass* title) { + DWIN_Draw_Rectangle(1, HMI_data.TitleBg_color, 0, 0, DWIN_WIDTH - 1, TITLE_HEIGHT - 1); + if (title->frameid) + DWIN_Frame_AreaCopy(title->frameid, title->frame.left, title->frame.top, title->frame.right, title->frame.bottom, 14, (TITLE_HEIGHT - (title->frame.bottom - title->frame.top)) / 2 - 1); + else + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, HMI_data.TitleTxt_color, HMI_data.TitleBg_color, 14, (TITLE_HEIGHT - DWINUI::Get_font_height(DWIN_FONT_HEAD)) / 2 - 1, title->caption); +} + +void Draw_Menu(MenuClass* menu) { + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + DWIN_Draw_Rectangle(1, DWINUI::backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); + ui.set_status(""); +} + +// Startup routines +void DWIN_Startup() { + DWINUI::Init(); + DWINUI::onCursorDraw = Draw_Menu_Cursor; + DWINUI::onCursorErase = Erase_Menu_Cursor; + DWINUI::onTitleDraw = Draw_Title; + DWINUI::onMenuDraw = Draw_Menu; + HMI_SetLanguage(); +} + +void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text) { + DWIN_Draw_Rectangle(1, bgcolor, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + if (text) DWINUI::Draw_CenteredString(color, STATUS_Y + 2, text); + DWIN_UpdateLCD(); +} + +// Update Status line +void DWIN_StatusChanged(const char *text) { + DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, text); +} + +void DWIN_StatusChanged_P(PGM_P const pstr) { + char str[strlen_P((const char*)pstr) + 1]; + strcpy_P(str, (const char*)pstr); + DWIN_StatusChanged(str); +} + +// Started a Print Job +void DWIN_Print_Started(const bool sd) { + sdprint = card.isPrinting() || sd; + _percent_done = 0; + _remain_time = 0; + Goto_PrintProcess(); +} + +// Ended print job +void DWIN_Print_Finished() { + if (checkkey == PrintProcess || printingIsActive()) { + thermalManager.disable_all_heaters(); + thermalManager.zero_fan_speeds(); + HMI_flag.print_finish = true; + } +} + +// Progress Bar update +void DWIN_Progress_Update() { + if (parser.seenval('P')) _percent_done = parser.byteval('P'); + if (parser.seenval('R')) _remain_time = parser.ulongval('R') * 60; + if (checkkey == PrintProcess) { + Draw_Print_ProgressBar(); + Draw_Print_ProgressRemain(); + Draw_Print_ProgressElapsed(); + } +} + +#if HAS_FILAMENT_SENSOR + // Filament Runout process + void DWIN_FilamentRunout(const uint8_t extruder) { ui.set_status_P(GET_TEXT(MSG_RUNOUT_SENSOR)); } +#endif + +void DWIN_SetColorDefaults() { + HMI_data.Background_Color = Def_Background_Color; + HMI_data.Cursor_color = Def_Cursor_color; + HMI_data.TitleBg_color = Def_TitleBg_color; + HMI_data.TitleTxt_color = Def_TitleTxt_color; + HMI_data.Text_Color = Def_Text_Color; + HMI_data.Selected_Color = Def_Selected_Color; + HMI_data.SplitLine_Color = Def_SplitLine_Color; + HMI_data.Highlight_Color = Def_Highlight_Color; + HMI_data.StatusBg_Color = Def_StatusBg_Color; + HMI_data.StatusTxt_Color = Def_StatusTxt_Color; + HMI_data.PopupBg_color = Def_PopupBg_color; + HMI_data.PopupTxt_Color = Def_PopupTxt_Color; + HMI_data.AlertBg_Color = Def_AlertBg_Color; + HMI_data.AlertTxt_Color = Def_AlertTxt_Color; + HMI_data.PercentTxt_Color = Def_PercentTxt_Color; + HMI_data.Barfill_Color = Def_Barfill_Color; + HMI_data.Indicator_Color = Def_Indicator_Color; + HMI_data.Coordinate_Color = Def_Coordinate_Color; +} + +void DWIN_SetDataDefaults() { + DWIN_SetColorDefaults(); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); + TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); + TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); +} + +void DWIN_StoreSettings(char *buff) { + memcpy(buff, &HMI_data, min(sizeof(HMI_data), eeprom_data_size)); +} + +void DWIN_LoadSettings(const char *buff) { + memcpy(&HMI_data, buff, min(sizeof(HMI_data), eeprom_data_size)); + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + if (HMI_data.Text_Color == HMI_data.Background_Color) DWIN_SetColorDefaults(); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); +} + +void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { + DWIN_Draw_Popup(ICON_BLTouch, lcd_error, lcd_component); + DWIN_UpdateLCD(); +} + +void DWIN_RebootScreen() { + DWIN_Frame_Clear(Color_Bg_Black); + DWINUI::Draw_Icon(ICON_LOGO, 71, 150); // CREALITY logo + DWINUI::Draw_CenteredString(Color_White, 200, F("Please wait until reboot.")); + DWIN_UpdateLCD(); + delay(500); +} + +void DWIN_Redraw_screen() { + Draw_Main_Area(); + DWIN_StatusChanged(ui.status_message); + Draw_Status_Area(false); +} + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + + void DWIN_Popup_Pause(const char *msg, uint8_t button = 0) { + HMI_SaveProcessID(button ? WaitResponse : NothingToDo); + DWIN_Draw_Popup(ICON_BLTouch, "Advanced Pause", msg, button); + ui.reset_status(true); + } + + void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { + switch (message) { + case PAUSE_MESSAGE_PARKING: DWIN_Popup_Pause(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); break; + case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); break; + case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); break; + case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING), ICON_Continue_E); break; + case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, "Advanced Pause", GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); break; + case PAUSE_MESSAGE_LOAD: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); break; + case PAUSE_MESSAGE_PURGE: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); break; + case PAUSE_MESSAGE_OPTION: DWIN_Popup_FilamentPurge(); break; + case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); break; + case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT), ICON_Continue_E); break; + case PAUSE_MESSAGE_HEATING: ui.set_status_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); break; + case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; + default: break; + } + } + + void Draw_Popup_FilamentPurge() { + DWIN_Draw_Popup(ICON_BLTouch, "Advanced Pause", "Purge or Continue?"); + DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); + DWINUI::Draw_Icon(ICON_Continue_E, 146, 280); + Draw_Select_Highlight(true); + } + + // Handle responses such as: + // - Purge More, Continue + // - General "Continue" response + void DWIN_Popup_FilamentPurge() { + HMI_SaveProcessID(FilamentPurge); + pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; + Draw_Popup_FilamentPurge(); + } + + void HMI_FilamentPurge() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW) + Draw_Select_Highlight(false); + else if (encoder_diffState == ENCODER_DIFF_CCW) + Draw_Select_Highlight(true); + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (HMI_flag.select_flag) + pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // "Purge More" button + else { + HMI_SaveProcessID(NothingToDo); + pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // "Continue" button + } + } + DWIN_UpdateLCD(); + } + +#endif // ADVANCED_PAUSE_FEATURE + +void HMI_LockScreen() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + LockScreen.onEncoderState(encoder_diffState); + if (LockScreen.isUnlocked()) { + if (CurrentMenu == AdvancedSettings) + Draw_AdvancedSettings_Menu(); + else + Draw_Tune_Menu(); + } +} + +void DWIN_LockScreen(const bool flag) { + HMI_flag.lock_flag = flag; + checkkey = Locked; + LockScreen.Init(); +} + +// +// NEW MENU SUBSYSTEM ========================================================= +// + +// On click functions + +// Generic onclick event without draw anything +// process: process id HMI destiny +// lo: low limit +// hi: high limit +// dp: decimal places, 0 for integers +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + last_checkkey = checkkey; + checkkey = process; + HMI_value.MinValue = lo; + HMI_value.MaxValue = hi; + HMI_value.dp = dp; + HMI_value.Apply = Apply; + HMI_value.LiveUpdate = LiveUpdate; + HMI_value.Value = val; + EncoderRate.enabled = true; +} + +// Generic onclick event for set values (dp = 0: integer, dp > 0: float) +// process: process id HMI destiny +// lo: scaled low limit +// hi: scaled high limit +// dp: decimal places, 0 for integers +// val: scaled value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetOnClick(process, lo, hi, dp, val, Apply, LiveUpdate); + dp ? DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value) + : Draw_Menu_IntValue(HMI_data.Selected_Color, CurrentMenu->line(), 4, HMI_value.Value); +} + +// Generic onclick event for integer values +// lo: scaled low limit +// hi: scaled high limit +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetValueOnClick(SetInt, lo, hi, 0, val, Apply, LiveUpdate); +} + +// Generic onclick event for set pointer to 16 bit uinteger values +// lo: low limit +// hi: high limit +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; + const int32_t value = *HMI_value.P_Int; + SetValueOnClick(SetPInt, lo, hi, 0, value, Apply, LiveUpdate); +} + +// Generic onclick event for float values +// process: process id HMI destiny +// lo: low limit +// hi: high limit +// dp: decimal places +// val: value +void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetValueOnClick(SetFloat, lo * POW(10, dp), hi * POW(10, dp), dp, val * POW(10, dp), Apply, LiveUpdate); +} + +// Generic onclick event for set pointer to float values +// lo: low limit +// hi: high limit +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + const int32_t value = *HMI_value.P_Float * POW(10, dp); + SetValueOnClick(SetPFloat, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); +} + +#if ENABLED(EEPROM_SETTINGS) + void WriteEeprom() { + const bool success = settings.save(); + HMI_AudioFeedback(success); + } + + void ReadEeprom() { + const bool success = settings.load(); + DWIN_Redraw_screen(); + HMI_AudioFeedback(success); + } + + void ResetEeprom() { + settings.reset(); + DWIN_Redraw_screen(); + HMI_AudioFeedback(); + } +#endif + +// Reset Printer +void RebootPrinter() { + dwin_abort_flag = true; + wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user + thermalManager.disable_all_heaters(); + planner.finish_and_disable(); + DWIN_RebootScreen(); + HAL_reboot(); +} + +void Goto_InfoMenu(){ + checkkey = Info; + Draw_Info_Menu(); +} + +void DisableMotors() { + queue.inject_P(PSTR("M84")); +} + +void AutoHome() { + queue.inject_P(G28_STR); +} + +void SetHome() { + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); +} + +#if HAS_ZOFFSET_ITEM + bool printer_busy() { return planner.movesplanned() || printingIsActive(); } + void ApplyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } + void LiveZOffset() { + last_zoffset = dwin_zoffset; + dwin_zoffset = HMI_value.Value / 100.0f; + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + #endif + } + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + void SetZOffset() { SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); } + #endif +#endif + +#if HAS_PREHEAT + void SetPreheat(const uint8_t i) { + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[i].hotend_temp, 0)); + TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[i].bed_temp)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[i].fan_speed)); + } + void SetPreheat0() { SetPreheat(0); } + void SetPreheat1() { SetPreheat(1); } + void SetPreheat2() { SetPreheat(2); } + + void SetCoolDown() { + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + #if HAS_HOTEND || HAS_HEATED_BED + thermalManager.disable_all_heaters(); + #endif + } +#endif + +void SetLanguage() { + HMI_ToggleLanguage(); + CurrentMenu = nullptr; // Invalidate menu to full redraw + Draw_Prepare_Menu(); +} + +void LiveMove() { + *HMI_value.P_Float = HMI_value.Value / MINUNITMULT; + if (!planner.is_full()) { + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(HMI_value.axis)); + } +} +void ApplyMoveE() { + last_E = HMI_value.Value / MINUNITMULT; + if (!planner.is_full()) { + planner.synchronize(); + planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E)); + } +} +void SetMoveX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(X_MIN_POS, X_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} +void SetMoveY() { HMI_value.axis = Y_AXIS; SetPFloatOnClick(Y_MIN_POS, Y_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} +void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS, UNITFDIGITS, planner.synchronize, LiveMove);} + +#if HAS_HOTEND + void SetMoveE() { + #ifdef PREVENT_COLD_EXTRUSION + if (thermalManager.tooColdToExtrude(0)) { + Popup_Window_ETempTooLow(); + return; + } + #endif + SetPFloatOnClick(last_E - (EXTRUDE_MAXLENGTH), last_E + (EXTRUDE_MAXLENGTH), UNITFDIGITS, ApplyMoveE); + } +#endif + +void SetMoveZto0() { + char cmd[48] = ""; + char str_1[5] = "", str_2[5] = ""; + sprintf_P(cmd, PSTR("G28OXY\nG28Z\nG0X%sY%sF5000\nG0Z0F300"), + dtostrf(X_CENTER, 1, 1, str_1), + dtostrf(Y_CENTER, 1, 1, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + ui.set_status_P(PSTR("Now adjust Z Offset")); + HMI_AudioFeedback(true); +} + +void SetPID(celsius_t t, heater_id_t h) { + char cmd[48] = ""; + char str_1[5] = "", str_2[5] = ""; + sprintf_P(cmd, PSTR("G28OXY\nG0Z5F300\nG0X%sY%sF5000\nM84"), + dtostrf(X_CENTER, 1, 1, str_1), + dtostrf(Y_CENTER, 1, 1, str_2)); + gcode.process_subcommands_now_P(cmd); + planner.synchronize(); + thermalManager.PID_autotune(t, h, HMI_data.PidCycles, true); +} +TERN_(HAS_HOTEND, void HotendPID() { SetPID(HMI_data.HotendPidT, H_E0); }) +TERN_(HAS_HEATED_BED, void BedPID() { SetPID(HMI_data.BedPidT, H_BED); }) + +void SetPwrLossr() { + recovery.enable(!recovery.enabled); + Draw_Chkb_Line(CurrentMenu->line(), recovery.enabled); + DWIN_UpdateLCD(); +} + +#if HAS_LCD_BRIGHTNESS + void ApplyBrightness() { ui.set_brightness(HMI_value.Value); } + void LiveBrightness() { DWIN_LCD_Brightness(HMI_value.Value); } + void SetBrightness() { SetIntOnClick(MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, ui.brightness, ApplyBrightness, LiveBrightness); } +#endif + +#if ENABLED(SOUND_MENU_ITEM) + void SetEnableSound() { + ui.buzzer_enabled = !ui.buzzer_enabled; + Draw_Chkb_Line(CurrentMenu->line(), ui.buzzer_enabled); + DWIN_UpdateLCD(); + } +#endif + +void Goto_LockScreen() { + DWIN_LockScreen(true); +} + +#if HAS_HOME_OFFSET + void ApplyHomeOffset() { set_home_offset(HMI_value.axis, HMI_value.Value / MINUNITMULT); } + void SetHomeOffsetX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(-50, 50, UNITFDIGITS, ApplyHomeOffset); } + void SetHomeOffsetY() { HMI_value.axis = Y_AXIS; SetPFloatOnClick(-50, 50, UNITFDIGITS, ApplyHomeOffset); } + void SetHomeOffsetZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick( -2, 2, UNITFDIGITS, ApplyHomeOffset); } +#endif + +#if HAS_BED_PROBE + void SetProbeOffsetX() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } + void SetProbeOffsetY() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } + void ProbeTest() { + ui.set_status_P(GET_TEXT(MSG_M48_TEST)); + queue.inject_P(PSTR("G28O\nM48 P10")); + } +#endif + +#if HAS_FILAMENT_SENSOR + void SetRunoutEnable() { + runout.reset(); + runout.enabled = !runout.enabled; + Draw_Chkb_Line(CurrentMenu->line(), runout.enabled); + DWIN_UpdateLCD(); + } + #if HAS_FILAMENT_RUNOUT_DISTANCE + void ApplyRunoutDistance() { runout.set_runout_distance(HMI_value.Value / MINUNITMULT); } + void SetRunoutDistance() { SetFloatOnClick(0, 999, UNITFDIGITS, runout.runout_distance(), ApplyRunoutDistance); } + #endif +#endif + +TERN_(ADVANCED_PAUSE_FEATURE, void SetFilLoad() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); }); +TERN_(ADVANCED_PAUSE_FEATURE, void SetFilUnload() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); }); + +TERN_(PREVENT_COLD_EXTRUSION, void ApplyExtMinT() { thermalManager.extrude_min_temp = HMI_data.ExtMinT; thermalManager.allow_cold_extrude = (HMI_data.ExtMinT == 0); }); +TERN_(PREVENT_COLD_EXTRUSION, void SetExtMinT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP, ApplyExtMinT); }); + +void RestoreDefaultsColors() { + DWIN_SetColorDefaults(); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + DWIN_Redraw_screen(); +} + +void SelColor() { + HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; + HMI_value.Color[2] = GetRColor(*HMI_value.P_Int); // Red + HMI_value.Color[1] = GetGColor(*HMI_value.P_Int); // Green + HMI_value.Color[0] = GetBColor(*HMI_value.P_Int); // Blue + Draw_GetColor_Menu(); +} + +void LiveRGBColor() { + HMI_value.Color[CurrentMenu->line() - 2] = HMI_value.Value; + uint16_t color = RGB(HMI_value.Color[2], HMI_value.Color[1], HMI_value.Color[0]); + DWIN_Draw_Rectangle(1, color, 20, 315, DWIN_WIDTH - 20, 335); +} +void SetRGBColor() { + const uint8_t line = CurrentMenu->line() - 2; + SetIntOnClick(0, (line == 1) ? 63 : 31, HMI_value.Color[CurrentMenu->SelectedItem()->icon], nullptr, LiveRGBColor); +} + +void DWIN_ApplyColor() { + *HMI_value.P_Int = RGB(HMI_value.Color[2], HMI_value.Color[1], HMI_value.Color[0]); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + Draw_Status_Area(false); + Draw_SelectColors_Menu(); + ui.set_status_P(PSTR("Colors applied")); +} + +void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } + +#if HAS_HOTEND + void ApplyHotendTemp() { thermalManager.setTargetHotend(HMI_value.Value, 0); } + void SetHotendTemp() { SetIntOnClick(HEATER_0_MINTEMP, HEATER_0_MAXTEMP, thermalManager.degTargetHotend(0), ApplyHotendTemp); } +#endif + +#if HAS_HEATED_BED + void ApplyBedTemp() { thermalManager.setTargetBed(HMI_value.Value); } + void SetBedTemp() { SetIntOnClick(BED_MINTEMP, BED_MAX_TARGET, thermalManager.degTargetBed(), ApplyBedTemp); } +#endif + +#if HAS_FAN + void ApplyFanSpeed() { thermalManager.set_fan_speed(0, HMI_value.Value); } + void SetFanSpeed() { SetIntOnClick(0, 255, thermalManager.fan_speed[0], ApplyFanSpeed); } +#endif + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void ChangeFilament() { + HMI_SaveProcessID(NothingToDo); + queue.inject_P(PSTR("M600 B2")); + } + + void ParkHead(){ + ui.set_status_P(GET_TEXT(MSG_FILAMENT_PARK_ENABLED)); + queue.inject_P(PSTR("G28O\nG27")); + } + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + void UnloadFilament(){ + ui.set_status_P(GET_TEXT(MSG_FILAMENTUNLOAD)); + queue.inject_P(PSTR("M702 Z20")); + } + + void LoadFilament(){ + ui.set_status_P(GET_TEXT(MSG_FILAMENTLOAD)); + queue.inject_P(PSTR("M701 Z20")); + } + #endif +#endif + +void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW); } + +// Leveling Bed Corners +void LevBed(uint8_t point) { + char cmd[100] = ""; + #if HAS_ONESTEP_LEVELING + char str_1[6] = "", str_2[6] = "", str_3[6] = ""; + #define fmt "X:%s, Y:%s, Z:%s" + float xpos = 0, ypos = 0, zval = 0; + float margin = PROBING_MARGIN; + #else + #define fmt "M420 S0\nG28O\nG90\nG0 Z5 F300\nG0 X%i Y%i F5000\nG0 Z0 F300" + int16_t xpos = 0, ypos = 0; + int16_t margin = 30; + #endif + + switch (point) { + case 0: + ui.set_status_P(GET_TEXT(MSG_LEVBED_FL)); + xpos = ypos = margin; + break; + case 1: + ui.set_status_P(GET_TEXT(MSG_LEVBED_FR)); + xpos = X_BED_SIZE - margin; ypos = margin; + break; + case 2: + ui.set_status_P(GET_TEXT(MSG_LEVBED_BR)); + xpos = X_BED_SIZE - margin; ypos = Y_BED_SIZE - margin; + break; + case 3: + ui.set_status_P(GET_TEXT(MSG_LEVBED_BL)); + xpos = margin; ypos = Y_BED_SIZE - margin; + break; + case 4: + ui.set_status_P(GET_TEXT(MSG_LEVBED_C)); + xpos = X_BED_SIZE / 2; ypos = Y_BED_SIZE / 2; + break; + } + + #if HAS_ONESTEP_LEVELING + planner.synchronize(); + gcode.process_subcommands_now_P(PSTR("M420S0\nG28O")); + planner.synchronize(); + zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); + sprintf_P(cmd, PSTR(fmt), + dtostrf(xpos, 1, 1, str_1), + dtostrf(ypos, 1, 1, str_2), + dtostrf(zval, 1, 2, str_3) + ); + ui.set_status_P(cmd); + #else + planner.synchronize(); + sprintf_P(cmd, PSTR(fmt), xpos, ypos); + queue.inject(cmd); + #endif +} + +void LevBedFL() { LevBed(0); } +void LevBedFR() { LevBed(1); } +void LevBedBR() { LevBed(2); } +void LevBedBL() { LevBed(3); } +void LevBedC () { LevBed(4); } + +#if ENABLED(MESH_BED_LEVELING) + void ManualMeshStart(){ + ui.set_status_P(GET_TEXT(MSG_UBL_BUILD_MESH_MENU)); + gcode.process_subcommands_now_P(PSTR("G28 XYO\nG28 Z\nM211 S0\nG29S1")); + planner.synchronize(); + #ifdef MANUAL_PROBE_START_Z + MMeshMoveZItem->Draw(CurrentMenu->line(MMeshMoveZItem->pos)); + #endif + } + + void SetMMeshMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMove);} + + void ManualMeshContinue(){ + gcode.process_subcommands_now_P(PSTR("G29S2")); + planner.synchronize(); + MMeshMoveZItem->Draw(CurrentMenu->line(MMeshMoveZItem->pos)); + } + + void ManualMeshSave(){ + ui.set_status_P(GET_TEXT(MSG_UBL_STORAGE_MESH_MENU)); + queue.inject_P(PSTR("M211 S1\nM500")); + } +#endif + +#if HAS_PREHEAT + TERN_(HAS_HOTEND, void SetPreheatEndTemp() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); }); + TERN_(HAS_HEATED_BED, void SetPreheatBedTemp() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); }); + TERN_(HAS_FAN, void SetPreheatFanSpeed() { SetPIntOnClick(0, 255); }); +#endif + +void ApplyMaxSpeed() { planner.set_max_feedrate(HMI_value.axis, HMI_value.Value / MINUNITMULT); } +void SetMaxSpeedX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[X_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[X_AXIS], ApplyMaxSpeed); } +void SetMaxSpeedY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Y_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Y_AXIS], ApplyMaxSpeed); } +void SetMaxSpeedZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Z_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Z_AXIS], ApplyMaxSpeed); } +TERN_(HAS_HOTEND, void SetMaxSpeedE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[E_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[E_AXIS], ApplyMaxSpeed); }); + +void ApplyMaxAccel() { planner.set_max_acceleration(HMI_value.axis, HMI_value.Value); } +void SetMaxAccelX() { HMI_value.axis = X_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[X_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[X_AXIS], ApplyMaxAccel); } +void SetMaxAccelY() { HMI_value.axis = Y_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Y_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ApplyMaxAccel); } +void SetMaxAccelZ() { HMI_value.axis = Z_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Z_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ApplyMaxAccel); } +TERN_(HAS_HOTEND, void SetMaxAccelE() { HMI_value.axis = E_AXIS; SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[E_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[E_AXIS], ApplyMaxAccel); }); + +#if HAS_CLASSIC_JERK + void ApplyMaxJerk() { planner.set_max_jerk(HMI_value.axis, HMI_value.Value / MINUNITMULT); } + void SetMaxJerkX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[X_AXIS] * 2, UNITFDIGITS, planner.max_jerk[X_AXIS], ApplyMaxJerk); } + void SetMaxJerkY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Y_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Y_AXIS], ApplyMaxJerk); } + void SetMaxJerkZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Z_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Z_AXIS], ApplyMaxJerk); } + TERN_(HAS_HOTEND, void SetMaxJerkE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXJERK, default_max_jerk[E_AXIS] * 2, UNITFDIGITS, planner.max_jerk[E_AXIS], ApplyMaxJerk); }); +#endif + +void SetStepsX() { HMI_value.axis = X_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } +void SetStepsY() { HMI_value.axis = Y_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } +void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } +TERN_(HAS_HOTEND, void SetStepsE() { HMI_value.axis = E_AXIS; SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); }); + +TERN_(HAS_HOTEND, void SetHotendPidT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); }) +TERN_(HAS_HEATED_BED, void SetBedPidT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); }) + +#if HAS_HOTEND || HAS_HEATED_BED + void SetPidCycles() { SetPIntOnClick(3, 50); } + void SetKp() { SetPFloatOnClick(0, 1000, 2); } + void ApplyPIDi() { + *HMI_value.P_Float = scalePID_i(HMI_value.Value / POW(10, 2)); + thermalManager.updatePID(); + } + void ApplyPIDd() { + *HMI_value.P_Float = scalePID_d(HMI_value.Value / POW(10, 2)); + thermalManager.updatePID(); + } + void SetKi() { + HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + const float value = unscalePID_i(*HMI_value.P_Float); + SetFloatOnClick(0, 1000, 2, value, ApplyPIDi); + } + void SetKd() { + HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + const float value = unscalePID_d(*HMI_value.P_Float); + SetFloatOnClick(0, 1000, 2, value, ApplyPIDd); + } +#endif +// Menuitem Drawing functions ================================================= + +void onDrawMenuItem(MenuItemClass* menuitem, int8_t line) { + if (menuitem->icon) DWINUI::Draw_Icon(menuitem->icon, ICOX, MBASE(line) - 3); + if (menuitem->frameid) + DWIN_Frame_AreaCopy(menuitem->frameid, menuitem->frame.left, menuitem->frame.top, menuitem->frame.right, menuitem->frame.bottom, LBLX, MBASE(line)); + else if (menuitem->caption) + DWINUI::Draw_String(LBLX, MBASE(line) - 1, menuitem->caption); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); +} + +void onDrawSubMenu(MenuItemClass* menuitem, int8_t line) { + onDrawMenuItem(menuitem, line); + DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); +} + +void onDrawIntMenu(MenuItemClass* menuitem, int8_t line, uint16_t value) { + onDrawMenuItem(menuitem, line); + Draw_Menu_IntValue(HMI_data.Background_Color, line, 4, value); +} + +void onDrawPIntMenu(MenuItemClass* menuitem, int8_t line) { + const uint16_t value = *(uint16_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawPInt8Menu(MenuItemClass* menuitem, int8_t line) { + const uint8_t value = *(uint8_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line) { + const uint32_t value = *(uint32_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value) { + onDrawMenuItem(menuitem, line); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), value * POW(10, dp)); +} + +void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { + const float value = *(float*)static_cast(menuitem)->value; + const int8_t dp = UNITFDIGITS; + onDrawFloatMenu(menuitem, line, dp, value); +} + +void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line) { + const float value = *(float*)static_cast(menuitem)->value; + const int8_t dp = 2; + onDrawFloatMenu(menuitem, line, dp, value); +} + +void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked) { + onDrawMenuItem(menuitem, line); + Draw_Chkb_Line(line, checked); +} + +void onDrawBack(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 129, 72, 156, 84); + onDrawMenuItem(menuitem, line); +} + +void onDrawTempSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 57, 104, 84, 116); + onDrawSubMenu(menuitem, line); +} + +void onDrawMotionSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 87, 104, 114, 116); + onDrawSubMenu(menuitem, line); +} + +#if ENABLED(EEPROM_SETTINGS) + void onDrawWriteEeprom(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 117, 104, 172, 116); + onDrawMenuItem(menuitem, line); + } + + void onDrawReadEeprom(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 174, 103, 229, 116); + onDrawMenuItem(menuitem, line); + } + + void onDrawResetEeprom(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 118, 56, 131); + onDrawMenuItem(menuitem, line); + } +#endif + +void onDrawInfoSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 231, 104, 258, 116); + onDrawSubMenu(menuitem, line); +} + +void onDrawMoveX(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 58, 118, 106, 132); + onDrawPFloatMenu(menuitem, line); +} + +void onDrawMoveY(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 109, 118, 157, 132); + onDrawPFloatMenu(menuitem, line); +} + +void onDrawMoveZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 160, 118, 209, 132); + onDrawPFloatMenu(menuitem, line); +} + +#if HAS_HOTEND + void onDrawMoveE(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 212, 118, 253, 131); + onDrawPFloatMenu(menuitem, line); + } +#endif + +void onDrawMoveSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 159, 70, 200, 84); + onDrawSubMenu(menuitem, line); +} + +void onDrawDisableMotors(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 204, 70, 259, 82); + onDrawMenuItem(menuitem, line); +} + +void onDrawAutoHome(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 0, 89, 41, 101); + onDrawMenuItem(menuitem, line); +} + +#if HAS_ZOFFSET_ITEM + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + void onDrawZOffset(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 174, 164, 223, 177); + onDrawPFloat2Menu(menuitem, line); + } + #else + void onDrawHomeOffset(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 43, 89, 98, 101); + onDrawMenuItem(menuitem, line); + } + #endif +#endif + +#if HAS_HOTEND + void onDrawPreheat1(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 100, 89, 151, 101); + onDrawMenuItem(menuitem, line); + } + void onDrawPreheat2(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 233, 100); + onDrawMenuItem(menuitem, line); + } +#endif + +#if HAS_PREHEAT + void onDrawCooldown(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 104, 56, 117); + onDrawMenuItem(menuitem, line); + } +#endif + +void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 239, 134, 266, 146); + onDrawMenuItem(menuitem, line); + DWINUI::Draw_String(VALX, MBASE(line), HMI_IsChinese() ? F("CN") : F("EN")); +} + +void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } + +void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } + +void onDrawSelColorItem(MenuItemClass* menuitem, int8_t line) { + const uint16_t color = *(uint16_t*)static_cast(menuitem)->value; + DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); + DWIN_Draw_Rectangle(1, color, ICOX + 2, MBASE(line) - 1 + 2, ICOX + 17, MBASE(line) - 1 + 17); + onDrawMenuItem(menuitem, line); +} + +void onDrawGetColorItem(MenuItemClass* menuitem, int8_t line) { + const uint8_t i = menuitem->icon; + uint16_t color; + switch (i) { + case 0: color = RGB(0, 0, 31); break; + case 1: color = RGB(0, 63, 0); break; + case 2: color = RGB(31, 0, 0); break; + default: color = 0; break; + } + DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); + DWIN_Draw_Rectangle(1, color, ICOX + 2, MBASE(line) - 1 + 2, ICOX + 17, MBASE(line) - 1 + 17); + DWINUI::Draw_String(LBLX, MBASE(line) - 1, menuitem->caption); + Draw_Menu_IntValue(HMI_data.Background_Color, line, 4, HMI_value.Color[i]); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); +} + +#if HAS_FILAMENT_SENSOR + void onDrawRunoutEnable(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, runout.enabled); } +#endif + +void onDrawPIDi(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_i(*(float*)static_cast(menuitem)->value)); } +void onDrawPIDd(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_d(*(float*)static_cast(menuitem)->value)); } + + +void onDrawSpeedItem(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 116, 164, 171, 176); + onDrawPIntMenu(menuitem, line); +} + +#if HAS_HOTEND + void onDrawHotendTemp(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 134, 56, 146); + onDrawPIntMenu(menuitem, line); + } +#endif + +#if HAS_HEATED_BED + void onDrawBedTemp(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 58, 134, 113, 146); + onDrawPIntMenu(menuitem, line); + } +#endif + +#if HAS_FAN + void onDrawFanSpeed(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 115, 134, 170, 146); + onDrawPInt8Menu(menuitem, line); + } +#endif + +void onDrawSpeed(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 173, 133, 228, 147); + onDrawSubMenu(menuitem, line); +} + +void onDrawAcc(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line) + 1); // ...Acceleration + } + onDrawSubMenu(menuitem, line); +} + +#if HAS_CLASSIC_JERK + void onDrawJerk(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line) + 1); // ... + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(line)); // ...Jerk + } + onDrawSubMenu(menuitem, line); + } +#endif + +void onDrawSteps(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 153, 148, 194, 161); + onDrawSubMenu(menuitem, line); +} + +#if ENABLED(MESH_BED_LEVELING) + void onDrawMMeshMoveZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 160, 118, 209, 132); + onDrawPFloatMenu(menuitem, line); + } +#endif + +#if HAS_PREHEAT + #if HAS_HOTEND + void onDrawSetPreheatHotend(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 134, 56, 146); + onDrawPIntMenu(menuitem, line); + } + #endif + #if HAS_HEATED_BED + void onDrawSetPreheatBed(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 58, 134, 113, 146); + onDrawPIntMenu(menuitem, line); + } + #endif + #if HAS_FAN + void onDrawSetPreheatFan(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 115, 134, 170, 146); + onDrawPIntMenu(menuitem, line); + } + #endif + void onDrawPLAPreheatSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 100, 89, 178, 101); + onDrawSubMenu(menuitem,line); + } + void onDrawABSPreheatSubMenu(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 260, 100); + onDrawSubMenu(menuitem,line); + } +#endif // HAS_HOTEND + +void onDrawMaxSpeedX(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 228, 147); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 58, MBASE(line)); // X + } + onDrawPFloatMenu(menuitem, line); +} + +void onDrawMaxSpeedY(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 228, 147); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 58, MBASE(line)); // Y + } + onDrawPFloatMenu(menuitem, line); +} + +void onDrawMaxSpeedZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 228, 147); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 58, MBASE(line) + 3); // Z + } + onDrawPFloatMenu(menuitem, line); +} + +#if HAS_HOTEND + void onDrawMaxSpeedE(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 228, 147); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(line)); // E + } + onDrawPFloatMenu(menuitem, line); + } +#endif + +void onDrawMaxAccelX(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(line)); // X + } + onDrawPInt32Menu(menuitem, line); +} + +void onDrawMaxAccelY(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(line)); // Y + } + onDrawPInt32Menu(menuitem, line); +} + +void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(line)); // Z + } + onDrawPInt32Menu(menuitem, line); +} + +#if HAS_HOTEND + void onDrawMaxAccelE(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(line)); // E + } + onDrawPInt32Menu(menuitem, line); + } +#endif + +#if HAS_CLASSIC_JERK + void onDrawMaxJerkX(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(line)); + } + onDrawPFloatMenu(menuitem, line); + } + + void onDrawMaxJerkY(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(line)); + } + onDrawPFloatMenu(menuitem, line); + } + + void onDrawMaxJerkZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(line)); + } + onDrawPFloatMenu(menuitem, line); + } + + #if HAS_HOTEND + void onDrawMaxJerkE(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(line)); + } + onDrawPFloatMenu(menuitem, line); + } + #endif +#endif // HAS_CLASSIC_JERK + +void onDrawStepsX(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 153, 148, 194, 161); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(line)); // X + } + onDrawPFloatMenu(menuitem, line); +} + +void onDrawStepsY(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 153, 148, 194, 161); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(line)); // Y + } + onDrawPFloatMenu(menuitem, line); +} + +void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 153, 148, 194, 161); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(line)); // Z + } + onDrawPFloatMenu(menuitem, line); +} + +#if HAS_HOTEND + void onDrawStepsE(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame (1, 153, 148, 194, 161); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(line)); // E + } + onDrawPFloatMenu(menuitem, line); + } +#endif + +// HMI Control functions ====================================================== + +// Generic menu control using the encoder +void HMI_Menu() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (CurrentMenu != nullptr) CurrentMenu->onClick(); + } else if (CurrentMenu != nullptr) CurrentMenu->onScroll(encoder_diffState == ENCODER_DIFF_CW); +} + +// Get an integer value using the encoder without draw anything +// lo: low limit +// hi: high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { + EncoderRate.enabled = false; + checkkey = last_checkkey; + return 2; + } + LIMIT(HMI_value.Value, lo, hi); + return 1; + } + return 0; +} + +// Get an integer value using the encoder +// lo: low limit +// hi: high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetInt(const int32_t lo, const int32_t hi) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { + EncoderRate.enabled = false; + DWINUI::Draw_Int(HMI_data.Text_Color, HMI_data.Background_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, HMI_value.Value); + checkkey = last_checkkey; + return 2; + } + LIMIT(HMI_value.Value, lo, hi); + DWINUI::Draw_Int(HMI_data.Text_Color, HMI_data.Selected_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, HMI_value.Value); + return 1; + } + return 0; +} + +// Set an integer using the encoder +void HMI_SetInt() { + int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); + switch (val) { + case 0: return; break; + case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + } +} + +// Set an integer without drawing +void HMI_SetIntNoDraw() { + int8_t val = HMI_GetIntNoDraw(HMI_value.MinValue, HMI_value.MaxValue); + switch (val) { + case 0: return; break; + case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + } +} + +// Set an integer pointer variable using the encoder +void HMI_SetPInt() { + int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); + if (!val) return; + else if (val == 2) { // Apply + *HMI_value.P_Int = HMI_value.Value; + if (HMI_value.Apply != nullptr) HMI_value.Apply(); + } else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); +} + +// Get an scaled float value using the encoder +// dp: decimal places +// lo: scaled low limit +// hi: scaled high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { + EncoderRate.enabled = false; + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value); + checkkey = last_checkkey; + return 2; + } + LIMIT(HMI_value.Value, lo, hi); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value); + return 1; + } + return 0; +} + +// Set an scaled float using the encoder +void HMI_SetFloat() { + int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); + switch (val) { + case 0: return; break; + case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + } +} + +// Set an scaled float pointer variable using the encoder +void HMI_SetPFloat() { + int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); + if (!val) return; + else if (val == 2) { // Apply + *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); + if (HMI_value.Apply != nullptr) HMI_value.Apply(); + } else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); +} + +// Menu Creation and Drawing functions ====================================================== + +void SetMenuTitle(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { + if (HMI_IsChinese() && (cn.w != 0)) + CurrentMenu->MenuTitle.SetFrame(cn.x, cn.y, cn.w, cn.h); + else { + #ifdef USE_STRING_HEADINGS + CurrentMenu->MenuTitle.SetCaption(text); + #else + if (en.w != 0) CurrentMenu->MenuTitle.SetFrame(en.x, en.y, en.w, en.h); + #endif + } +} + +void Draw_Prepare_Menu() { + checkkey = Menu; + if (PrepareMenu == nullptr) PrepareMenu = new MenuClass(); + if (CurrentMenu != PrepareMenu) { + CurrentMenu = PrepareMenu; + SetMenuTitle({133, 1, 28, 13}, {179, 0, 48, 14}, GET_TEXT_F(MSG_PREPARE)); + DWINUI::MenuItemsPrepare(13); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu)); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_MOVE_AXIS), onDrawMoveSubMenu, Draw_Move_Menu); + ADDMENUITEM(ICON_LevBed, GET_TEXT(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); + ADDMENUITEM(ICON_CloseMotor, GET_TEXT(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); + ADDMENUITEM(ICON_Homing, GET_TEXT(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + TERN_(MESH_BED_LEVELING, ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu)); + #if HAS_ZOFFSET_ITEM + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + ADDMENUITEM(ICON_SetZOffset, GET_TEXT(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); + #else + ADDMENUITEM(ICON_SetHome, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); + #endif + #endif + #if HAS_HOTEND + ADDMENUITEM(ICON_PLAPreheat, GET_TEXT(MSG_PREHEAT_1), onDrawPreheat1, SetPreheat0); + ADDMENUITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, SetPreheat1); + ADDMENUITEM(ICON_CustomPreheat, GET_TEXT(MSG_PREHEAT_CUSTOM), onDrawMenuItem, SetPreheat2); + #endif + TERN_(HAS_PREHEAT, ADDMENUITEM(ICON_Cool, GET_TEXT(MSG_COOLDOWN), onDrawCooldown, SetCoolDown)); + ADDMENUITEM(ICON_Language, PSTR("UI Language"), onDrawLanguage, SetLanguage); + } + CurrentMenu->Draw(); +} + +void Draw_LevBedCorners_Menu() { + DWINUI::ClearMenuArea(); + checkkey = Menu; + if (LevBedMenu == nullptr) LevBedMenu = new MenuClass(); + if (CurrentMenu != LevBedMenu) { + CurrentMenu = LevBedMenu; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG + DWINUI::MenuItemsPrepare(6); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_FL), onDrawMenuItem, LevBedFL); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_FR), onDrawMenuItem, LevBedFR); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_BR), onDrawMenuItem, LevBedBR); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_BL), onDrawMenuItem, LevBedBL); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_C ), onDrawMenuItem, LevBedC ); + } + CurrentMenu->Draw(); +} + +void Draw_Control_Menu() { + checkkey = Menu; + if (ControlMenu == nullptr) ControlMenu = new MenuClass(); + if (CurrentMenu != ControlMenu) { + CurrentMenu = ControlMenu; + SetMenuTitle({103, 1, 28, 14}, {128, 2, 49, 11}, GET_TEXT_F(MSG_CONTROL)); + DWINUI::MenuItemsPrepare(9); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + ADDMENUITEM(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); + ADDMENUITEM(ICON_Motion, GET_TEXT(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); + #if ENABLED(EEPROM_SETTINGS) + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + ADDMENUITEM(ICON_ReadEEPROM, GET_TEXT(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); + ADDMENUITEM(ICON_ResumeEEPROM, GET_TEXT(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); + #endif + ADDMENUITEM(ICON_Reboot, GET_TEXT(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); + ADDMENUITEM(ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_Info, GET_TEXT(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_InfoMenu); + } + CurrentMenu->Draw(); +} + +void Draw_AdvancedSettings_Menu() { + checkkey = Menu; + if (AdvancedSettings == nullptr) AdvancedSettings = new MenuClass(); + if (CurrentMenu != AdvancedSettings) { + CurrentMenu = AdvancedSettings; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG + DWINUI::MenuItemsPrepare(11); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + TERN_(HAS_HOME_OFFSET, ADDMENUITEM(ICON_HomeOffset, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu)); + TERN_(HAS_BED_PROBE, ADDMENUITEM(ICON_ProbeSet, GET_TEXT(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu)); + TERN_(HAS_HOTEND, ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu)); + TERN_(HAS_HEATED_BED, ADDMENUITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu)); + TERN_(HAS_FILAMENT_SENSOR, ADDMENUITEM(ICON_FilSet, GET_TEXT(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu)); + TERN_(POWER_LOSS_RECOVERY, ADDMENUITEM(ICON_Pwrlossr, F("Power-loss recovery"), onDrawPwrLossR, SetPwrLossr)); + TERN_(HAS_LCD_BRIGHTNESS, ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness)); + ADDMENUITEM(ICON_Scolor, F("Select Colors"), onDrawSubMenu, Draw_SelectColors_Menu); + TERN_(SOUND_MENU_ITEM, ADDMENUITEM(ICON_Sound, F("Enable Sound"), onDrawEnableSound, SetEnableSound)); + ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); + } + CurrentMenu->Draw(); +} + +void Draw_Move_Menu() { + checkkey = Menu; + if (MoveMenu == nullptr) MoveMenu = new MenuClass(); + if (CurrentMenu != MoveMenu) { + CurrentMenu = MoveMenu; + SetMenuTitle({192, 1, 42, 14}, {231, 2, 35, 11}, GET_TEXT_F(MSG_MOVE_AXIS)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM_P(ICON_MoveX, GET_TEXT(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); + ADDMENUITEM_P(ICON_MoveY, GET_TEXT(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); + ADDMENUITEM_P(ICON_MoveZ, GET_TEXT(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_Extruder, GET_TEXT(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e)); + } + CurrentMenu->Draw(); + if (!all_axes_trusted()) ui.set_status_P(PSTR("WARNING: position is unknow")); +} + +#if HAS_HOME_OFFSET + void Draw_HomeOffset_Menu() { + checkkey = Menu; + if (HomeOffMenu == nullptr) HomeOffMenu = new MenuClass(); + if (CurrentMenu != HomeOffMenu) { + CurrentMenu = HomeOffMenu; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG + DWINUI::MenuItemsPrepare(4); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM_P(ICON_HomeOffsetX, GET_TEXT(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); + ADDMENUITEM_P(ICON_HomeOffsetY, GET_TEXT(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); + ADDMENUITEM_P(ICON_HomeOffsetZ, GET_TEXT(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); + } + CurrentMenu->Draw(); + } +#endif + +#if HAS_BED_PROBE + void Draw_ProbeSet_Menu() { + checkkey = Menu; + if (ProbeSetMenu == nullptr) ProbeSetMenu = new MenuClass(); + if (CurrentMenu != ProbeSetMenu) { + CurrentMenu = ProbeSetMenu; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG + DWINUI::MenuItemsPrepare(4); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); + ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); + ADDMENUITEM(ICON_ProbeTest, GET_TEXT(MSG_M48_TEST), onDrawMenuItem, ProbeTest); + } + CurrentMenu->Draw(); + } +#endif + +#if HAS_FILAMENT_SENSOR + void Draw_FilSet_Menu() { + checkkey = Menu; + if (FilSetMenu == nullptr) FilSetMenu = new MenuClass(); + if (CurrentMenu != FilSetMenu) { + CurrentMenu = FilSetMenu; + CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); + DWINUI::MenuItemsPrepare(6); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + TERN_(HAS_FILAMENT_SENSOR, ADDMENUITEM(ICON_Runout, GET_TEXT(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable)); + TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance())); + TERN_(PREVENT_COLD_EXTRUSION, ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &thermalManager.extrude_min_temp)); + TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilLoad, GET_TEXT(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length)); + TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length)); + } + CurrentMenu->Draw(); + } +#endif +void Draw_SelectColors_Menu() { + checkkey = Menu; + if (SelectColorMenu == nullptr) SelectColorMenu = new MenuClass(); + if (CurrentMenu != SelectColorMenu) { + CurrentMenu = SelectColorMenu; + SetMenuTitle({0}, {0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG + DWINUI::MenuItemsPrepare(20); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_StockConfiguration, GET_TEXT(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); + ADDMENUITEM_P(0, "Screen Background", onDrawSelColorItem, SelColor, &HMI_data.Background_Color); + ADDMENUITEM_P(0, "Cursor", onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); + ADDMENUITEM_P(0, "Title Background", onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); + ADDMENUITEM_P(0, "Title Text", onDrawSelColorItem, SelColor, &HMI_data.TitleTxt_color); + ADDMENUITEM_P(0, "Text", onDrawSelColorItem, SelColor, &HMI_data.Text_Color); + ADDMENUITEM_P(0, "Selected", onDrawSelColorItem, SelColor, &HMI_data.Selected_Color); + ADDMENUITEM_P(0, "Split Line", onDrawSelColorItem, SelColor, &HMI_data.SplitLine_Color); + ADDMENUITEM_P(0, "Highlight", onDrawSelColorItem, SelColor, &HMI_data.Highlight_Color); + ADDMENUITEM_P(0, "Status Background", onDrawSelColorItem, SelColor, &HMI_data.StatusBg_Color); + ADDMENUITEM_P(0, "Status Text", onDrawSelColorItem, SelColor, &HMI_data.StatusTxt_Color); + ADDMENUITEM_P(0, "Popup Background", onDrawSelColorItem, SelColor, &HMI_data.PopupBg_color); + ADDMENUITEM_P(0, "Popup Text", onDrawSelColorItem, SelColor, &HMI_data.PopupTxt_Color); + ADDMENUITEM_P(0, "Alert Background", onDrawSelColorItem, SelColor, &HMI_data.AlertBg_Color); + ADDMENUITEM_P(0, "Alert Text", onDrawSelColorItem, SelColor, &HMI_data.AlertTxt_Color); + ADDMENUITEM_P(0, "Percent Text", onDrawSelColorItem, SelColor, &HMI_data.PercentTxt_Color); + ADDMENUITEM_P(0, "Bar Fill", onDrawSelColorItem, SelColor, &HMI_data.Barfill_Color); + ADDMENUITEM_P(0, "Indicator value", onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); + ADDMENUITEM_P(0, "Coordinate value", onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); + } + CurrentMenu->Draw(); +} + +void Draw_GetColor_Menu() { + checkkey = Menu; + if (GetColorMenu == nullptr) GetColorMenu = new MenuClass(); + if (CurrentMenu != GetColorMenu) { + CurrentMenu = GetColorMenu; + SetMenuTitle({0}, {0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); + ADDMENUITEM(ICON_Cancel, GET_TEXT(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); + ADDMENUITEM(0, "Blue", onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(1, "Green", onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(2, "Red", onDrawGetColorItem, SetRGBColor); + } + CurrentMenu->Draw(); + DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); +} + +void Draw_Tune_Menu() { + checkkey = Menu; + if (TuneMenu == nullptr) TuneMenu = new MenuClass(); + if (CurrentMenu != TuneMenu) { + CurrentMenu = TuneMenu; + SetMenuTitle({73, 2, 28, 12}, {94, 2, 33, 11}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG + DWINUI::MenuItemsPrepare(10); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); + ADDMENUITEM_P(ICON_Speed, GET_TEXT(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); + TERN_(HAS_HOTEND, HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target)); + TERN_(HAS_HEATED_BED, BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target)); + TERN_(HAS_FAN, FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0])); + #if HAS_ZOFFSET_ITEM + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); + #else + ADDMENUITEM(ICON_SetHome, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); + #endif + #endif + ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament)); + ADDMENUITEM(ICON_Lock, PSTR("Lock Screen"), onDrawMenuItem, Goto_LockScreen); + TERN_(HAS_LCD_BRIGHTNESS, ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness)); + } + CurrentMenu->Draw(); +} + +void Draw_Motion_Menu() { + checkkey = Menu; + if (MotionMenu == nullptr) MotionMenu = new MenuClass(); + if (CurrentMenu != MotionMenu) { + CurrentMenu = MotionMenu; + SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG + DWINUI::MenuItemsPrepare(6); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + ADDMENUITEM(ICON_MaxSpeed, GET_TEXT(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); + ADDMENUITEM(ICON_MaxAccelerated, GET_TEXT(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); + TERN_(HAS_CLASSIC_JERK, ADDMENUITEM(ICON_MaxJerk, GET_TEXT(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu)); + ADDMENUITEM(ICON_Step, GET_TEXT(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); + ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + } + CurrentMenu->Draw(); + DWIN_StatusChanged(nullptr); +} + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void Draw_FilamentMan_Menu() { + checkkey = Menu; + if (FilamentMenu == nullptr) FilamentMenu = new MenuClass(); + if (CurrentMenu != FilamentMenu) { + CurrentMenu = FilamentMenu; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Park, GET_TEXT(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); + ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + TERN_(FILAMENT_LOAD_UNLOAD_GCODES, ADDMENUITEM(ICON_FilUnload, GET_TEXT(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament)); + TERN_(FILAMENT_LOAD_UNLOAD_GCODES, ADDMENUITEM(ICON_FilLoad, GET_TEXT(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament)); + } + CurrentMenu->Draw(); + } +#endif + +#if ENABLED(MESH_BED_LEVELING) + void Draw_ManualMesh_Menu() { + checkkey = Menu; + if (ManualMesh == nullptr) ManualMesh = new MenuClass(); + if (CurrentMenu != ManualMesh) { + CurrentMenu = ManualMesh; + SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); + MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); + ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); + ADDMENUITEM(ICON_MeshSave, GET_TEXT(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); + } + CurrentMenu->Draw(); + } +#endif + +#if HAS_PREHEAT + void Draw_Preheat_Menu(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { + checkkey = Menu; + if (CurrentMenu != PreheatMenu) { + CurrentMenu = PreheatMenu; + SetMenuTitle(cn, en, text); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp)); + TERN_(HAS_HEATED_BED, ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp)); + TERN_(HAS_FAN, ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed)); + TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom)); + } + CurrentMenu->Draw(); + } + + void Draw_Preheat1_Menu() { + HMI_value.Preheat = 0; + if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + Draw_Preheat_Menu({59, 16, 81, 14}, {56, 15, 85, 14}, F(PREHEAT_1_LABEL " Preheat Settings")); // TODO: English "PLA Settings" JPG + } + + void Draw_Preheat2_Menu() { + HMI_value.Preheat = 1; + if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + Draw_Preheat_Menu({142, 16, 82, 14}, {56, 15, 85, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG + } + + #ifdef PREHEAT_3_LABEL + void Draw_Preheat3_Menu() { + HMI_value.Preheat = 2; + if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + #define PREHEAT_3_TITLE PREHEAT_3_LABEL " Preheat Set." + Draw_Preheat_Menu({0}, {0}, F(PREHEAT_3_TITLE)); // TODO: Chinese, English "Custom Preheat Settings" JPG + } + #endif + +#endif + +void Draw_Temperature_Menu() { + checkkey = Menu; + if (TemperatureMenu == nullptr) TemperatureMenu = new MenuClass(); + if (CurrentMenu != TemperatureMenu) { + CurrentMenu = TemperatureMenu; + SetMenuTitle({236, 2, 28, 12}, {56, 15, 85, 14}, GET_TEXT_F(MSG_TEMPERATURE)); + DWINUI::MenuItemsPrepare(7); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + TERN_(HAS_HOTEND, HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target)); + TERN_(HAS_HEATED_BED, BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target)); + TERN_(HAS_FAN, FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0])); + #if HAS_HOTEND + ADDMENUITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); + ADDMENUITEM(ICON_SetABSPreheat, F(PREHEAT_2_LABEL " Preheat Settings"), onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); + #ifdef PREHEAT_3_LABEL + ADDMENUITEM(ICON_SetCustomPreheat, PREHEAT_3_TITLE, onDrawSubMenu, Draw_Preheat3_Menu); + #endif + #endif + } + CurrentMenu->Draw(); +} + +void Draw_MaxSpeed_Menu() { + checkkey = Menu; + if (MaxSpeedMenu == nullptr) MaxSpeedMenu = new MenuClass(); + if (CurrentMenu != MaxSpeedMenu) { + CurrentMenu = MaxSpeedMenu; + SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MAXSPEED)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS])); + } + CurrentMenu->Draw(); +} + +void Draw_MaxAccel_Menu() { + checkkey = Menu; + if (MaxAccelMenu == nullptr) MaxAccelMenu = new MenuClass(); + if (CurrentMenu != MaxAccelMenu) { + CurrentMenu = MaxAccelMenu; + SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_ACCELERATION)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + ADDMENUITEM_P(ICON_MaxAccY, GET_TEXT(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxAccZ, GET_TEXT(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS])); + } + CurrentMenu->Draw(); +} + +#if HAS_CLASSIC_JERK + void Draw_MaxJerk_Menu() { + checkkey = Menu; + if (MaxJerkMenu == nullptr) MaxJerkMenu = new MenuClass(); + if (CurrentMenu != MaxJerkMenu) { + CurrentMenu = MaxJerkMenu; + SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_JERK)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedJerkY, GET_TEXT(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedJerkZ, GET_TEXT(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS])); + } + CurrentMenu->Draw(); + } +#endif + +void Draw_Steps_Menu() { + checkkey = Menu; + if (StepsMenu == nullptr) StepsMenu = new MenuClass(); + if (CurrentMenu != StepsMenu) { + CurrentMenu = StepsMenu; + SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_STEPS_PER_MM)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_StepX, GET_TEXT(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); + ADDMENUITEM_P(ICON_StepY, GET_TEXT(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); + ADDMENUITEM_P(ICON_StepZ, GET_TEXT(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); + TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_StepE, GET_TEXT(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS])); + } + CurrentMenu->Draw(); +} + +#if HAS_HOTEND + void Draw_HotendPID_Menu() { + checkkey = Menu; + if (HotendPIDMenu == nullptr) HotendPIDMenu = new MenuClass(); + if (CurrentMenu != HotendPIDMenu) { + CurrentMenu = HotendPIDMenu; + CurrentMenu->MenuTitle.SetCaption(F("Hotend PID Settings")); + DWINUI::MenuItemsPrepare(8); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); + ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); + ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); + } + CurrentMenu->Draw(); + } +#endif + +#if HAS_HEATED_BED + void Draw_BedPID_Menu() { + checkkey = Menu; + if (BedPIDMenu == nullptr) BedPIDMenu = new MenuClass(); + if (CurrentMenu != BedPIDMenu) { + CurrentMenu = BedPIDMenu; + CurrentMenu->MenuTitle.SetCaption(F("Bed PID Settings")); + DWINUI::MenuItemsPrepare(8); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); + ADDMENUITEM_P(ICON_PIDValue, F(STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); + ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); + ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); + } + CurrentMenu->Draw(); + } +#endif + +#if EITHER(HAS_BED_PROBE, BABYSTEPPING) + void Draw_ZOffsetWiz_Menu() { + checkkey = Menu; + if (ZOffsetWizMenu == nullptr) ZOffsetWizMenu = new MenuClass(); + if (CurrentMenu != ZOffsetWizMenu) { + CurrentMenu = ZOffsetWizMenu; + CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_PROBE_WIZARD)); + DWINUI::MenuItemsPrepare(4); + ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Homing, GET_TEXT(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + ADDMENUITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + } + CurrentMenu->Draw(); + } +#endif + + +#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h new file mode 100644 index 0000000000..365ac9ed4b --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -0,0 +1,268 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DWIN by Creality3D + * Enhanced implementation by Miguel A. Risco-Castillo + */ + +#include "../../../inc/MarlinConfigPre.h" +#include "dwinui.h" +#include "rotary_encoder.h" +#include "../../../libs/BL24CXX.h" + +#if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT + #define HAS_PREHEAT 1 + #if PREHEAT_COUNT < 2 + #error "Creality DWIN requires two material preheat presets." + #endif +#endif + +#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) + #define HAS_ONESTEP_LEVELING 1 +#endif + +#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) + #define JUST_BABYSTEP 1 +#endif + +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 +#endif + +static constexpr size_t eeprom_data_size = 64; + +enum processID : uint8_t { + // Process ID + MainMenu, + Menu, + SetInt, + SetPInt, + SetIntNoDraw, + SetFloat, + SetPFloat, + SelectFile, + PrintProcess, + PrintDone, + Info, + + // Popup Windows + Homing, + Leveling, + PauseOrStop, + FilamentPurge, + WaitResponse, + Locked, + NothingToDo, +}; + +enum pidresult_t : uint8_t { + PID_BAD_EXTRUDER_NUM, + PID_TEMP_TOO_HIGH, + PID_TUNING_TIMEOUT, + PID_EXTR_START, + PID_BED_START, + PID_DONE +}; + +// Picture ID +#define Start_Process 0 +#define Language_English 1 +#define Language_Chinese 2 + +#define DWIN_CHINESE 123 +#define DWIN_ENGLISH 0 + +typedef struct { + int8_t Color[3]; // Color components + int8_t Preheat = 0; // Material Select 0: PLA, 1: ABS, 2: Custom + AxisEnum axis = X_AXIS; // Axis Select + int32_t MaxValue = 0; // Auxiliar max integer/scaled float value + int32_t MinValue = 0; // Auxiliar min integer/scaled float value + int8_t dp = 0; // Auxiliar decimal places + int32_t Value = 0; // Auxiliar integer / scaled float value + int16_t *P_Int = nullptr; // Auxiliar pointer to 16 bit integer variable + float *P_Float = nullptr; // Auxiliar pointer to float variable + void (*Apply)() = nullptr; // Auxiliar apply function + void (*LiveUpdate)() = nullptr; // Auxiliar live update function +} HMI_value_t; + +typedef struct { + uint16_t Background_Color = Def_Background_Color; + uint16_t Cursor_color = Def_Cursor_color; + uint16_t TitleBg_color = Def_TitleBg_color; + uint16_t TitleTxt_color = Def_TitleTxt_color; + uint16_t Text_Color = Def_Text_Color; + uint16_t Selected_Color = Def_Selected_Color; + uint16_t SplitLine_Color = Def_SplitLine_Color; + uint16_t Highlight_Color = Def_Highlight_Color; + uint16_t StatusBg_Color = Def_StatusBg_Color; + uint16_t StatusTxt_Color = Def_StatusTxt_Color; + uint16_t PopupBg_color = Def_PopupBg_color; + uint16_t PopupTxt_Color = Def_PopupTxt_Color; + uint16_t AlertBg_Color = Def_AlertBg_Color; + uint16_t AlertTxt_Color = Def_AlertTxt_Color; + uint16_t PercentTxt_Color = Def_PercentTxt_Color; + uint16_t Barfill_Color = Def_Barfill_Color; + uint16_t Indicator_Color = Def_Indicator_Color; + uint16_t Coordinate_Color = Def_Coordinate_Color; + TERN_(HAS_HOTEND, int16_t HotendPidT = PREHEAT_1_TEMP_HOTEND); + TERN_(HAS_HOTEND, int16_t PidCycles = 10); + #ifdef PREHEAT_1_TEMP_BED + int16_t BedPidT = PREHEAT_1_TEMP_BED; + #endif + TERN_(PREVENT_COLD_EXTRUSION, uint16_t ExtMinT = EXTRUDE_MINTEMP); +} HMI_data_t; + +typedef struct { + uint8_t language; + bool pause_flag:1; // printing is paused + bool pause_action:1; // flag a pause action + bool print_finish:1; // print was finished + bool select_flag:1; // Popup button selected + bool home_flag:1; // homing in course + bool heat_flag:1; // 0: heating done 1: during heating + bool lock_flag:1; // 0: lock called from AdvSet 1: lock called from Tune +} HMI_flag_t; + +extern HMI_value_t HMI_value; +extern HMI_flag_t HMI_flag; +extern HMI_data_t HMI_data; +extern uint8_t checkkey; +extern millis_t dwin_heat_time; + +// Popup windows +void DWIN_Popup_Confirm(uint8_t icon, const char * const msg1, const char * const msg2); +#if HAS_HOTEND || HAS_HEATED_BED + void DWIN_Popup_Temperature(const bool toohigh); +#endif +TERN_(HAS_HOTEND, void Popup_Window_ETempTooLow()); +void Popup_Window_Resume(); + +// SD Card +void HMI_SDCardInit(); +void HMI_SDCardUpdate(); + +// Main Process +//void Icon_print(); +//void Icon_control(); +//void Icon_leveling(bool value); + +// Other +void Goto_PrintProcess(); +void Goto_Main_Menu(); +void update_variable(); +void Draw_Select_Highlight(const bool sel); +void Draw_Status_Area(const bool with_update); // Status Area +void Draw_Main_Area(); // Redraw main area; +void DWIN_Redraw_screen(); // Redraw all screen elements +void HMI_StartFrame(const bool with_update); // Prepare the menu view +void HMI_MainMenu(); // Main process screen +void HMI_SelectFile(); // File page +void HMI_Printing(); // Print page +void HMI_ReturnScreen(); // Return to previous screen before popups +void ApplyExtMinT(); +void HMI_SetLanguageCache(); // Set the languaje image cache + +//void HMI_Leveling(); // Level the page +//void HMI_LevBedCorners(); // Tramming menu +//void HMI_Info(); // Information menu + + +void HMI_Init(); +void HMI_Popup(); +void HMI_SaveProcessID(const uint8_t id); +void HMI_AudioFeedback(const bool success=true); +void DWIN_Startup(); +void DWIN_Update(); +void EachMomentUpdate(); +void DWIN_HandleScreen(); +void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text); +void DWIN_StatusChanged(const char * const text); +void DWIN_StatusChanged_P(PGM_P const text); +void DWIN_StartHoming(); +void DWIN_CompletedHoming(); +TERN_(MESH_BED_LEVELING, void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval)); +void DWIN_MeshLevelingStart(); +void DWIN_CompletedLeveling(); +void DWIN_PidTuning(pidresult_t result); +void DWIN_Print_Started(const bool sd = false); +void DWIN_Print_Finished(); +#if HAS_FILAMENT_SENSOR + void DWIN_FilamentRunout(const uint8_t extruder); +#endif +void DWIN_Progress_Update(); +void DWIN_Print_Header(const char *text); +void DWIN_SetColorDefaults(); +void DWIN_StoreSettings(char *buff); +void DWIN_LoadSettings(const char *buff); +void DWIN_SetDataDefaults(); +void DWIN_RebootScreen(); + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void Draw_Popup_FilamentPurge(); + void DWIN_Popup_FilamentPurge(); + void HMI_FilamentPurge(); +#endif + +// Utility and extensions +void HMI_LockScreen(); +void DWIN_LockScreen(const bool flag = true); + +// HMI user control functions +void HMI_Menu(); +void HMI_SetInt(); +void HMI_SetPInt(); +void HMI_SetIntNoDraw(); +void HMI_SetFloat(); +void HMI_SetPFloat(); + +// Menu drawing functions +void Draw_Control_Menu(); +void Draw_AdvancedSettings_Menu(); +void Draw_Prepare_Menu(); +void Draw_Move_Menu(); +void Draw_LevBedCorners_Menu(); +TERN_(HAS_HOME_OFFSET, void Draw_HomeOffset_Menu()); +TERN_(HAS_BED_PROBE, void Draw_ProbeSet_Menu()); +TERN_(HAS_FILAMENT_SENSOR, void Draw_FilSet_Menu()); +void Draw_SelectColors_Menu(); +void Draw_GetColor_Menu(); +void Draw_Tune_Menu(); +void Draw_Motion_Menu(); +TERN_(ADVANCED_PAUSE_FEATURE, void Draw_FilamentMan_Menu()); +TERN_(MESH_BED_LEVELING, void Draw_ManualMesh_Menu()); +#if HAS_HOTEND + void Draw_Preheat1_Menu(); + void Draw_Preheat2_Menu(); + void Draw_Preheat3_Menu(); +#endif +void Draw_Temperature_Menu(); +void Draw_MaxSpeed_Menu(); +void Draw_MaxAccel_Menu(); +TERN_(HAS_CLASSIC_JERK, void Draw_MaxJerk_Menu()); +void Draw_Steps_Menu(); +TERN_(HAS_HOTEND, void Draw_HotendPID_Menu()); +TERN_(HAS_HEATED_BED, void Draw_BedPID_Menu()); +#if EITHER(HAS_BED_PROBE, BABYSTEPPING) + void Draw_ZOffsetWiz_Menu(); +#endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp new file mode 100644 index 0000000000..99ee74732e --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp @@ -0,0 +1,564 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +/******************************************************************************** + * @file lcd/e3v2/enhanced/dwin_lcd.cpp + * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo + * @date 2021/08/29 + * @version 2.1.1 + * @brief DWIN screen control functions + ********************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + +#include "../../../inc/MarlinConfig.h" + +#include "dwin_lcd.h" +#include // for memset + +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + +// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. +// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. +uint8_t DWIN_SendBuf[11 + DWIN_DataLength] = { 0xAA }; +uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; +uint8_t databuf[26] = { 0 }; +uint8_t receivedType; + +int recnum = 0; + +inline void DWIN_Byte(size_t &i, const uint16_t bval) { + DWIN_SendBuf[++i] = bval; +} + +inline void DWIN_Word(size_t &i, const uint16_t wval) { + DWIN_SendBuf[++i] = wval >> 8; + DWIN_SendBuf[++i] = wval & 0xFF; +} + +inline void DWIN_Long(size_t &i, const uint32_t lval) { + DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; + DWIN_SendBuf[++i] = lval & 0xFF; +} + +inline void DWIN_String(size_t &i, const char * const string, uint16_t rlimit = 0xFFFF) { + if (!string) return; + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(strlen(string), rlimit)); + if (len == 0) return; + memcpy(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +inline void DWIN_String(size_t &i, const __FlashStringHelper * string, uint16_t rlimit = 0xFFFF) { + if (!string) return; + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P((PGM_P)string))); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. + if (len == 0) return; + memcpy(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +// Send the data in the buffer and the packet end +inline void DWIN_Send(size_t &i) { + ++i; + LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } +} + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void) { + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + const millis_t serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + + size_t i = 0; + DWIN_Byte(i, 0x00); + DWIN_Send(i); + + while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { + databuf[recnum] = LCD_SERIAL.read(); + // ignore the invalid data + if (databuf[0] != FHONE) { // prevent the program from running. + if (recnum > 0) { + recnum = 0; + ZERO(databuf); + } + continue; + } + delay(10); + recnum++; + } + + return ( recnum >= 3 + && databuf[0] == FHONE + && databuf[1] == '\0' + && databuf[2] == 'O' + && databuf[3] == 'K' ); +} + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir) { + size_t i = 0; + DWIN_Byte(i, 0x34); + DWIN_Byte(i, 0x5A); + DWIN_Byte(i, 0xA5); + DWIN_Byte(i, dir); + DWIN_Send(i); +} + +// Update display +void DWIN_UpdateLCD(void) { + size_t i = 0; + DWIN_Byte(i, 0x3D); + DWIN_Send(i); +} + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color) { + size_t i = 0; + DWIN_Byte(i, 0x01); + DWIN_Word(i, color); + DWIN_Send(i); +} + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + DWIN_Word(i, color); + DWIN_Byte(i, width); + DWIN_Byte(i, height); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x03); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, + uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x05); + DWIN_Byte(i, mode); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x09); + DWIN_Byte(i, (mode << 7) | dir); + DWIN_Word(i, dis); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +// rlimit: For draw less chars than string length use rlimit +void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit) { + size_t i = 0; + DWIN_Byte(i, 0x11); + // Bit 7: widthAdjust + // Bit 6: bShow + // Bit 5-4: Unused (0) + // Bit 3-0: size + DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_String(i, string, rlimit); + DWIN_Send(i); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + size_t i = 0; + DWIN_Byte(i, 0x14); + // Bit 7: bshow + // Bit 6: 1 = signed; 0 = unsigned number; + // Bit 5: zeroFill + // Bit 4: zeroMode + // Bit 3-0: size + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, 0); // fNum + DWIN_Word(i, x); + DWIN_Word(i, y); + #if 0 + for (char count = 0; count < 8; count++) { + DWIN_Byte(i, value); + value >>= 8; + if (!(value & 0xFF)) break; + } + #else + // Write a big-endian 64 bit integer + const size_t p = i + 1; + for (char count = 8; count--;) { // 7..0 + ++i; + DWIN_SendBuf[p + count] = value; + value >>= 8; + } + #endif + + DWIN_Send(i); +} + +// Draw a positive floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Scaled positive float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + size_t i = 0; + DWIN_Byte(i, 0x14); + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, fNum); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Long(i, value); + DWIN_Send(i); +} + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Display QR code +// The size of the QR code is (46*QR_Pixel)*(46*QR_Pixel) dot matrix +// QR_Pixel: The pixel size occupied by each point of the QR code: 0x01-0x0F (1-16) +// (Nx, Ny): The coordinates of the upper left corner displayed by the QR code +// str: multi-bit data +void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, char *string) { + size_t i = 0; + DWIN_Byte(i, 0x21); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, QR_Pixel); + DWIN_String(i, string); + DWIN_Send(i); +} + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id) { + size_t i = 0; + DWIN_Word(i, 0x2200); + DWIN_Byte(i, id); + DWIN_Send(i); +} + +// Draw an Icon +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x23); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | libID); + DWIN_Byte(i, picID); + DWIN_Send(i); +} + +// Draw an Icon from SRAM +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// x/y: Upper-left point +// addr: SRAM address +void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint16_t x, uint16_t y, uint16_t addr) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x24); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | 0x00); + DWIN_Word(i, addr); + DWIN_Send(i); +} + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { + size_t i = 0; + DWIN_Byte(i, 0x25); + DWIN_Byte(i, n); + DWIN_Byte(i, id); + DWIN_Send(i); +} + +// Copy area from current virtual display area to current screen +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x26); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Copy area from virtual display area to current screen +// IBD: background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x27); + DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | cacheID); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Animate a series of icons +// animID: Animation ID; 0x00-0x0F +// animate: true on; false off; +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Bit 7: animation on or off + // Bit 6: start from begin or end + // Bit 5-4: unused (0) + // Bit 3-0: animID + DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); + DWIN_Byte(i, libID); + DWIN_Byte(i, picIDs); + DWIN_Byte(i, picIDe); + DWIN_Byte(i, interval); + DWIN_Send(i); +} + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state) { + size_t i = 0; + DWIN_Byte(i, 0x29); + DWIN_Word(i, state); + DWIN_Send(i); +} + +// Set LCD Brightness 0x00-0xFF +void DWIN_LCD_Brightness(const uint8_t brightness) { + size_t i = 0; + DWIN_Byte(i, 0x30); + DWIN_Byte(i, brightness); + DWIN_Send(i); +} + +// Write buffer data to the SRAM or Flash +// mem: 0x5A=32KB SRAM, 0xA5=16KB Flash +// addr: start address +// length: Bytes to write +// data: address of the buffer with data +void DWIN_WriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data) { + const uint8_t max_size = 128; + uint16_t pending = length; + uint16_t to_send; + uint16_t indx; + uint8_t block = 0; + + while (pending > 0) { + indx = block * max_size; + to_send = _MIN(pending, max_size); + size_t i = 0; + DWIN_Byte(i, 0x31); + DWIN_Byte(i, mem); + DWIN_Word(i, addr + indx); // start address of the data block + ++i; + LOOP_L_N(j, i) { LCD_SERIAL.write(DWIN_SendBuf[j]); delayMicroseconds(1); } // Buf header + for (uint16_t j = indx; j <= indx + to_send - 1; j++) LCD_SERIAL.write(*(data + j)); delayMicroseconds(1); // write block of data + LOOP_L_N(j, 4) { LCD_SERIAL.write(DWIN_BufTail[j]); delayMicroseconds(1); } + block++; + pending -= to_send; + } +} + +// Write the contents of the 32KB SRAM data memory into the designated image memory space. +// picID: Picture memory space location, 0x00-0x0F, each space is 32Kbytes +void DWIN_SRAMToPic(uint8_t picID) { + size_t i = 0; + DWIN_Byte(i, 0x33); + DWIN_Byte(i, 0x5A); + DWIN_Byte(i, 0xA5); + DWIN_Byte(i, picID); + DWIN_Send(i); +} + +//--------------------------Test area ------------------------- + +// void DWIN_ReadSRAM(uint16_t addr, uint8_t length, const char * const data) { +// size_t i = 0; +// DWIN_Byte(i, 0x32); +// DWIN_Byte(i, 0x5A); // 0x5A Read from SRAM - 0xA5 Read from Flash +// DWIN_Word(i, addr); // 0x0000 to 0x7FFF +// const size_t len = _MIN(0xF0, length); +// DWIN_Byte(i, len); +// DWIN_Send(i); +// } + +/*---------------------------------------- Memory functions ----------------------------------------*/ +// The LCD has an additional 32KB SRAM and 16KB Flash + +// Data can be written to the sram and save to one of the jpeg page files + +// Write Data Memory +// command 0x31 +// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Data: data +// +// Flash writing returns 0xA5 0x4F 0x4B + +// Read Data Memory +// command 0x32 +// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Length: leangth of data to read; 0x01-0xF0 +// +// Response: +// Type, Address, Length, Data + +// Write Picture Memory +// Write the contents of the 32KB SRAM data memory into the designated image memory space +// Issued: 0x5A, 0xA5, PIC_ID +// Response: 0xA5 0x4F 0x4B +// +// command 0x33 +// 0x5A, 0xA5 +// PicId: Picture Memory location, 0x00-0x0F +// +// Flash writing returns 0xA5 0x4F 0x4B + +#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h new file mode 100644 index 0000000000..71e66301b4 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -0,0 +1,282 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +/******************************************************************************** + * @file lcd/e3v2/enhanced/dwin_lcd.h + * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo + * @date 2021/08/29 + * @version 2.1.1 + * @brief DWIN screen control functions + ********************************************************************************/ + +#pragma once + +#include + +#define RECEIVED_NO_DATA 0x00 +#define RECEIVED_SHAKE_HAND_ACK 0x01 + +#define FHONE 0xAA + +#define DWIN_SCROLL_UP 2 +#define DWIN_SCROLL_DOWN 3 + +#define DWIN_WIDTH 272 +#define DWIN_HEIGHT 480 + +#define DWIN_DataLength (DWIN_WIDTH / 6 * 2) + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(void); + +// Set the backlight luminance +// luminance: (0x00-0xFF) +void DWIN_Backlight_SetLuminance(const uint8_t luminance); + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir); + +// Update display +void DWIN_UpdateLCD(void); + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color); + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +// rlimit: For draw less chars than string length use rlimit +void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit = 0xFFFF); +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit = 0xFFFF) { + DWIN_Draw_String(0, bShow, size, color, bColor, x, y, string, rlimit); +} + +class __FlashStringHelper; + +inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, (char *)title); +} +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(0, bShow, size, color, bColor, x, y, (char *)title); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); + +// Draw a positive floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Scaled positive float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Display QR code +// The size of the QR code is (46*QR_Pixel)*(46*QR_Pixel) dot matrix +// QR_Pixel: The pixel size occupied by each point of the QR code: 0x01-0x0F (1-16) +// (Nx, Ny): The coordinates of the upper left corner displayed by the QR code +// str: multi-bit data +void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, char *string); + +inline void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_QR(QR_Pixel, x, y, (char *)title); +} + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id); + +// Draw an Icon +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Draw an Icon with transparent background +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +inline void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + DWIN_ICON_Show(0, 0, 1, libID, picID, x, y); +} + +// Draw an Icon from SRAM +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// x/y: Upper-left point +// addr: SRAM address +void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint16_t x, uint16_t y, uint16_t addr); + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); + +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID +inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } + +// Copy area from current virtual display area to current screen +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Copy area from virtual display area to current screen +// IBD: background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Copy area from virtual display area to current screen with transparent background +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +inline void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, + uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + DWIN_Frame_AreaCopy(0, 0, 1, cacheID, xStart, yStart, xEnd, yEnd, x, y); +} + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, + uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); + +// Set LCD Brightness 0x00-0x0F +void DWIN_LCD_Brightness(const uint8_t brightness); + +// Write buffer data to the SRAM or Flash +// mem: 0x5A=32KB SRAM, 0xA5=16KB Flash +// addr: start address +// length: Bytes to write +// data: address of the buffer with data +void DWIN_WriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data); + +// Write the contents of the 32KB SRAM data memory into the designated image memory space. +// picID: Picture memory space location, 0x00-0x0F, each space is 32Kbytes +void DWIN_SRAMToPic(uint8_t picID); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp new file mode 100644 index 0000000000..db08242183 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -0,0 +1,452 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + +#include "../../../inc/MarlinConfig.h" +#include "../../../core/macros.h" +#include "dwin_lcd.h" +#include "dwinui.h" + +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + +uint8_t MenuItemTotal = 0; +uint8_t MenuItemCount = 0; +MenuItemClass** MenuItems = nullptr; +MenuClass *CurrentMenu = nullptr; +MenuClass *PreviousMenu = nullptr; + +xy_int_t DWINUI::cursor = { 0 }; +uint16_t DWINUI::pencolor = Color_White; +uint16_t DWINUI::textcolor = Def_Text_Color; +uint16_t DWINUI::backcolor = Def_Background_Color; +uint8_t DWINUI::font = font8x16; + +void (*DWINUI::onCursorErase)(uint8_t line)=nullptr; +void (*DWINUI::onCursorDraw)(uint8_t line)=nullptr; +void (*DWINUI::onTitleDraw)(TitleClass* title)=nullptr; +void (*DWINUI::onMenuDraw)(MenuClass* menu)=nullptr; + +void DWINUI::Init(void) { + DEBUG_ECHOPGM("\r\nDWIN handshake "); + delay(750); // Delay here or init later in the boot process + const bool success = DWIN_Handshake(); + if (success) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); + DWIN_Frame_SetDir(1); + TERN(SHOW_BOOTSCREEN,,DWIN_Frame_Clear(Color_Bg_Black)); + DWIN_UpdateLCD(); + cursor.x = 0; + cursor.y = 0; + pencolor = Color_White; + textcolor = Def_Text_Color; + backcolor = Def_Background_Color; + font = font8x16; +} + +// Set text/number font +void DWINUI::SetFont(uint8_t cfont) { + font = cfont; +} + +// Get font character width +uint8_t DWINUI::Get_font_width(uint8_t cfont) { + switch (cfont) { + case font6x12 : return 6; + case font8x16 : return 8; + case font10x20: return 10; + case font12x24: return 12; + case font14x28: return 14; + case font16x32: return 16; + case font20x40: return 20; + case font24x48: return 24; + case font28x56: return 28; + case font32x64: return 32; + default: return 0; + } +} + +// Get font character heigh +uint8_t DWINUI::Get_font_height(uint8_t cfont) { + switch (cfont) { + case font6x12 : return 12; + case font8x16 : return 16; + case font10x20: return 20; + case font12x24: return 24; + case font14x28: return 28; + case font16x32: return 32; + case font20x40: return 40; + case font24x48: return 48; + case font28x56: return 56; + case font32x64: return 64; + default: return 0; + } +} + +// Get screen x coodinates from text column +uint16_t DWINUI::ColToX(uint8_t col) { + return col * Get_font_width(font); +} + +// Get screen y coodinates from text row +uint16_t DWINUI::RowToY(uint8_t row) { + return row * Get_font_height(font); +} + +// Set text/number color +void DWINUI::SetColors(uint16_t fgcolor, uint16_t bgcolor) { + textcolor = fgcolor; + backcolor = bgcolor; +} +void DWINUI::SetTextColor(uint16_t fgcolor) { + textcolor = fgcolor; +} +void DWINUI::SetBackgroundColor(uint16_t bgcolor) { + backcolor = bgcolor; +} + +// Moves cursor to point +// x: abscissa of the display +// y: ordinate of the display +// point: xy coordinate +void DWINUI::MoveTo(int16_t x, int16_t y) { + cursor.x = x; + cursor.y = y; +} +void DWINUI::MoveTo(xy_int_t point) { + cursor = point; +} + +// Moves cursor relative to the actual position +// x: abscissa of the display +// y: ordinate of the display +// point: xy coordinate +void DWINUI::MoveBy(int16_t x, int16_t y) { + cursor.x += x; + cursor.y += y; +} +void DWINUI::MoveBy(xy_int_t point) { + cursor += point; +} + +// Draw a Centered string using DWIN_WIDTH +void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { + const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * Get_font_width(size)) / 2 - 1; + DWIN_Draw_String(bShow, size, color, bColor, x, y, string); +} + +// Draw a char at cursor position +void DWINUI::Draw_Char(const char c) { + const char string[2] = { c, 0}; + DWIN_Draw_String(false, font, textcolor, backcolor, cursor.x, cursor.y, string, 1); + MoveBy(Get_font_width(font), 0); +} + +// Draw a string at cursor position +// color: Character color +// *string: The string +// rlimit: For draw less chars than string length use rlimit +void DWINUI::Draw_String(const char * const string, uint16_t rlimit) { + DWIN_Draw_String(false, font, textcolor, backcolor, cursor.x, cursor.y, string, rlimit); + MoveBy(strlen(string) * Get_font_width(font), 0); +} +void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rlimit) { + DWIN_Draw_String(false, font, color, backcolor, cursor.x, cursor.y, string, rlimit); + MoveBy(strlen(string) * Get_font_width(font), 0); +} + +// Draw a signed floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWINUI::Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + if (value < 0) { + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, -value); + DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, F("-")); + } + else { + DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, F(" ")); + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + } +} + +// Draw a circle +// color: circle color +// x: the abscissa of the center of the circle +// y: ordinate of the center of the circle +// r: circle radius +void DWINUI::Draw_Circle(uint16_t color, uint16_t x, uint16_t y, uint8_t r) { + int a = 0, b = 0; + while (a <= b) { + b = SQRT(sq(r) - sq(a)); + if (a == 0) b--; + DWIN_Draw_Point(color, 1, 1, x + a, y + b); // Draw some sector 1 + DWIN_Draw_Point(color, 1, 1, x + b, y + a); // Draw some sector 2 + DWIN_Draw_Point(color, 1, 1, x + b, y - a); // Draw some sector 3 + DWIN_Draw_Point(color, 1, 1, x + a, y - b); // Draw some sector 4 + DWIN_Draw_Point(color, 1, 1, x - a, y - b); // Draw some sector 5 + DWIN_Draw_Point(color, 1, 1, x - b, y - a); // Draw some sector 6 + DWIN_Draw_Point(color, 1, 1, x - b, y + a); // Draw some sector 7 + DWIN_Draw_Point(color, 1, 1, x - a, y + b); // Draw some sector 8 + a++; + } +} + +// Draw a circle filled with color +// bcolor: fill color +// x: the abscissa of the center of the circle +// y: ordinate of the center of the circle +// r: circle radius +void DWINUI::Draw_FillCircle(uint16_t bcolor, uint16_t x,uint16_t y,uint8_t r) { + int a = 0, b = 0; + while (a <= b) { + b = SQRT(sq(r) - sq(a)); // b=sqrt(r*r-a*a); + if (a == 0) b--; + DWIN_Draw_Line(bcolor, x-b,y-a,x+b,y-a); + DWIN_Draw_Line(bcolor, x-a,y-b,x+a,y-b); + DWIN_Draw_Line(bcolor, x-b,y+a,x+b,y+a); + DWIN_Draw_Line(bcolor, x-a,y+b,x+a,y+b); + a++; + } +} + +// Color Interpolator +// val : Interpolator minv..maxv +// minv : Minimum value +// maxv : Maximun value +// color1 : Start color +// color2 : End color +uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2) { + uint8_t B,G,R; + float n; + n = (float)(val-minv)/(maxv-minv); + R = (1-n)*GetRColor(color1) + n*GetRColor(color2); + G = (1-n)*GetGColor(color1) + n*GetGColor(color2); + B = (1-n)*GetBColor(color1) + n*GetBColor(color2); + return RGB(R,G,B); +} + +// Color Interpolator through Red->Yellow->Green->Blue +// val : Interpolator minv..maxv +// minv : Minimum value +// maxv : Maximun value +uint16_t DWINUI::RainbowInt(int16_t val, int16_t minv, int16_t maxv) { + uint8_t B,G,R; + const uint8_t maxB = 28; + const uint8_t maxR = 28; + const uint8_t maxG = 38; + const int16_t limv = _MAX(abs(minv), abs(maxv)); + float n; + if (minv>=0) { + n = (float)(val-minv)/(maxv-minv); + } else { + n = (float)val/limv; + } + n = _MIN(1, n); + n = _MAX(-1, n); + if (n < 0) { + R = 0; + G = (1+n)*maxG; + B = (-n)*maxB; + } else if (n < 0.5) { + R = maxR*n*2; + G = maxG; + B = 0; + } else { + R = maxR; + G = maxG*(1-n); + B = 0; + } + return RGB(R,G,B); +} + +// Draw a checkbox +// Color: frame color +// bColor: Background color +// x/y: Upper-left point +// mode : 0 : unchecked, 1 : checked +void DWINUI::Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool checked=false) { + DWIN_Draw_String(false, true, font8x16, color, bcolor, x + 4, y, checked ? F("x") : F(" ")); + DWIN_Draw_Rectangle(0, color, x + 2, y + 2, x + 17, y + 17); +} + +// Clear Menu by filling the menu area with background color +void DWINUI::ClearMenuArea() { + DWIN_Draw_Rectangle(1, backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); +} + +void DWINUI::MenuItemsClear() { + if (MenuItems == nullptr) return; + for (uint8_t i = 0; i < MenuItemCount; i++) delete MenuItems[i]; + delete[] MenuItems; + MenuItems = nullptr; + MenuItemCount = 0; + MenuItemTotal = 0; +} + +void DWINUI::MenuItemsPrepare(uint8_t totalitems) { + MenuItemsClear(); + MenuItemTotal = totalitems; + MenuItems = new MenuItemClass*[totalitems]; +} + +MenuItemClass* DWINUI::MenuItemsAdd(MenuItemClass* menuitem) { + if (MenuItemCount < MenuItemTotal) { + MenuItems[MenuItemCount] = menuitem; + menuitem->pos = MenuItemCount++; + return menuitem; + } + else { + delete menuitem; + return nullptr; + } +} + +/* Title Class ==============================================================*/ + +TitleClass Title; + +void TitleClass::Draw() { + if (DWINUI::onTitleDraw != nullptr) (*DWINUI::onTitleDraw)(this); +} + +void TitleClass::SetCaption(const char * const title) { + frameid = 0; + if ( caption == title ) return; + const uint8_t len = _MIN(sizeof(caption) - 1, strlen(title)); + memcpy(&caption[0], title, len); + caption[len] = '\0'; +} + +void TitleClass::ShowCaption(const char * const title) { + SetCaption(title); + Draw(); +} + +void TitleClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + caption[0] = '\0'; + frameid = id; + frame = { x1, y1, x2, y2 }; +} + +void TitleClass::SetFrame(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { + SetFrame(1, x, y, x + w - 1, y + h - 1); +} + +void TitleClass::FrameCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + SetFrame(id, x1, y1, x2, y2); + Draw(); +} + +void TitleClass::FrameCopy(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { + FrameCopy(1, x, y, x + w - 1, y + h - 1); +} + +/* Menu Class ===============================================================*/ + +MenuClass::MenuClass() { + selected = 0; + topline = 0; +} + +void MenuClass::Draw() { + MenuTitle.Draw(); + if (DWINUI::onMenuDraw != nullptr) (*DWINUI::onMenuDraw)(this); + for (uint8_t i = 0; i < MenuItemCount; i++) + MenuItems[i]->Draw(i - topline); + if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); + DWIN_UpdateLCD(); +} + +void MenuClass::onScroll(bool dir) { + int8_t sel = selected; + if (dir) sel++; else sel--; + LIMIT(sel, 0, MenuItemCount - 1); + if (sel != selected) { + if (DWINUI::onCursorErase != nullptr) DWINUI::onCursorErase(line()); + if ((sel - topline) == TROWS) { + DWIN_Frame_AreaMove(1, DWIN_SCROLL_UP, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); + topline++; + MenuItems[sel]->Draw(TROWS - 1); + } + if ((sel < topline)) { + DWIN_Frame_AreaMove(1, DWIN_SCROLL_DOWN, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); + topline--; + MenuItems[sel]->Draw(0); + } + selected = sel; + if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); + DWIN_UpdateLCD(); + } +} + +void MenuClass::onClick() { + if (MenuItems[selected]->onClick != nullptr) (*MenuItems[selected]->onClick)(); +} + +MenuItemClass *MenuClass::SelectedItem() { + return MenuItems[selected]; +} + +/* MenuItem Class ===========================================================*/ + +MenuItemClass::MenuItemClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { + icon = cicon; + onClick = onclick; + onDraw = ondraw; + const uint8_t len = _MIN(sizeof(caption) - 1, strlen(text)); + memcpy(&caption[0], text, len); + caption[len] = '\0'; +} + +MenuItemClass::MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)()) { + icon = cicon; + onClick = onclick; + onDraw = ondraw; + caption[0] = '\0'; + frameid = id; + frame = { x1, y1, x2, y2 }; +} + +void MenuItemClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { + caption[0] = '\0'; + frameid = id; + frame = { x1, y1, x2, y2 }; +} + +void MenuItemClass::Draw(int8_t line) { + if (line < 0 || line >= TROWS) return; + if (onDraw != nullptr) (*onDraw)(this, line); +}; + +MenuItemPtrClass::MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemClass(cicon, text, ondraw, onclick) { + value = val; +}; + +#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h new file mode 100644 index 0000000000..0aec187049 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -0,0 +1,623 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../core/types.h" +#include "dwin_lcd.h" + +// ICON ID +#define ICON 7 // Icon set file 7.ICO + +#define ICON_LOGO 0 +#define ICON_Print_0 1 +#define ICON_Print_1 2 +#define ICON_Prepare_0 3 +#define ICON_Prepare_1 4 +#define ICON_Control_0 5 +#define ICON_Control_1 6 +#define ICON_Leveling_0 7 +#define ICON_Leveling_1 8 +#define ICON_HotendTemp 9 +#define ICON_BedTemp 10 +#define ICON_Speed 11 +#define ICON_Zoffset 12 +#define ICON_Back 13 +#define ICON_File 14 +#define ICON_PrintTime 15 +#define ICON_RemainTime 16 +#define ICON_Setup_0 17 +#define ICON_Setup_1 18 +#define ICON_Pause_0 19 +#define ICON_Pause_1 20 +#define ICON_Continue_0 21 +#define ICON_Continue_1 22 +#define ICON_Stop_0 23 +#define ICON_Stop_1 24 +#define ICON_Bar 25 +#define ICON_More 26 + +#define ICON_Axis 27 +#define ICON_CloseMotor 28 +#define ICON_Homing 29 +#define ICON_SetHome 30 +#define ICON_PLAPreheat 31 +#define ICON_ABSPreheat 32 +#define ICON_Cool 33 +#define ICON_Language 34 + +#define ICON_MoveX 35 +#define ICON_MoveY 36 +#define ICON_MoveZ 37 +#define ICON_Extruder 38 + +#define ICON_Temperature 40 +#define ICON_Motion 41 +#define ICON_WriteEEPROM 42 +#define ICON_ReadEEPROM 43 +#define ICON_ResumeEEPROM 44 +#define ICON_Info 45 + +#define ICON_SetEndTemp 46 +#define ICON_SetBedTemp 47 +#define ICON_FanSpeed 48 +#define ICON_SetPLAPreheat 49 +#define ICON_SetABSPreheat 50 + +#define ICON_MaxSpeed 51 +#define ICON_MaxAccelerated 52 +#define ICON_MaxJerk 53 +#define ICON_Step 54 +#define ICON_PrintSize 55 +#define ICON_Version 56 +#define ICON_Contact 57 +#define ICON_StockConfiguration 58 +#define ICON_MaxSpeedX 59 +#define ICON_MaxSpeedY 60 +#define ICON_MaxSpeedZ 61 +#define ICON_MaxSpeedE 62 +#define ICON_MaxAccX 63 +#define ICON_MaxAccY 64 +#define ICON_MaxAccZ 65 +#define ICON_MaxAccE 66 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 +#define ICON_StepX 71 +#define ICON_StepY 72 +#define ICON_StepZ 73 +#define ICON_StepE 74 +#define ICON_Setspeed 75 +#define ICON_SetZOffset 76 +#define ICON_Rectangle 77 +#define ICON_BLTouch 78 +#define ICON_TempTooLow 79 +#define ICON_AutoLeveling 80 +#define ICON_TempTooHigh 81 +#define ICON_NoTips_C 82 +#define ICON_NoTips_E 83 +#define ICON_Continue_C 84 +#define ICON_Continue_E 85 +#define ICON_Cancel_C 86 +#define ICON_Cancel_E 87 +#define ICON_Confirm_C 88 +#define ICON_Confirm_E 89 +#define ICON_Info_0 90 +#define ICON_Info_1 91 + +// Extra Icons +#define ICON_AdvSet ICON_Language +#define ICON_Brightness ICON_Motion +#define ICON_Cancel ICON_StockConfiguration +#define ICON_CustomPreheat ICON_SetEndTemp +#define ICON_Error ICON_TempTooHigh +#define ICON_ExtrudeMinT ICON_HotendTemp +#define ICON_FilLoad ICON_WriteEEPROM +#define ICON_FilMan ICON_ResumeEEPROM +#define ICON_FilSet ICON_ResumeEEPROM +#define ICON_FilUnload ICON_ReadEEPROM +#define ICON_Flow ICON_StepE +#define ICON_HomeOffset ICON_AdvSet +#define ICON_HomeOffsetX ICON_StepX +#define ICON_HomeOffsetY ICON_StepY +#define ICON_HomeOffsetZ ICON_StepZ +#define ICON_LevBed ICON_SetEndTemp +#define ICON_Lock ICON_Cool +#define ICON_ManualMesh ICON_HotendTemp +#define ICON_MeshNext ICON_Axis +#define ICON_MeshSave ICON_WriteEEPROM +#define ICON_MoveZ0 ICON_HotendTemp +#define ICON_Park ICON_Motion +#define ICON_PIDbed ICON_SetBedTemp +#define ICON_PIDcycles ICON_ResumeEEPROM +#define ICON_PIDNozzle ICON_SetEndTemp +#define ICON_PIDValue ICON_Contact +#define ICON_ProbeOffsetX ICON_StepX +#define ICON_ProbeOffsetY ICON_StepY +#define ICON_ProbeSet ICON_SetEndTemp +#define ICON_ProbeTest ICON_SetEndTemp +#define ICON_Pwrlossr ICON_Motion +#define ICON_Reboot ICON_ResumeEEPROM +#define ICON_Runout ICON_MaxAccE +#define ICON_Scolor ICON_MaxSpeed +#define ICON_SetCustomPreheat ICON_SetEndTemp +#define ICON_Sound ICON_Cool + +/** + * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: + * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 + * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 + */ +#define font6x12 0x00 +#define font8x16 0x01 +#define font10x20 0x02 +#define font12x24 0x03 +#define font14x28 0x04 +#define font16x32 0x05 +#define font20x40 0x06 +#define font24x48 0x07 +#define font28x56 0x08 +#define font32x64 0x09 + +// Extended and default UI Colors +#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 +#define GetRColor(color) ((color >> 11) & 0x1F) +#define GetGColor(color) ((color >> 5) & 0x3F) +#define GetBColor(color) ((color >> 0) & 0x1F) + +#define Color_White 0xFFFF +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_Bg_Red 0xF00F // Red background color +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color + +#define Color_Black 0 +#define Color_Red RGB(31,0,0) +#define Color_Yellow RGB(31,63,0) +#define Color_Green RGB(0,63,0) +#define Color_Aqua RGB(0,63,31) +#define Color_Blue RGB(0,0,31) + +// Default UI Colors +#define Def_Background_Color Color_Bg_Black +#define Def_Cursor_color Rectangle_Color +#define Def_TitleBg_color Color_Bg_Blue +#define Def_TitleTxt_color Color_White +#define Def_Text_Color Color_White +#define Def_Selected_Color Select_Color +#define Def_SplitLine_Color Line_Color +#define Def_Highlight_Color Color_White +#define Def_StatusBg_Color RGB(0,20,20) +#define Def_StatusTxt_Color Color_Yellow +#define Def_PopupBg_color Color_Bg_Window +#define Def_PopupTxt_Color Popup_Text_Color +#define Def_AlertBg_Color Color_Bg_Red +#define Def_AlertTxt_Color Color_Yellow +#define Def_PercentTxt_Color Percent_Color +#define Def_Barfill_Color BarFill_Color +#define Def_Indicator_Color Color_White +#define Def_Coordinate_Color Color_White + +//UI elements defines and constants +#define DWIN_FONT_MENU font8x16 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 +#define DWIN_FONT_ALERT font10x20 +#define STATUS_Y 354 +#define LCD_WIDTH (DWIN_WIDTH / 8) + +constexpr uint16_t TITLE_HEIGHT = 30, // Title bar height + MLINE = 53, // Menu line height + TROWS = (STATUS_Y - TITLE_HEIGHT) / MLINE, // Total rows + MROWS = TROWS - 1, // Other-than-Back + ICOX = 26, // Menu item icon X position + LBLX = 60, // Menu item label X position + VALX = 210, // Menu item value X position + MENU_CHR_W = 8, MENU_CHR_H = 16, // Menu font 8x16 + STAT_CHR_W = 10; + +// Menuitem Y position +#define MYPOS(L) (TITLE_HEIGHT + MLINE * (L)) + +// Menuitem caption Offset +#define CAPOFF ((MLINE - MENU_CHR_H) / 2) + +// Menuitem caption Y position +#define MBASE(L) (MYPOS(L) + CAPOFF) + +// Create and add a MenuItem object to the menu array +#define ADDMENUITEM(V...) DWINUI::MenuItemsAdd(new MenuItemClass(V)) +#define ADDMENUITEM_P(V...) DWINUI::MenuItemsAdd(new MenuItemPtrClass(V)) + +typedef struct { uint16_t left, top, right, bottom; } rect_t; +typedef struct { uint16_t x, y, w, h; } frame_rect_t; + +class TitleClass { +public: + char caption[32] = ""; + uint8_t frameid = 0; + rect_t frame = {0}; + void Draw(); + void SetCaption(const char * const title); + inline void SetCaption(const __FlashStringHelper * title) { SetCaption((char *)title); } + void ShowCaption(const char * const title); + inline void ShowCaption(const __FlashStringHelper * title) { ShowCaption((char *)title); } + void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); + void SetFrame(uint16_t x, uint16_t y, uint16_t w, uint16_t h); + void FrameCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); + void FrameCopy(uint16_t x, uint16_t y, uint16_t h, uint16_t v); +}; +extern TitleClass Title; + +class MenuItemClass { +protected: +public: + uint8_t pos = 0; + uint8_t icon = 0; + char caption[32] = ""; + uint8_t frameid = 0; + rect_t frame = {0}; + void (*onDraw)(MenuItemClass* menuitem, int8_t line) = nullptr; + void (*onClick)() = nullptr; + MenuItemClass() {}; + MenuItemClass(uint8_t cicon, const char * const text=nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); + MenuItemClass(uint8_t cicon, const __FlashStringHelper * text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) : MenuItemClass(cicon, (char*)text, ondraw, onclick){} + MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); + void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); + virtual ~MenuItemClass(){}; + virtual void Draw(int8_t line); +}; + +class MenuItemPtrClass: public MenuItemClass { +public: + void *value = nullptr; + using MenuItemClass::MenuItemClass; + MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val); + MenuItemPtrClass(uint8_t cicon, const __FlashStringHelper * text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemPtrClass(cicon, (char*)text, ondraw, onclick, val){} +}; + +class MenuClass { +public: + int8_t topline = 0; + int8_t selected = 0; + TitleClass MenuTitle; + MenuClass(); + virtual ~MenuClass(){}; + inline int8_t line() { return selected - topline; }; + inline int8_t line(uint8_t pos) {return pos - topline; }; + void Draw(); + void onScroll(bool dir); + void onClick(); + MenuItemClass* SelectedItem(); +}; +extern MenuClass *CurrentMenu; + +namespace DWINUI { + extern xy_int_t cursor; + extern uint16_t pencolor; + extern uint16_t textcolor; + extern uint16_t backcolor; + extern uint8_t font; + + extern void (*onCursorErase)(uint8_t line); + extern void (*onCursorDraw)(uint8_t line); + extern void (*onTitleDraw)(TitleClass* title); + extern void (*onMenuDraw)(MenuClass* menu); + + // DWIN LCD Initialization + void Init(void); + + // Set text/number font + void SetFont(uint8_t cfont); + + // Get font character width + uint8_t Get_font_width(uint8_t cfont); + + // Get font character heigh + uint8_t Get_font_height(uint8_t cfont); + + // Get screen x coodinates from text column + uint16_t ColToX(uint8_t col); + + // Get screen y coodinates from text row + uint16_t RowToY(uint8_t row); + + // Set text/number color + void SetColors(uint16_t fgcolor, uint16_t bgcolor); + void SetTextColor(uint16_t fgcolor); + void SetBackgroundColor(uint16_t bgcolor); + + // Moves cursor to point + // x: abscissa of the display + // y: ordinate of the display + // point: xy coordinate + void MoveTo(int16_t x, int16_t y); + void MoveTo(xy_int_t point); + + // Moves cursor relative to the actual position + // x: abscissa of the display + // y: ordinate of the display + // point: xy coordinate + void MoveBy(int16_t x, int16_t y); + void MoveBy(xy_int_t point); + + // Draw a line from the cursor to xy position + // color: Line segment color + // x/y: End point + inline void LineTo(uint16_t color, uint16_t x, uint16_t y) { + DWIN_Draw_Line(color, cursor.x, cursor.y, x, y); + } + inline void LineTo(uint16_t x, uint16_t y) { + DWIN_Draw_Line(pencolor, cursor.x, cursor.y, x, y); + } + + // Draw an Icon with transparent background from the library ICON + // icon: Icon ID + // x/y: Upper-left point + inline void Draw_Icon(uint8_t icon, uint16_t x, uint16_t y) { + DWIN_ICON_Show(ICON, icon, x, y); + } + + // Draw a positive integer + // bShow: true=display background color; false=don't display background color + // zeroFill: true=zero fill; false=no zero fill + // zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space + // size: Font size + // color: Character color + // bColor: Background color + // iNum: Number of digits + // x/y: Upper-left coordinate + // value: Integer value + inline void Draw_Int(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + DWIN_Draw_IntValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, x, y, value); + } + inline void Draw_Int(uint8_t iNum, uint16_t value) { + DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); + MoveBy(iNum * Get_font_width(font), 0); + } + inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, x, y, value); + } + inline void Draw_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_IntValue(false, true, 0, font, color, backcolor, iNum, x, y, value); + } + inline void Draw_Int(uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_IntValue(true, true, 0, font, color, bColor, iNum, x, y, value); + } + inline void Draw_Int(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_IntValue(true, true, 0, size, color, bColor, iNum, x, y, value); + } + + // Draw a floating point number + // bShow: true=display background color; false=don't display background color + // zeroFill: true=zero fill; false=no zero fill + // zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space + // size: Font size + // color: Character color + // bColor: Background color + // iNum: Number of whole digits + // fNum: Number of decimal digits + // x/y: Upper-left point + // value: Float value + inline void Draw_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + } + inline void Draw_Float(uint8_t iNum, uint8_t fNum, long value) { + DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); + } + inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + } + inline void Draw_Float(uint16_t color, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_FloatValue(false, true, 0, font, color, backcolor, iNum, fNum, x, y, value); + } + inline void Draw_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_FloatValue(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); + } + inline void Draw_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_FloatValue(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); + } + + // Draw a signed floating point number + // bShow: true=display background color; false=don't display background color + // zeroFill: true=zero fill; false=no zero fill + // zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space + // size: Font size + // bColor: Background color + // iNum: Number of whole digits + // fNum: Number of decimal digits + // x/y: Upper-left point + // value: Float value + void Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); + inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, long value) { + Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); + } + inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + } + inline void Draw_Signed_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + Draw_Signed_Float(false, true, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); + } + inline void Draw_Signed_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + Draw_Signed_Float(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); + } + inline void Draw_Signed_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + Draw_Signed_Float(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); + } + + // Draw a char at cursor position + void Draw_Char(const char c); + + // Draw a string at cursor position + // color: Character color + // *string: The string + // rlimit: For draw less chars than string length use rlimit + void Draw_String(const char * const string, uint16_t rlimit = 0xFFFF); + void Draw_String(uint16_t color, const char * const string, uint16_t rlimit = 0xFFFF); + + // Draw a string + // size: Font size + // color: Character color + // bColor: Background color + // x/y: Upper-left coordinate of the string + // *string: The string + inline void Draw_String(uint16_t x, uint16_t y, const char * const string) { + DWIN_Draw_String(false, font, textcolor, backcolor, x, y, string); + } + inline void Draw_String(uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(false, font, textcolor, backcolor, x, y, (char *)title); + } + inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, const char * const string) { + DWIN_Draw_String(false, font, color, backcolor, x, y, string); + } + inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(false, font, color, backcolor, x, y, (char *)title); + } + inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { + DWIN_Draw_String(true, font, color, bgcolor, x, y, string); + } + inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(true, font, color, bgcolor, x, y, (char *)title); + } + inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { + DWIN_Draw_String(true, size, color, bgcolor, x, y, string); + } + inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(true, size, color, bgcolor, x, y, (char *)title); + } + + // Draw a centered string using DWIN_WIDTH + // bShow: true=display background color; false=don't display background color + // size: Font size + // color: Character color + // bColor: Background color + // y: Upper coordinate of the string + // *string: The string + void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string); + inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const __FlashStringHelper *title) { + Draw_CenteredString(bShow, size, color, bColor, y, (char *)title); + } + inline void Draw_CenteredString(uint16_t color, uint16_t bcolor, uint16_t y, const char * const string) { + Draw_CenteredString(true, font, color, bcolor, y, string); + } + inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, const char * const string) { + Draw_CenteredString(false, size, color, backcolor, y, string); + } + inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, const __FlashStringHelper *title) { + Draw_CenteredString(false, size, color, backcolor, y, (char *)title); + } + inline void Draw_CenteredString(uint16_t color, uint16_t y, const char * const string) { + Draw_CenteredString(false, font, color, backcolor, y, string); + } + inline void Draw_CenteredString(uint16_t color, uint16_t y, const __FlashStringHelper *title) { + Draw_CenteredString(false, font, color, backcolor, y, (char *)title); + } + inline void Draw_CenteredString(uint16_t y, const char * const string) { + Draw_CenteredString(false, font, textcolor, backcolor, y, string); + } + inline void Draw_CenteredString(uint16_t y, const __FlashStringHelper *title) { + Draw_CenteredString(false, font, textcolor, backcolor, y, (char *)title); + } + + // Draw a circle + // Color: circle color + // x: the abscissa of the center of the circle + // y: ordinate of the center of the circle + // r: circle radius + void Draw_Circle(uint16_t color, uint16_t x,uint16_t y,uint8_t r); + inline void Draw_Circle(uint16_t color, uint8_t r) { + Draw_Circle(color, cursor.x, cursor.y, r); + } + + // Draw a checkbox + // Color: frame color + // bColor: Background color + // x/y: Upper-left point + // checked : 0 : unchecked, 1 : checked + void Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool checked); + inline void Draw_Checkbox(uint16_t x, uint16_t y, bool checked=false) { + Draw_Checkbox(textcolor, backcolor, x, y, checked); + } + + // Color Interpolator + // val : Interpolator minv..maxv + // minv : Minimum value + // maxv : Maximun value + // color1 : Start color + // color2 : End color + uint16_t ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2); + + // -------------------------- Extra -------------------------------// + + // Draw a circle filled with color + // bcolor: fill color + // x: the abscissa of the center of the circle + // y: ordinate of the center of the circle + // r: circle radius + void Draw_FillCircle(uint16_t bcolor, uint16_t x,uint16_t y,uint8_t r); + inline void Draw_FillCircle(uint16_t bcolor, uint8_t r) { + Draw_FillCircle(bcolor, cursor.x, cursor.y, r); + } + + // Color Interpolator through Red->Yellow->Green->Blue + // val : Interpolator minv..maxv + // minv : Minimum value + // maxv : Maximun value + uint16_t RainbowInt(int16_t val, int16_t minv, int16_t maxv); + + // Write buffer data to the SRAM + // addr: SRAM start address 0x0000-0x7FFF + // length: Bytes to write + // data: address of the buffer with data + inline void WriteToSRAM(uint16_t addr, uint16_t length, uint8_t *data) { + DWIN_WriteToMem(0x5A, addr, length, data); + } + + // Write buffer data to the Flash + // addr: Flash start address 0x0000-0x3FFF + // length: Bytes to write + // data: address of the buffer with data + inline void WriteToFlash(uint16_t addr, uint16_t length, uint8_t *data) { + DWIN_WriteToMem(0xA5, addr, length, data); + } + + // Clear Menu by filling the area with background color + // Area (0, TITLE_HEIGHT, DWIN_WIDTH, STATUS_Y - 1) + void ClearMenuArea(); + + // Clear MenuItems array and free MenuItems elements + void MenuItemsClear(); + + // Prepare MenuItems array + void MenuItemsPrepare(uint8_t totalitems); + + // Add elements to the MenuItems array + MenuItemClass* MenuItemsAdd(MenuItemClass* menuitem); + +}; diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp new file mode 100644 index 0000000000..2615a05881 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp @@ -0,0 +1,69 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + +#include "../../../core/types.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin.h" +#include "lockscreen.h" + +LockScreenClass LockScreen; + +void LockScreenClass::Init() { + Lock_Pos = 0; + unlocked = false; + Draw(); +} + +void LockScreenClass::Draw() { + Title.SetCaption(PSTR("Lock Screen")); + DWINUI::ClearMenuArea(); + DWINUI::Draw_Icon(ICON_LOGO, 71, 120); // CREALITY logo + DWINUI::Draw_CenteredString(Color_White, 180, F("Printer is Locked,")); + DWINUI::Draw_CenteredString(Color_White, 200, F("Scroll to unlock.")); + DWINUI::Draw_CenteredString(Color_White, 240, F("-> | <-")); + DWIN_Draw_Box(1, HMI_data.Barfill_Color, 0, 260, DWIN_WIDTH, 20); + DWIN_Draw_VLine(Color_Yellow, Lock_Pos * DWIN_WIDTH / 255, 260, 20); + DWIN_UpdateLCD(); +} + +void LockScreenClass::onEncoderState(ENCODER_DiffState encoder_diffState) { + if (encoder_diffState == ENCODER_DIFF_CW) { + Lock_Pos += 8; + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + Lock_Pos -= 8; + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + unlocked = (Lock_Pos == 128); + } + DWIN_Draw_Box(1, HMI_data.Barfill_Color, 0, 260, DWIN_WIDTH, 20); + DWIN_Draw_VLine(Color_Yellow, Lock_Pos * DWIN_WIDTH / 255, 260, 20); + DWIN_UpdateLCD(); +} + +bool LockScreenClass::isUnlocked() { return unlocked; } + +#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h new file mode 100644 index 0000000000..32a0cc3e5a --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h @@ -0,0 +1,35 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../core/types.h" + +class LockScreenClass { +private: + uint8_t Lock_Pos = 0; + bool unlocked = false; +public: + void Init(); + void onEncoderState(ENCODER_DiffState encoder_diffState); + void Draw(); + bool isUnlocked(); +}; +extern LockScreenClass LockScreen; diff --git a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp new file mode 100644 index 0000000000..4f815fdee0 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp @@ -0,0 +1,261 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +/***************************************************************************** + * @file lcd/e3v2/enhanced/rotary_encoder.cpp + * @author LEO / Creality3D + * @date 2019/07/06 + * @version 2.0.1 + * @brief Rotary encoder functions + *****************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + +#include "rotary_encoder.h" +#include "../../buttons.h" + +#include "../../../MarlinCore.h" +#include "../../../HAL/shared/Delay.h" + +#if HAS_BUZZER + #include "../../../libs/buzzer.h" +#endif + +#include + +#ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP 4 +#endif + +#if ENABLED(SOUND_MENU_ITEM) + #include "../../marlinui.h" +#endif + +ENCODER_Rate EncoderRate; + +// Buzzer +void Encoder_tick() { + #if PIN_EXISTS(BEEPER) + if (TERN1(SOUND_MENU_ITEM, ui.buzzer_enabled)) { + WRITE(BEEPER_PIN, HIGH); + delay(10); + WRITE(BEEPER_PIN, LOW); + } + #endif +} + +// Encoder initialization +void Encoder_Configuration() { + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if PIN_EXISTS(BEEPER) + SET_OUTPUT(BEEPER_PIN); + #endif +} + +// Analyze encoder value and return state +ENCODER_DiffState Encoder_ReceiveAnalyze() { + const millis_t now = millis(); + static uint8_t lastEncoderBits; + uint8_t newbutton = 0; + static signed char temp_diff = 0; + + ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (BUTTON_PRESSED(ENC)) { + static millis_t next_click_update_ms; + if (ELAPSED(now, next_click_update_ms)) { + next_click_update_ms = millis() + 300; + Encoder_tick(); + #if PIN_EXISTS(LCD_LED) + //LED_Action(); + #endif + const bool was_waiting = wait_for_user; + wait_for_user = false; + return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; + } + else return ENCODER_DIFF_NO; + } + if (newbutton != lastEncoderBits) { + switch (newbutton) { + case ENCODER_PHASE_0: + if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; + break; + case ENCODER_PHASE_1: + if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; + break; + case ENCODER_PHASE_2: + if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; + break; + case ENCODER_PHASE_3: + if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; + else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; + break; + } + lastEncoderBits = newbutton; + } + + if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { + if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; + else temp_diffState = ENCODER_DIFF_CCW; + + #if ENABLED(ENCODER_RATE_MULTIPLIER) + + millis_t ms = millis(); + int32_t encoderMultiplier = 1; + + // if must encoder rati multiplier + if (EncoderRate.enabled) { + const float abs_diff = ABS(temp_diff), + encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.lastEncoderTime) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the temp_diff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + } + EncoderRate.lastEncoderTime = ms; + } + + #else + + constexpr int32_t encoderMultiplier = 1; + + #endif + + // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; + + temp_diff = 0; + } + return temp_diffState; +} + +#if PIN_EXISTS(LCD_LED) + + // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 + uint16_t LED_DataArray[LED_NUM]; + + // LED light operation + void LED_Action() { + LED_Control(RGB_SCALE_WARM_WHITE,0x0F); + delay(30); + LED_Control(RGB_SCALE_WARM_WHITE,0x00); + } + + // LED initialization + void LED_Configuration() { + SET_OUTPUT(LCD_LED_PIN); + } + + // LED write data + void LED_WriteData() { + uint8_t tempCounter_LED, tempCounter_Bit; + for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { + for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { + if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { + LED_DATA_HIGH; + DELAY_NS(300); + LED_DATA_LOW; + DELAY_NS(200); + } + else { + LED_DATA_HIGH; + LED_DATA_LOW; + DELAY_NS(200); + } + } + } + } + + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance) { + for (uint8_t i = 0; i < LED_NUM; i++) { + LED_DataArray[i] = 0; + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 5/10; break; + case RGB_SCALE_R10_G7_B4: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 4/10; break; + case RGB_SCALE_R10_G8_B7: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 8/10) << 16 | luminance * 7/10; break; + } + } + LED_WriteData(); + } + + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval) { + struct { uint8_t g, r, b; } led_data[LED_NUM]; + for (uint8_t i = 0; i < LED_NUM; i++) { + switch (RGB_Scale) { + case RGB_SCALE_R10_G7_B5: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 5/10 }; + break; + case RGB_SCALE_R10_G7_B4: + led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 4/10 }; + break; + case RGB_SCALE_R10_G8_B7: + led_data[i] = { luminance * 8/10, luminance * 10/10, luminance * 7/10 }; + break; + } + } + + struct { bool g, r, b; } led_flag = { false, false, false }; + for (uint8_t i = 0; i < LED_NUM; i++) { + while (1) { + const uint8_t g = uint8_t(LED_DataArray[i] >> 16), + r = uint8_t(LED_DataArray[i] >> 8), + b = uint8_t(LED_DataArray[i]); + if (g == led_data[i].g) led_flag.g = true; + else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; + if (r == led_data[i].r) led_flag.r = true; + else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; + if (b == led_data[i].b) led_flag.b = true; + else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; + LED_WriteData(); + if (led_flag.r && led_flag.g && led_flag.b) break; + delay(change_Interval); + } + } + } + +#endif // LCD_LED + +#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h new file mode 100644 index 0000000000..c500cfe5bb --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h @@ -0,0 +1,93 @@ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.1 + * Date: 2021/08/29 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/***************************************************************************** + * @file lcd/e3v2/enhanced/rotary_encoder.h + * @author LEO / Creality3D + * @date 2019/07/06 + * @version 2.0.1 + * @brief Rotary encoder functions + ****************************************************************************/ + +#include "../../../inc/MarlinConfig.h" + +/*********************** Encoder Set ***********************/ + +typedef struct { + bool enabled = false; + int encoderMoveValue = 0; + millis_t lastEncoderTime = 0; +} ENCODER_Rate; + +extern ENCODER_Rate EncoderRate; + +typedef enum { + ENCODER_DIFF_NO = 0, // no state + ENCODER_DIFF_CW = 1, // clockwise rotation + ENCODER_DIFF_CCW = 2, // counterclockwise rotation + ENCODER_DIFF_ENTER = 3 // click +} ENCODER_DiffState; + +// Encoder initialization +void Encoder_Configuration(); + +// Analyze encoder value and return state +ENCODER_DiffState Encoder_ReceiveAnalyze(); + +/*********************** Encoder LED ***********************/ + +#if PIN_EXISTS(LCD_LED) + + #define LED_NUM 4 + #define LED_DATA_HIGH WRITE(LCD_LED_PIN, 1) + #define LED_DATA_LOW WRITE(LCD_LED_PIN, 0) + + #define RGB_SCALE_R10_G7_B5 1 + #define RGB_SCALE_R10_G7_B4 2 + #define RGB_SCALE_R10_G8_B7 3 + #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 + #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 + #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 + + extern unsigned int LED_DataArray[LED_NUM]; + + // LED light operation + void LED_Action(); + + // LED initialization + void LED_Configuration(); + + // LED write data + void LED_WriteData(); + + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance); + + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) + void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval); + +#endif // LCD_LED diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h index 18b7c34744..9f8bd25295 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -44,9 +44,6 @@ // Handshake (1: Success, 0: Fail) bool DWIN_Handshake(void); -// Common DWIN startup -void DWIN_Startup(void); - // Set the backlight luminance // luminance: (0x00-0xFF) void DWIN_Backlight_SetLuminance(const uint8_t luminance); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index bddddb75bf..11c976ee41 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -78,6 +78,14 @@ namespace Language_en { PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; + PROGMEM Language_Str MSG_FILAMENT_SET = _UxGT("Filament Settings"); + PROGMEM Language_Str MSG_FILAMENT_MAN = _UxGT("Filament Management"); + PROGMEM Language_Str MSG_LEVBED_FL = _UxGT("Front Left"); + PROGMEM Language_Str MSG_LEVBED_FR = _UxGT("Front Right"); + PROGMEM Language_Str MSG_LEVBED_C = _UxGT("Center"); + PROGMEM Language_Str MSG_LEVBED_BL = _UxGT("Back Left"); + PROGMEM Language_Str MSG_LEVBED_BR = _UxGT("Back Right"); + PROGMEM Language_Str MSG_MANUAL_MESH = _UxGT("Manual Mesh"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); @@ -289,6 +297,11 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Move 1.0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); + PROGMEM Language_Str MSG_MAXSPEED = _UxGT("Max Speed (mm/s)"); + PROGMEM Language_Str MSG_MAXSPEED_X = _UxGT("Max ") LCD_STR_A _UxGT(" Speed"); + PROGMEM Language_Str MSG_MAXSPEED_Y = _UxGT("Max ") LCD_STR_B _UxGT(" Speed"); + PROGMEM Language_Str MSG_MAXSPEED_Z = _UxGT("Max ") LCD_STR_C _UxGT(" Speed"); + PROGMEM Language_Str MSG_MAXSPEED_E = _UxGT("Max ") LCD_STR_E _UxGT(" Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); @@ -321,7 +334,7 @@ namespace Language_en { 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_CYCLE = _UxGT("PID Cycle"); + PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("PID Cycles"); PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); @@ -504,6 +517,7 @@ namespace Language_en { 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("Home %s%s%s First"); + PROGMEM Language_Str MSG_ZPROBE_SETTINGS = _UxGT("Probe Settings"); PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); @@ -611,6 +625,7 @@ namespace Language_en { 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("Runout Dist mm"); + PROGMEM Language_Str MSG_RUNOUT_ENABLE = _UxGT("Enable Runout"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 51cbf4534f..8c59500574 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -48,6 +48,8 @@ MarlinUI ui; #if ENABLED(DWIN_CREALITY_LCD) #include "e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "e3v2/enhanced/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "e3v2/jyersui/dwin.h" #endif @@ -101,6 +103,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; backlight = !!value; if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); // Set brightness on enabled LCD here + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_LCD_Brightness(brightness)); TERN_(DWIN_CREALITY_LCD_JYERSUI, DWIN_Backlight_SetLuminance(backlight ? brightness : 0)); } #endif @@ -1474,7 +1477,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); - TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_StatusChanged(status_message)); TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 268d018508..d3a3c9d521 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -55,11 +55,17 @@ #include "../module/printcounter.h" #endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) +#if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) #include "../feature/pause.h" #include "../module/motion.h" // for active_extruder #endif +#if ENABLED(DWIN_CREALITY_LCD) + #include "e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "e3v2/enhanced/dwin.h" +#endif + #define START_OF_UTF8_CHAR(C) (((C) & 0xC0u) != 0x80U) #if HAS_WIRED_LCD @@ -257,7 +263,7 @@ public: FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } #endif - #if ENABLED(DWIN_CREALITY_LCD) + #if HAS_DWIN_E3V2_BASIC static void refresh(); #else FORCE_INLINE static void refresh() { @@ -315,7 +321,7 @@ public: #if HAS_STATUS_MESSAGE - #if HAS_WIRED_LCD + #if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) #if ENABLED(STATUS_MESSAGE_SCROLLING) #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) #else @@ -351,6 +357,12 @@ public: static inline void reset_alert_level() {} #endif + #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) + static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); + #else + static inline void kill_screen(PGM_P const, PGM_P const) {} + #endif + #if HAS_DISPLAY static void init(); @@ -457,7 +469,6 @@ public: static bool did_first_redraw; #endif - static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); static void draw_kill_screen(); #else // No LCD @@ -585,7 +596,7 @@ public: static inline bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static inline void _pause_show_message() {} diff --git a/Marlin/src/lcd/tft/ui_common.h b/Marlin/src/lcd/tft/ui_common.h index 617447a181..759712b64c 100644 --- a/Marlin/src/lcd/tft/ui_common.h +++ b/Marlin/src/lcd/tft/ui_common.h @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if !HAS_LCD_MENU +#if ENABLED(NO_LCD_MENUS) #error "Seriously? High resolution TFT screen without menu?" #endif diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index cbadda2eef..a4469bb209 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -79,6 +79,8 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) @@ -295,7 +297,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); - + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, PSTR("Stow Probe"), CONTINUE_STR)); wait_for_user_response(); ui.reset_status(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index f2d2aeee92..c24a63ee51 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -71,9 +71,9 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#endif - -#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "../lcd/e3v2/jyersui/dwin.h" #endif @@ -441,14 +441,15 @@ typedef struct SettingsDataStruct { // EXTENSIBLE_UI // #if ENABLED(EXTENSIBLE_UI) - // This is a significant hardware change; don't reserve space when not present uint8_t extui_data[ExtUI::eeprom_data_size]; #endif // - // DWIN_CREALITY_LCD_JYERSUI + // Ender-3 V2 DWIN // - #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + uint8_t dwin_data[eeprom_data_size]; + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) uint8_t dwin_settings[CrealityDWIN.eeprom_data_size]; #endif @@ -1358,9 +1359,16 @@ void MarlinSettings::postprocess() { #endif // - // Creality UI Settings + // Creality DWIN User Data // - #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + { + char dwin_data[eeprom_data_size] = { 0 }; + DWIN_StoreSettings(dwin_data); + _FIELD_TEST(dwin_data); + EEPROM_WRITE(dwin_data); + } + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) { char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; CrealityDWIN.Save_Settings(dwin_settings); @@ -1488,6 +1496,8 @@ void MarlinSettings::postprocess() { stored_ver[1] = '\0'; } DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); + TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status(GET_TEXT(MSG_ERR_EEPROM_VERSION))); + IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); eeprom_error = true; } @@ -2249,9 +2259,16 @@ void MarlinSettings::postprocess() { #endif // - // Creality UI Settings + // Creality DWIN User Data // - #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + { + const char dwin_data[eeprom_data_size] = { 0 }; + _FIELD_TEST(dwin_data); + EEPROM_READ(dwin_data); + if (!validating) DWIN_LoadSettings(dwin_data); + } + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) { const char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; _FIELD_TEST(dwin_settings); @@ -2340,6 +2357,7 @@ void MarlinSettings::postprocess() { else if (working_crc != stored_crc) { eeprom_error = true; DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); + TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status(GET_TEXT(MSG_ERR_EEPROM_CRC))); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } else if (!validating) { @@ -2656,7 +2674,7 @@ void MarlinSettings::reset() { #endif TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); - + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_SetDataDefaults()); TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Reset_Settings()); // diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 935de772f4..1bb86ed4c7 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -47,6 +47,8 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "../lcd/e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" #endif #if ENABLED(EXTENSIBLE_UI) @@ -603,10 +605,12 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_STARTED)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(isbed ? PID_BED_START : PID_EXTR_START)); if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); return; } @@ -627,6 +631,7 @@ volatile bool Temperature::raw_temps_ready = false; // PID Tuning loop wait_for_heatup = true; // Can be interrupted with M108 + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT), "Wait for heat up...")); while (wait_for_heatup) { const millis_t ms = millis(); @@ -687,6 +692,7 @@ volatile bool Temperature::raw_temps_ready = false; } } SHV((bias + d) >> 1); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); cycles++; minT = target; } @@ -699,6 +705,7 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); break; } @@ -734,6 +741,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if ((ms - _MIN(t1, t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TUNING_TIMEOUT)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -787,6 +795,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_DONE)); goto EXIT_M303; } @@ -795,7 +804,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAL_IDLETASK, HAL_idletask()); // Run UI update - TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); + TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); } wait_for_heatup = false; @@ -804,6 +813,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_DONE)); EXIT_M303: TERN_(NO_FAN_SLOWING_IN_PID_TUNING, adaptive_fan_slowing = true); @@ -1014,14 +1024,14 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms } void Temperature::max_temp_error(const heater_id_t heater_id) { - #if ENABLED(DWIN_CREALITY_LCD) && (HAS_HOTEND || HAS_HEATED_BED) + #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(1); #endif _temp_error(heater_id, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); } void Temperature::min_temp_error(const heater_id_t heater_id) { - #if ENABLED(DWIN_CREALITY_LCD) && (HAS_HOTEND || HAS_HEATED_BED) + #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(0); #endif _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); @@ -1329,7 +1339,7 @@ void Temperature::manage_heater() { if (watch_hotend[e].check(degHotend(e))) // Increased enough? start_watching_hotend(e); // If temp reached, turn off elapsed check else { - TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); _temp_error((heater_id_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } } @@ -1372,7 +1382,7 @@ void Temperature::manage_heater() { if (watch_bed.check(degBed())) // Increased enough? start_watching_bed(); // If temp reached, turn off elapsed check else { - TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); _temp_error(H_BED, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } } @@ -2586,7 +2596,7 @@ void Temperature::init() { state = TRRunaway; case TRRunaway: - TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); } } @@ -3600,7 +3610,7 @@ void Temperature::isr() { #if HAS_MULTI_HOTEND PSTR("E%c " S_FMT), '1' + e #else - PSTR("E " S_FMT) + PSTR("E1 " S_FMT) #endif , heating ? GET_TEXT(MSG_HEATING) : GET_TEXT(MSG_COOLING) ); @@ -3720,13 +3730,12 @@ void Temperature::isr() { if (wait_for_heatup) { wait_for_heatup = false; - #if ENABLED(DWIN_CREALITY_LCD) + #if HAS_DWIN_E3V2_BASIC HMI_flag.heat_flag = 0; duration_t elapsed = print_job_timer.duration(); // print timer dwin_heat_time = elapsed.value; - #else - ui.reset_status(); #endif + ui.reset_status(); TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onHeatingDone()); return true; } diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 9f923b4ea9..48d38e2213 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -148,7 +148,7 @@ * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. */ - #error "DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. Comment out this line to continue." + #error "Ender-3 V2 display requires a custom cable, see diagram above this line. Comment out this line to continue." #define BEEPER_PIN EXP1_9 #define BTN_EN1 EXP1_3 diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index c0bc81a3ef..832cfa405f 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -33,6 +33,8 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "../lcd/e3v2/creality/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../lcd/e3v2/enhanced/dwin.h" #endif #include "../module/planner.h" // for synchronize @@ -564,7 +566,7 @@ void CardReader::startOrResumeFilePrinting() { // void CardReader::endFilePrintNow(TERN_(SD_RESORT, const bool re_sort/*=false*/)) { TERN_(ADVANCED_PAUSE_FEATURE, did_pause_print = 0); - TERN_(DWIN_CREALITY_LCD, HMI_flag.print_finish = flag.sdprinting); + TERN_(HAS_DWIN_E3V2_BASIC, HMI_flag.print_finish = flag.sdprinting); flag.abort_sd_printing = false; if (isFileOpen()) file.close(); TERN_(SD_RESORT, if (re_sort) presort()); diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index 0ad66bfdb9..277a68411d 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -13,6 +13,11 @@ use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" +use_example_configs "Creality/Ender-3 V2/CrealityUI" +opt_disable DWIN_CREALITY_LCD +opt_enable DWIN_CREALITY_LCD_ENHANCED +exec_test $1 $2 "Ender 3 v2 with Enhanced UI" "$3" + use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_disable DWIN_CREALITY_LCD opt_enable DWIN_CREALITY_LCD_JYERSUI diff --git a/ini/features.ini b/ini/features.ini index acadd7763a..6ad375e594 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -45,6 +45,7 @@ I2C_EEPROM = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ +DWIN_CREALITY_LCD_ENHANCED = src_filter=+ DWIN_CREALITY_LCD_JYERSUI = src_filter=+ DWIN_MARLINUI_.+ = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 23ee15d98b..5502069800 100644 --- a/platformio.ini +++ b/platformio.ini @@ -50,7 +50,7 @@ lib_deps = default_src_filter = + - - + - - - - - - - - - - - + - - - - - - - - - - From 7a2515bcac682ffc0e5afddaa663910e4f305cb5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 8 Sep 2021 00:57:48 +0000 Subject: [PATCH 0646/2168] [cron] Bump distribution date (2021-09-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d11b20166e..41584fb772 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-07" +//#define STRING_DISTRIBUTION_DATE "2021-09-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3139e96475..c2c9e4ff6f 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 "2021-09-07" + #define STRING_DISTRIBUTION_DATE "2021-09-08" #endif /** From 7a4f1c410f15a5204264b2fc027ac5e04c9f0d97 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 9 Sep 2021 01:01:56 +0000 Subject: [PATCH 0647/2168] [cron] Bump distribution date (2021-09-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 41584fb772..54926116e7 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-08" +//#define STRING_DISTRIBUTION_DATE "2021-09-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c2c9e4ff6f..427343637a 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 "2021-09-08" + #define STRING_DISTRIBUTION_DATE "2021-09-09" #endif /** From 650e73af27eab6c185337c3fc2c44300a9262af8 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 9 Sep 2021 18:13:01 +1200 Subject: [PATCH 0648/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Enhanced=20E3V2?= =?UTF-8?q?=20Advanced=20Pause=20(#22728)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 6de8dc9860..c45995aba5 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2953,7 +2953,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH From 79c72ed821564507b0ef46cbb26f9577585e2ccc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 7 Sep 2021 18:06:10 -0500 Subject: [PATCH 0649/2168] =?UTF-8?q?=F0=9F=8E=A8=20Standardize=20G-code?= =?UTF-8?q?=20reporting?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/pinsDebug.h | 10 +- Marlin/src/core/language.h | 47 +- Marlin/src/core/types.h | 2 + Marlin/src/feature/fwretract.cpp | 11 +- Marlin/src/feature/fwretract.h | 6 +- Marlin/src/gcode/bedlevel/M420.cpp | 14 + Marlin/src/gcode/calibrate/G34_M422.cpp | 34 +- Marlin/src/gcode/calibrate/M425.cpp | 18 + Marlin/src/gcode/calibrate/M665.cpp | 36 + Marlin/src/gcode/calibrate/M666.cpp | 68 +- Marlin/src/gcode/calibrate/M852.cpp | 34 +- Marlin/src/gcode/config/M200-M205.cpp | 142 ++- Marlin/src/gcode/config/M217.cpp | 73 +- Marlin/src/gcode/config/M218.cpp | 29 +- Marlin/src/gcode/config/M281.cpp | 37 +- Marlin/src/gcode/config/M301.cpp | 63 +- Marlin/src/gcode/config/M304.cpp | 14 +- Marlin/src/gcode/config/M305.cpp | 4 +- Marlin/src/gcode/config/M309.cpp | 13 +- Marlin/src/gcode/config/M575.cpp | 6 +- Marlin/src/gcode/config/M92.cpp | 73 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 4 +- Marlin/src/gcode/control/M211.cpp | 18 +- Marlin/src/gcode/feature/advance/M900.cpp | 13 + .../src/gcode/feature/controllerfan/M710.cpp | 24 +- .../src/gcode/feature/digipot/M907-M910.cpp | 42 +- .../src/gcode/feature/fwretract/M207-M209.cpp | 25 + .../src/gcode/feature/network/M552-M554.cpp | 36 +- Marlin/src/gcode/feature/pause/M603.cpp | 18 + Marlin/src/gcode/feature/powerloss/M413.cpp | 13 +- Marlin/src/gcode/feature/runout/M412.cpp | 12 + Marlin/src/gcode/feature/trinamic/M569.cpp | 62 ++ Marlin/src/gcode/feature/trinamic/M906.cpp | 95 ++ .../src/gcode/feature/trinamic/M911-M914.cpp | 160 +++ Marlin/src/gcode/gcode.cpp | 20 +- Marlin/src/gcode/gcode.h | 81 +- Marlin/src/gcode/geometry/M206_M428.cpp | 38 +- Marlin/src/gcode/lcd/M145.cpp | 19 + Marlin/src/gcode/lcd/M250.cpp | 12 +- Marlin/src/gcode/lcd/M256.cpp | 11 +- Marlin/src/gcode/lcd/M414.cpp | 7 + Marlin/src/gcode/parser.h | 17 +- Marlin/src/gcode/probe/M851.cpp | 31 +- Marlin/src/gcode/units/M149.cpp | 7 + Marlin/src/module/endstops.cpp | 4 +- Marlin/src/module/settings.cpp | 994 +++--------------- Marlin/src/module/temperature.cpp | 31 +- Marlin/src/module/temperature.h | 2 +- 48 files changed, 1360 insertions(+), 1170 deletions(-) diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 6923e1f902..50da32292b 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -235,7 +235,7 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); inline void com_print(const uint8_t N, const uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); - SERIAL_ECHOPAIR(" COM", AS_CHAR('0' + N)); + SERIAL_ECHOPAIR(" COM", AS_DIGIT(N)); SERIAL_CHAR(Z); SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03)); } @@ -247,7 +247,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1)))); if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1); - SERIAL_ECHOPAIR(" TIMER", AS_CHAR(T + '0')); + SERIAL_ECHOPAIR(" TIMER", AS_DIGIT(T)); SERIAL_CHAR(L); SERIAL_ECHO_SP(3); @@ -262,11 +262,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - SERIAL_ECHOPAIR(" WGM: ", WGM); com_print(T,L); SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) )); - SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "A: ", *TCCRA); - SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "B: ", *TCCRB); + SERIAL_ECHOPAIR(" TCCR", AS_DIGIT(T), "A: ", *TCCRA); + SERIAL_ECHOPAIR(" TCCR", AS_DIGIT(T), "B: ", *TCCRB); const uint8_t *TMSK = (uint8_t*)TIMSK(T); - SERIAL_ECHOPAIR(" TIMSK", AS_CHAR(T + '0'), ": ", *TMSK); + SERIAL_ECHOPAIR(" TIMSK", AS_DIGIT(T), ": ", *TMSK); const uint8_t OCIE = L - 'A' + 1; if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); } diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 8de8397593..3341656671 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -158,9 +158,7 @@ #define STR_OFF "OFF" #define STR_ENDSTOP_HIT "TRIGGERED" #define STR_ENDSTOP_OPEN "open" -#define STR_HOTEND_OFFSET "Hotend offsets:" #define STR_DUPLICATION_MODE "Duplication mode: " -#define STR_SOFT_ENDSTOPS "Soft endstops: " #define STR_SOFT_MIN " Min: " #define STR_SOFT_MAX " Max: " @@ -262,6 +260,49 @@ #define STR_REMINDER_SAVE_SETTINGS "Remember to save!" #define STR_PASSWORD_SET "Password is " +// Settings Report Strings +#define STR_Z_AUTO_ALIGN "Z Auto-Align" +#define STR_BACKLASH_COMPENSATION "Backlash compensation" +#define STR_DELTA_SETTINGS "Delta settings (L R H S XYZ ABC)" +#define STR_SCARA_SETTINGS "SCARA settings" +#define STR_SCARA_S "S" +#define STR_SCARA_P_T_Z "P T Z" +#define STR_ENDSTOP_ADJUSTMENT "Endstop adjustment" +#define STR_SKEW_FACTOR "Skew Factor" +#define STR_FILAMENT_SETTINGS "Filament settings" +#define STR_MAX_ACCELERATION "Max Acceleration (units/s2)" +#define STR_MAX_FEEDRATES "Max feedrates (units/s)" +#define STR_ACCELERATION_P_R_T "Acceleration (units/s2) (P R T)" +#define STR_TOOL_CHANGING "Tool-changing" +#define STR_HOTEND_OFFSETS "Hotend offsets" +#define STR_SERVO_ANGLES "Servo Angles" +#define STR_HOTEND_PID "Hotend PID" +#define STR_BED_PID "Bed PID" +#define STR_CHAMBER_PID "Chamber PID" +#define STR_STEPS_PER_UNIT "Steps per unit" +#define STR_LINEAR_ADVANCE "Linear Advance" +#define STR_CONTROLLER_FAN "Controller Fan" +#define STR_STEPPER_MOTOR_CURRENTS "Stepper motor currents" +#define STR_RETRACT_S_F_Z "Retract (S F Z)" +#define STR_RECOVER_S_F "Recover (S F)" +#define STR_AUTO_RETRACT_S "Auto-Retract (S)" +#define STR_FILAMENT_LOAD_UNLOAD "Filament load/unload" +#define STR_POWER_LOSS_RECOVERY "Power-loss recovery" +#define STR_FILAMENT_RUNOUT_SENSOR "Filament runout sensor" +#define STR_DRIVER_STEPPING_MODE "Driver stepping mode" +#define STR_STEPPER_DRIVER_CURRENT "Stepper driver current" +#define STR_HYBRID_THRESHOLD "Hybrid Threshold" +#define STR_STALLGUARD_THRESHOLD "StallGuard threshold" +#define STR_HOME_OFFSET "Home offset" +#define STR_SOFT_ENDSTOPS "Soft endstops" +#define STR_MATERIAL_HEATUP "Material heatup parameters" +#define STR_LCD_CONTRAST "LCD Contrast" +#define STR_LCD_BRIGHTNESS "LCD Brightness" +#define STR_UI_LANGUAGE "UI Language" +#define STR_Z_PROBE_OFFSET "Z-Probe Offset" +#define STR_TEMPERATURE_UNITS "Temperature Units" +#define STR_USER_THERMISTORS "User thermistors" + // // Endstop Names used by Endstops::report_states // @@ -290,7 +331,7 @@ #define STR_Z_PROBE "z_probe" #define STR_PROBE_EN "probe_en" -#define STR_FILAMENT_RUNOUT_SENSOR "filament" +#define STR_FILAMENT "filament" // General axis names #define STR_X "X" diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 833167a7a1..372b4b1e66 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -55,6 +55,8 @@ struct IF { typedef L type; }; #define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k) #define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) +#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) + #if HAS_EXTRUDERS #define LIST_ITEM_E(N) , N #define CODE_ITEM_E(N) ; N diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 41dbf430e8..71630d30ac 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -36,7 +36,7 @@ FWRetract fwretract; // Single instance - this calls the constructor #include "../module/planner.h" #include "../module/stepper.h" -#include "../gcode/parser.h" +#include "../gcode/gcode.h" #if ENABLED(RETRACT_SYNC_MIXING) #include "mixing.h" @@ -214,8 +214,7 @@ void FWRetract::M207() { if (parser.seenval('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS); } -void FWRetract::M207_report(const bool forReplay/*=false*/) { - if (!forReplay) { SERIAL_ECHO_MSG("; Retract: S F Z"); SERIAL_ECHO_START(); } +void FWRetract::M207_report() { SERIAL_ECHOLNPAIR_P( PSTR(" M207 S"), LINEAR_UNIT(settings.retract_length) , PSTR(" W"), LINEAR_UNIT(settings.swap_retract_length) @@ -240,8 +239,7 @@ void FWRetract::M208() { if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS); } -void FWRetract::M208_report(const bool forReplay/*=false*/) { - if (!forReplay) { SERIAL_ECHO_MSG("; Recover: S F"); SERIAL_ECHO_START(); } +void FWRetract::M208_report() { SERIAL_ECHOLNPAIR( " M208 S", LINEAR_UNIT(settings.retract_recover_extra) , " W", LINEAR_UNIT(settings.swap_retract_recover_extra) @@ -262,8 +260,7 @@ void FWRetract::M208_report(const bool forReplay/*=false*/) { enable_autoretract(parser.value_bool()); } - void FWRetract::M209_report(const bool forReplay/*=false*/) { - if (!forReplay) { SERIAL_ECHO_MSG("; Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover"); SERIAL_ECHO_START(); } + void FWRetract::M209_report() { SERIAL_ECHOLNPAIR(" M209 S", AS_DIGIT(autoretract_enabled)); } diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index cd93e9cf39..9b0ff19c8b 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -76,13 +76,13 @@ public: static void retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping = false)); + static void M207_report(); static void M207(); - static void M207_report(const bool forReplay=false); + static void M208_report(); static void M208(); - static void M208_report(const bool forReplay=false); #if ENABLED(FWRETRACT_AUTORETRACT) + static void M209_report(); static void M209(); - static void M209_report(const bool forReplay=false); #endif }; diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 703e73b5a4..55055a5b02 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -242,4 +242,18 @@ void GcodeSuite::M420() { report_current_position(); } +void GcodeSuite::M420_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR( + TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) + )); + SERIAL_ECHOPAIR_P( + PSTR(" M420 S"), planner.leveling_active + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) + #endif + , " ; Leveling " + ); + serialprintln_onoff(planner.leveling_active); +} + #endif // HAS_LEVELING diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 50f3419c89..c5f5e582a9 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -475,21 +475,13 @@ void GcodeSuite::G34() { */ void GcodeSuite::M422() { + if (!parser.seen_any()) return M422_report(); + if (parser.seen('R')) { z_stepper_align.reset_to_default(); return; } - if (!parser.seen_any()) { - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) - 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); - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) - 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); - #endif - return; - } - const bool is_probe_point = parser.seen('S'); if (TERN0(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, is_probe_point && parser.seen('W'))) { @@ -545,4 +537,26 @@ void GcodeSuite::M422() { pos_dest[position_index] = pos; } +void GcodeSuite::M422_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_Z_AUTO_ALIGN)); + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + report_echo_start(forReplay); + 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 + ); + } + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + report_echo_start(forReplay); + 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 + ); + } + #endif +} + #endif // Z_STEPPER_AUTO_ALIGN diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index f30de00a0f..9f7e00738b 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -113,4 +113,22 @@ void GcodeSuite::M425() { } } +void GcodeSuite::M425_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_BACKLASH_COMPENSATION)); + SERIAL_ECHOLNPAIR_P( + PSTR(" M425 F"), backlash.get_correction() + #ifdef BACKLASH_SMOOTHING_MM + , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) + #endif + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), + SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), + SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), + SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), + SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), + SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) + ) + ); +} + #endif // BACKLASH_GCODE diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 0d0c4146d9..d4d49d6a6c 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -30,6 +30,7 @@ #if ENABLED(DELTA) #include "../../module/delta.h" + /** * M665: Set delta configurations * @@ -45,6 +46,8 @@ * C = Gamma (Tower 3) diagonal rod trim */ void GcodeSuite::M665() { + if (!parser.seen_any()) return M665_report(); + if (parser.seenval('H')) delta_height = parser.value_linear_units(); if (parser.seenval('L')) delta_diagonal_rod = parser.value_linear_units(); if (parser.seenval('R')) delta_radius = parser.value_linear_units(); @@ -58,6 +61,22 @@ recalc_delta_settings(); } + void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_DELTA_SETTINGS)); + SERIAL_ECHOLNPAIR_P( + PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) + , PSTR(" R"), LINEAR_UNIT(delta_radius) + , PSTR(" H"), LINEAR_UNIT(delta_height) + , PSTR(" S"), segments_per_second + , SP_X_STR, LINEAR_UNIT(delta_tower_angle_trim.a) + , SP_Y_STR, LINEAR_UNIT(delta_tower_angle_trim.b) + , SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c) + , PSTR(" A"), LINEAR_UNIT(delta_diagonal_rod_trim.a) + , PSTR(" B"), LINEAR_UNIT(delta_diagonal_rod_trim.b) + , PSTR(" C"), LINEAR_UNIT(delta_diagonal_rod_trim.c) + ); + } + #elif IS_SCARA #include "../../module/scara.h" @@ -68,6 +87,9 @@ * Parameters: * * S[segments-per-second] - Segments-per-second + * + * Without NO_WORKSPACE_OFFSETS: + * * P[theta-psi-offset] - Theta-Psi offset, added to the shoulder (A/X) angle * T[theta-offset] - Theta offset, added to the elbow (B/Y) angle * Z[z-offset] - Z offset, added to Z @@ -76,6 +98,8 @@ * B, T, and Y are all aliases for the elbow angle */ void GcodeSuite::M665() { + if (!parser.seen_any()) return M665_report(); + if (parser.seenval('S')) segments_per_second = parser.value_float(); #if HAS_SCARA_OFFSET @@ -107,6 +131,18 @@ #endif // HAS_SCARA_OFFSET } + void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_SCARA_S TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); + SERIAL_ECHOLNPAIR_P( + PSTR(" M665 S"), segments_per_second + #if HAS_SCARA_OFFSET + , SP_P_STR, scara_home_offset.a + , SP_T_STR, scara_home_offset.b + , SP_Z_STR, LINEAR_UNIT(scara_home_offset.z) + #endif + ); + } + #endif #endif // IS_KINEMATIC diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 872344e4e9..6e1ebfb5db 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -36,38 +36,6 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" -void M666_report(const bool forReplay=true) { - if (!forReplay) { SERIAL_ECHOLNPGM("; Endstop adjustment:"); SERIAL_ECHO_START(); } - #if ENABLED(DELTA) - SERIAL_ECHOLNPAIR_P( - PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) - , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) - , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) - ); - #else - SERIAL_ECHOPGM(" M666"); - #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - #if NUM_Z_STEPPER_DRIVERS >= 3 - SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - if (!forReplay) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); - #if NUM_Z_STEPPER_DRIVERS >= 4 - if (!forReplay) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); - #endif - #else - SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); - #endif - #endif - #endif -} - #if ENABLED(DELTA) /** @@ -92,6 +60,15 @@ void M666_report(const bool forReplay=true) { if (!is_set) M666_report(); } + void GcodeSuite::M666_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); + SERIAL_ECHOLNPAIR_P( + PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) + , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) + , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) + ); + } + #else /** @@ -105,6 +82,8 @@ void M666_report(const bool forReplay=true) { * Set All: M666 Z */ void GcodeSuite::M666() { + if (!parser.seen_any()) return M666_report(); + #if ENABLED(X_DUAL_ENDSTOPS) if (parser.seenval('X')) endstops.x2_endstop_adj = parser.value_linear_units(); #endif @@ -123,7 +102,30 @@ void M666_report(const bool forReplay=true) { #endif } #endif - if (!parser.seen("XYZ")) M666_report(); + } + + void GcodeSuite::M666_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); + SERIAL_ECHOPGM(" M666"); + #if ENABLED(X_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + #if NUM_Z_STEPPER_DRIVERS >= 3 + SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + report_echo_start(forReplay); + SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + #if NUM_Z_STEPPER_DRIVERS >= 4 + report_echo_start(forReplay); + SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); + #endif + #else + SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); + #endif + #endif } #endif // HAS_EXTRA_ENDSTOPS diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index 73b18ad466..c4361b89f3 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -36,10 +36,11 @@ * K[yz_factor] - New YZ skew factor */ void GcodeSuite::M852() { - uint8_t ijk = 0, badval = 0, setval = 0; + if (!parser.seen("SIJK")) return M852_report(); - if (parser.seen('I') || parser.seen('S')) { - ++ijk; + uint8_t badval = 0, setval = 0; + + if (parser.seenval('I') || parser.seenval('S')) { const float value = parser.value_linear_units(); if (WITHIN(value, SKEW_FACTOR_MIN, SKEW_FACTOR_MAX)) { if (planner.skew_factor.xy != value) { @@ -53,8 +54,7 @@ void GcodeSuite::M852() { #if ENABLED(SKEW_CORRECTION_FOR_Z) - if (parser.seen('J')) { - ++ijk; + if (parser.seenval('J')) { const float value = parser.value_linear_units(); if (WITHIN(value, SKEW_FACTOR_MIN, SKEW_FACTOR_MAX)) { if (planner.skew_factor.xz != value) { @@ -66,8 +66,7 @@ void GcodeSuite::M852() { ++badval; } - if (parser.seen('K')) { - ++ijk; + if (parser.seenval('K')) { const float value = parser.value_linear_units(); if (WITHIN(value, SKEW_FACTOR_MIN, SKEW_FACTOR_MAX)) { if (planner.skew_factor.yz != value) { @@ -90,17 +89,18 @@ void GcodeSuite::M852() { sync_plan_position(); report_current_position(); } +} - if (!ijk) { - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Skew Factor"); - SERIAL_ECHOPAIR_F(" XY: ", planner.skew_factor.xy, 6); - #if ENABLED(SKEW_CORRECTION_FOR_Z) - SERIAL_ECHOPAIR_F(" XZ: ", planner.skew_factor.xz, 6); - SERIAL_ECHOPAIR_F(" YZ: ", planner.skew_factor.yz, 6); - #endif - SERIAL_EOL(); - } +void GcodeSuite::M852_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_SKEW_FACTOR)); + SERIAL_ECHOPAIR_F(" M851 I", planner.skew_factor.xy, 6); + #if ENABLED(SKEW_CORRECTION_FOR_Z) + SERIAL_ECHOPAIR_F(" J", planner.skew_factor.xz, 6); + SERIAL_ECHOPAIR_F(" K", planner.skew_factor.yz, 6); + SERIAL_ECHOLNPGM(" ; XY, XZ, YZ"); + #else + SERIAL_ECHOLNPGM(" ; XY"); + #endif } #endif // SKEW_CORRECTION_GCODE diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index a2bcb8bb86..048a2887e6 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -32,9 +32,14 @@ * T - Optional extruder number. Current extruder if omitted. * D - Set filament diameter and enable. D0 disables volumetric. * S - Turn volumetric ON or OFF. + * + * With VOLUMETRIC_EXTRUDER_LIMIT: + * * L - Volumetric extruder limit (in mm^3/sec). L0 disables the limit. */ void GcodeSuite::M200() { + if (!parser.seen("DST" TERN_(VOLUMETRIC_EXTRUDER_LIMIT, "L"))) + return M200_report(); const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -69,6 +74,37 @@ planner.calculate_volumetric_multipliers(); } + void GcodeSuite::M200_report(const bool forReplay/*=true*/) { + if (!forReplay) { + report_heading(forReplay, PSTR(STR_FILAMENT_SETTINGS), false); + if (!parser.volumetric_enabled) SERIAL_ECHOPGM(" (Disabled):"); + SERIAL_EOL(); + report_echo_start(forReplay); + } + + #if EXTRUDERS == 1 + { + SERIAL_ECHOLNPAIR( + " M200 S", parser.volumetric_enabled, " D", LINEAR_UNIT(planner.filament_size[0]) + #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) + , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) + #endif + ); + } + #else + SERIAL_ECHOLNPAIR(" M200 S", parser.volumetric_enabled); + LOOP_L_N(i, EXTRUDERS) { + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR( + " M200 T", i, " D", LINEAR_UNIT(planner.filament_size[i]) + #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) + , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) + #endif + ); + } + #endif + } + #endif // !NO_VOLUMETRICS /** @@ -77,6 +113,8 @@ * With multiple extruders use T to specify which one. */ void GcodeSuite::M201() { + if (!parser.seen("T" LOGICAL_AXES_STRING)) + return M201_report(); const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -94,12 +132,40 @@ void GcodeSuite::M201() { } } +void GcodeSuite::M201_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_MAX_ACCELERATION)); + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) + #endif + ); + #if ENABLED(DISTINCT_E_FACTORS) + LOOP_L_N(i, E_STEPPERS) { + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR_P( + PSTR(" M201 T"), i + , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) + ); + } + #endif +} + /** * M203: Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in units/sec * * With multiple extruders use T to specify which one. */ void GcodeSuite::M203() { + if (!parser.seen("T" LOGICAL_AXES_STRING)) + return M203_report(); const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -111,6 +177,32 @@ void GcodeSuite::M203() { } } +void GcodeSuite::M203_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_MAX_FEEDRATES)); + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) + #endif + ); + #if ENABLED(DISTINCT_E_FACTORS) + LOOP_L_N(i, E_STEPPERS) { + SERIAL_ECHO_START(); + SERIAL_ECHOLNPAIR_P( + PSTR(" M203 T"), i + , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) + ); + } + #endif +} + /** * M204: Set Accelerations in units/sec^2 (M204 P1200 R3000 T3000) * @@ -119,11 +211,8 @@ void GcodeSuite::M203() { * T = Travel (non printing) moves */ void GcodeSuite::M204() { - if (!parser.seen("PRST")) { - SERIAL_ECHOPAIR("Acceleration: P", planner.settings.acceleration); - SERIAL_ECHOPAIR(" R", planner.settings.retract_acceleration); - SERIAL_ECHOLNPAIR_P(SP_T_STR, planner.settings.travel_acceleration); - } + if (!parser.seen("PRST")) + return M204_report(); else { //planner.synchronize(); // 'S' for legacy compatibility. Should NOT BE USED for new development @@ -134,6 +223,15 @@ void GcodeSuite::M204() { } } +void GcodeSuite::M204_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_ACCELERATION_P_R_T)); + SERIAL_ECHOLNPAIR_P( + PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration) + , PSTR(" R"), LINEAR_UNIT(planner.settings.retract_acceleration) + , SP_T_STR, LINEAR_UNIT(planner.settings.travel_acceleration) + ); +} + /** * M205: Set Advanced Settings * @@ -147,7 +245,8 @@ void GcodeSuite::M204() { * J = Junction Deviation (mm) (If not using CLASSIC_JERK) */ void GcodeSuite::M205() { - if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) return; + if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) + return M205_report(); //planner.synchronize(); if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong(); @@ -184,3 +283,34 @@ void GcodeSuite::M205() { #endif #endif // HAS_CLASSIC_JERK } + +void GcodeSuite::M205_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR( + "Advanced (B S T" + TERN_(HAS_JUNCTION_DEVIATION, " J") + TERN_(HAS_CLASSIC_JERK, " X Y Z") + TERN_(HAS_CLASSIC_E_JERK, " E") + ")" + )); + SERIAL_ECHOLNPAIR_P( + PSTR(" M205 B"), LINEAR_UNIT(planner.settings.min_segment_time_us) + , PSTR(" S"), LINEAR_UNIT(planner.settings.min_feedrate_mm_s) + , SP_T_STR, LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s) + #if HAS_JUNCTION_DEVIATION + , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) + #endif + #if HAS_CLASSIC_JERK + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), + SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), + SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), + SP_I_STR, LINEAR_UNIT(planner.max_jerk.i), + SP_J_STR, LINEAR_UNIT(planner.max_jerk.j), + SP_K_STR, LINEAR_UNIT(planner.max_jerk.k) + ) + #if HAS_CLASSIC_E_JERK + , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e) + #endif + #endif + ); +} diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 2035ae55ab..72b7d16ac0 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -33,44 +33,6 @@ #include "../../MarlinCore.h" // for SP_X_STR, etc. -void M217_report(const bool eeprom=false) { - - #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - SERIAL_ECHOPGM_P(eeprom ? PSTR(" M217") : PSTR("Toolchange:")); - SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length)); - SERIAL_ECHOPAIR_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), - SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), - SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); - SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed), - " U", LINEAR_UNIT(toolchange_settings.unretract_speed), - " F", toolchange_settings.fan_speed, - " G", toolchange_settings.fan_time); - - #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOPAIR(" A", migration.automode); - SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); - #endif - - #if ENABLED(TOOLCHANGE_PARK) - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(toolchange_settings.enable_park)); - SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)); - SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)); - #endif - - #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) - SERIAL_ECHOPAIR(" V", LINEAR_UNIT(enable_first_prime)); - #endif - - #else - - UNUSED(eeprom); - - #endif - - SERIAL_ECHOPAIR_P(SP_Z_STR, LINEAR_UNIT(toolchange_settings.z_raise)); - SERIAL_EOL(); -} - /** * M217 - Set SINGLENOZZLE toolchange parameters * @@ -168,4 +130,39 @@ void GcodeSuite::M217() { M217_report(); } +void GcodeSuite::M217_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_TOOL_CHANGING)); + + SERIAL_ECHOPGM(" M217"); + + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) + SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length)); + SERIAL_ECHOPAIR_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), + SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), + SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); + SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed), + " U", LINEAR_UNIT(toolchange_settings.unretract_speed), + " F", toolchange_settings.fan_speed, + " G", toolchange_settings.fan_time); + + #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) + SERIAL_ECHOPAIR(" A", migration.automode); + SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); + #endif + + #if ENABLED(TOOLCHANGE_PARK) + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(toolchange_settings.enable_park)); + SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)); + SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)); + #endif + + #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) + SERIAL_ECHOPAIR(" V", LINEAR_UNIT(enable_first_prime)); + #endif + + #endif + + SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(toolchange_settings.z_raise)); +} + #endif // HAS_MULTI_EXTRUDER diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index 7701320e9e..249c16622f 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -41,6 +41,8 @@ */ void GcodeSuite::M218() { + if (!parser.seen_any()) return M218_report(); + const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -48,24 +50,23 @@ void GcodeSuite::M218() { if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); - if (!parser.seen("XYZ")) { - SERIAL_ECHO_START(); - SERIAL_ECHOPGM(STR_HOTEND_OFFSET); - HOTEND_LOOP() { - SERIAL_CHAR(' '); - SERIAL_ECHO(hotend_offset[e].x); - SERIAL_CHAR(','); - SERIAL_ECHO(hotend_offset[e].y); - SERIAL_CHAR(','); - SERIAL_ECHO_F(hotend_offset[e].z, 3); - } - SERIAL_EOL(); - } - #if ENABLED(DELTA) if (target_extruder == active_extruder) do_blocking_move_to_xy(current_position, planner.settings.max_feedrate_mm_s[X_AXIS]); #endif } +void GcodeSuite::M218_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_HOTEND_OFFSETS)); + LOOP_S_L_N(e, 1, HOTENDS) { + report_echo_start(forReplay); + SERIAL_ECHOPAIR_P( + PSTR(" M218 T"), e, + SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), + SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) + ); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(hotend_offset[e].z), 3); + } +} + #endif // HAS_HOTEND_OFFSET diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index eeb0fcc470..36b62f5163 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -34,6 +34,7 @@ * U - Stowed Angle */ void GcodeSuite::M281() { + if (!parser.seen_any()) return M281_report(); if (!parser.seenval('P')) return; @@ -45,24 +46,32 @@ void GcodeSuite::M281() { return; } #endif - bool angle_change = false; - if (parser.seen('L')) { - servo_angles[servo_index][0] = parser.value_int(); - angle_change = true; - } - if (parser.seen('U')) { - servo_angles[servo_index][1] = parser.value_int(); - angle_change = true; - } - if (!angle_change) { - SERIAL_ECHO_MSG(" Servo ", servo_index, - " L", servo_angles[servo_index][0], - " U", servo_angles[servo_index][1]); - } + if (parser.seen('L')) servo_angles[servo_index][0] = parser.value_int(); + if (parser.seen('U')) servo_angles[servo_index][1] = parser.value_int(); } else SERIAL_ERROR_MSG("Servo ", servo_index, " out of range"); +} +void GcodeSuite::M281_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_SERVO_ANGLES)); + LOOP_L_N(i, NUM_SERVOS) { + switch (i) { + default: break; + #if ENABLED(SWITCHING_EXTRUDER) + case SWITCHING_EXTRUDER_SERVO_NR: + #if EXTRUDERS > 3 + case SWITCHING_EXTRUDER_E23_SERVO_NR: + #endif + #elif ENABLED(SWITCHING_NOZZLE) + case SWITCHING_NOZZLE_SERVO_NR: + #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) + case Z_PROBE_SERVO_NR: + #endif + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]); + } + } } #endif // EDITABLE_SERVO_ANGLES diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp index 7b3f57608b..904744c958 100644 --- a/Marlin/src/gcode/config/M301.cpp +++ b/Marlin/src/gcode/config/M301.cpp @@ -46,46 +46,63 @@ * F[float] Kf term */ void GcodeSuite::M301() { - // multi-extruder PID patch: M301 updates or prints a single extruder's PID values // default behavior (omitting E parameter) is to update for extruder 0 only - const uint8_t e = parser.byteval('E'); // extruder being updated + int8_t e = parser.byteval('E', -1); // extruder being updated + + if (!parser.seen("PID" TERN_(PID_EXTRUSION_SCALING, "CL") TERN_(PID_FAN_SCALING, "F"))) + return M301_report(true, e); + + if (e == -1) e = 0; if (e < HOTENDS) { // catch bad input value - if (parser.seen('P')) PID_PARAM(Kp, e) = parser.value_float(); - if (parser.seen('I')) PID_PARAM(Ki, e) = scalePID_i(parser.value_float()); - if (parser.seen('D')) PID_PARAM(Kd, e) = scalePID_d(parser.value_float()); + + if (parser.seenval('P')) PID_PARAM(Kp, e) = parser.value_float(); + if (parser.seenval('I')) PID_PARAM(Ki, e) = scalePID_i(parser.value_float()); + if (parser.seenval('D')) PID_PARAM(Kd, e) = scalePID_d(parser.value_float()); + #if ENABLED(PID_EXTRUSION_SCALING) - if (parser.seen('C')) PID_PARAM(Kc, e) = parser.value_float(); + if (parser.seenval('C')) PID_PARAM(Kc, e) = parser.value_float(); if (parser.seenval('L')) thermalManager.lpq_len = parser.value_int(); NOMORE(thermalManager.lpq_len, LPQ_MAX_LEN); NOLESS(thermalManager.lpq_len, 0); #endif #if ENABLED(PID_FAN_SCALING) - if (parser.seen('F')) PID_PARAM(Kf, e) = parser.value_float(); + if (parser.seenval('F')) PID_PARAM(Kf, e) = parser.value_float(); #endif thermalManager.updatePID(); - - SERIAL_ECHO_START(); - #if ENABLED(PID_PARAMS_PER_HOTEND) - SERIAL_ECHOPAIR(" e:", e); // specify extruder in serial output - #endif - SERIAL_ECHOPAIR(" p:", PID_PARAM(Kp, e), - " i:", unscalePID_i(PID_PARAM(Ki, e)), - " d:", unscalePID_d(PID_PARAM(Kd, e))); - #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPAIR(" c:", PID_PARAM(Kc, e)); - #endif - #if ENABLED(PID_FAN_SCALING) - SERIAL_ECHOPAIR(" f:", PID_PARAM(Kf, e)); - #endif - - SERIAL_EOL(); } else SERIAL_ERROR_MSG(STR_INVALID_EXTRUDER); } +void GcodeSuite::M301_report(const bool forReplay/*=true*/, const int8_t eindex/*=-1*/) { + report_heading(forReplay, PSTR(STR_HOTEND_PID)); + HOTEND_LOOP() { + if (e == eindex || eindex == -1) { + report_echo_start(forReplay); + SERIAL_ECHOPAIR_P( + #if ENABLED(PID_PARAMS_PER_HOTEND) + PSTR(" M301 E"), e, SP_P_STR + #else + PSTR(" M301 P") + #endif + , PID_PARAM(Kp, e) + , PSTR(" I"), unscalePID_i(PID_PARAM(Ki, e)) + , PSTR(" D"), unscalePID_d(PID_PARAM(Kd, e)) + ); + #if ENABLED(PID_EXTRUSION_SCALING) + SERIAL_ECHOPAIR_P(SP_C_STR, PID_PARAM(Kc, e)); + if (e == 0) SERIAL_ECHOPAIR(" L", thermalManager.lpq_len); + #endif + #if ENABLED(PID_FAN_SCALING) + SERIAL_ECHOPAIR(" F", PID_PARAM(Kf, e)); + #endif + SERIAL_EOL(); + } + } +} + #endif // PIDTEMP diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp index b1af5a5ae2..05ee4bad80 100644 --- a/Marlin/src/gcode/config/M304.cpp +++ b/Marlin/src/gcode/config/M304.cpp @@ -35,15 +35,19 @@ * D - Set the D value */ void GcodeSuite::M304() { - + if (!parser.seen("PID")) return M304_report(); if (parser.seen('P')) thermalManager.temp_bed.pid.Kp = parser.value_float(); if (parser.seen('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float()); if (parser.seen('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float()); +} - SERIAL_ECHO_MSG(" p:", thermalManager.temp_bed.pid.Kp, - " i:", unscalePID_i(thermalManager.temp_bed.pid.Ki), - " d:", unscalePID_d(thermalManager.temp_bed.pid.Kd)); - +void GcodeSuite::M304_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_BED_PID)); + SERIAL_ECHO_MSG( + " M304 P", thermalManager.temp_bed.pid.Kp + , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) + , " D", unscalePID_d(thermalManager.temp_bed.pid.Kd) + ); } #endif // PIDTEMPBED diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index 10ef55c173..6957eef050 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -70,10 +70,10 @@ void GcodeSuite::M305() { } // If not setting then report parameters else if (t_index < 0) { // ...all user thermistors LOOP_L_N(i, USER_THERMISTORS) - thermalManager.log_user_thermistor(i); + thermalManager.M305_report(i); } else // ...one user thermistor - thermalManager.log_user_thermistor(t_index); + thermalManager.M305_report(t_index); } #endif // HAS_USER_THERMISTORS diff --git a/Marlin/src/gcode/config/M309.cpp b/Marlin/src/gcode/config/M309.cpp index 2247481b25..d5297e9563 100644 --- a/Marlin/src/gcode/config/M309.cpp +++ b/Marlin/src/gcode/config/M309.cpp @@ -35,14 +35,19 @@ * D - Set the D value */ void GcodeSuite::M309() { + if (!parser.seen("PID")) return M309_report(); if (parser.seen('P')) thermalManager.temp_chamber.pid.Kp = parser.value_float(); if (parser.seen('I')) thermalManager.temp_chamber.pid.Ki = scalePID_i(parser.value_float()); if (parser.seen('D')) thermalManager.temp_chamber.pid.Kd = scalePID_d(parser.value_float()); +} - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" p:", thermalManager.temp_chamber.pid.Kp, - " i:", unscalePID_i(thermalManager.temp_chamber.pid.Ki), - " d:", unscalePID_d(thermalManager.temp_chamber.pid.Kd)); +void GcodeSuite::M309_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_CHAMBER_PID)); + SERIAL_ECHOLNPAIR( + " M309 P", thermalManager.temp_chamber.pid.Kp + , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) + , " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd) + ); } #endif // PIDTEMPCHAMBER diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 7739510cf3..2c12428d98 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -53,13 +53,13 @@ void GcodeSuite::M575() { case 115200: case 250000: case 500000: case 1000000: { const int8_t port = parser.intval('P', -99); const bool set1 = (port == -99 || port == 0); - if (set1) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('0'), " baud rate set to ", baud); + if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); #if HAS_MULTI_SERIAL const bool set2 = (port == -99 || port == 1); - if (set2) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('1'), " baud rate set to ", baud); + if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); #ifdef SERIAL_PORT_3 const bool set3 = (port == -99 || port == 2); - if (set3) SERIAL_ECHO_MSG(" Serial ", AS_CHAR('2'), " baud rate set to ", baud); + if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); #endif #endif diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 544c66a076..9f4f2ac65b 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -23,33 +23,6 @@ #include "../gcode.h" #include "../../module/planner.h" -void report_M92(const bool echo=true, const int8_t e=-1) { - if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); - SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), - PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), - SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), - SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), - SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) - ); - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); - #endif - SERIAL_EOL(); - - #if ENABLED(DISTINCT_E_FACTORS) - 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"), i, - SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)])); - } - #endif - - UNUSED(e); -} - /** * M92: Set axis steps-per-unit for one or more axes, X, Y, Z, and E. * (Follows the same syntax as G92) @@ -58,10 +31,11 @@ void report_M92(const bool echo=true, const int8_t e=-1) { * * If no argument is given print the current values. * - * With MAGIC_NUMBERS_GCODE: - * Use 'H' and/or 'L' to get ideal layer-height information. - * 'H' specifies micro-steps to use. We guess if it's not supplied. - * 'L' specifies a desired layer height. Nearest good heights are shown. + * With MAGIC_NUMBERS_GCODE: + * + * Use 'H' and/or 'L' to get ideal layer-height information. + * H - Specify micro-steps to use. Best guess if not supplied. + * L - Desired layer height in current units. Nearest good heights are shown. */ void GcodeSuite::M92() { @@ -69,10 +43,8 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen( - LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) - TERN_(MAGIC_NUMBERS_GCODE, "HL") - )) return report_M92(true, target_extruder); + if (!parser.seen(LOGICAL_AXES_STRING TERN_(MAGIC_NUMBERS_GCODE, "HL"))) + return M92_report(true, target_extruder); LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { @@ -100,7 +72,7 @@ void GcodeSuite::M92() { #ifndef Z_MICROSTEPS #define Z_MICROSTEPS 16 #endif - const float wanted = parser.floatval('L'); + const float wanted = parser.linearval('L'); if (parser.seen('H') || wanted) { const uint16_t argH = parser.ushortval('H'), micro_steps = argH ?: Z_MICROSTEPS; @@ -117,3 +89,32 @@ void GcodeSuite::M92() { } #endif } + +void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) { + report_heading_etc(forReplay, PSTR(STR_STEPS_PER_UNIT)); + SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) + ); + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); + #endif + SERIAL_EOL(); + + #if ENABLED(DISTINCT_E_FACTORS) + LOOP_L_N(i, E_STEPPERS) { + if (e >= 0 && i != e) continue; + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR_P( + PSTR(" M92 T"), i, + SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)]) + ); + } + #else + UNUSED(e); + #endif +} diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 4ebb81cf7e..e6e0f033ec 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -33,7 +33,7 @@ * M17: Enable stepper motors */ void GcodeSuite::M17() { - if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + if (parser.seen_axis()) { LOGICAL_AXIS_CODE( if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), if (parser.seen_test('X')) ENABLE_AXIS_X(), @@ -59,7 +59,7 @@ void GcodeSuite::M18_M84() { stepper_inactive_time = parser.value_millis_from_seconds(); } else { - if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + if (parser.seen_axis()) { planner.synchronize(); LOGICAL_AXIS_CODE( if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 2ba777ba65..b15cb6ef0a 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -33,14 +33,22 @@ * Usage: M211 S1 to enable, M211 S0 to disable, M211 alone for report */ void GcodeSuite::M211() { + if (parser.seen('S')) + soft_endstop._enabled = parser.value_bool(); + else + M211_report(); +} + +void GcodeSuite::M211_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_SOFT_ENDSTOPS)); + SERIAL_ECHOPAIR(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); + serialprintln_onoff(soft_endstop._enabled); + + report_echo_start(forReplay); const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(), l_soft_max = soft_endstop.max.asLogical(); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS); - if (parser.seen('S')) soft_endstop._enabled = parser.value_bool(); - serialprint_onoff(soft_endstop._enabled); print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); print_pos(l_soft_max, PSTR(STR_SOFT_MAX)); } -#endif +#endif // HAS_SOFTWARE_ENDSTOPS diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 1d76ebf7d5..e1859fb7d9 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -144,4 +144,17 @@ void GcodeSuite::M900() { } +void GcodeSuite::M900_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_LINEAR_ADVANCE)); + #if EXTRUDERS < 2 + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR(" M900 K", planner.extruder_advance_K[0]); + #else + LOOP_L_N(i, EXTRUDERS) { + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR(" M900 T", i, " K", planner.extruder_advance_K[i]); + } + #endif +} + #endif // LIN_ADVANCE diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index aa382a3ea9..3b72ee002c 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -27,18 +27,6 @@ #include "../../gcode.h" #include "../../../feature/controllerfan.h" -void M710_report(const bool forReplay=true) { - if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } - SERIAL_ECHOLNPAIR(" M710" - " S", int(controllerFan.settings.active_speed), - " I", int(controllerFan.settings.idle_speed), - " A", int(controllerFan.settings.auto_mode), - " D", controllerFan.settings.duration, - " ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%" - " ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)" - ); -} - /** * M710: Set controller fan settings * @@ -78,4 +66,16 @@ void GcodeSuite::M710() { M710_report(); } +void GcodeSuite::M710_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_CONTROLLER_FAN)); + SERIAL_ECHOLNPAIR(" M710" + " S", int(controllerFan.settings.active_speed), + " I", int(controllerFan.settings.idle_speed), + " A", int(controllerFan.settings.auto_mode), + " D", controllerFan.settings.duration, + " ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%" + " ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)" + ); +} + #endif // CONTROLLER_FAN_EDITABLE diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index bd741f8a64..cde73ff271 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM || HAS_MOTOR_CURRENT_I2C || HAS_MOTOR_CURRENT_DAC #include "../../gcode.h" @@ -44,12 +44,27 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_SPI + if (!parser.seen("BS" LOGICAL_AXES_STRING)) + return M907_report(); + LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int()); if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int()); if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int()); #elif HAS_MOTOR_CURRENT_PWM + if (!parser.seen( + #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY) + "XY" + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + "Z" + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + "E" + #endif + )) return M907_report(); + #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY) if (parser.seenval('X') || parser.seenval('Y')) stepper.set_digipot_current(0, parser.value_int()); #endif @@ -82,7 +97,30 @@ void GcodeSuite::M907() { #endif } -#if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) +#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM + + void GcodeSuite::M907_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_STEPPER_MOTOR_CURRENTS)); + #if HAS_MOTOR_CURRENT_PWM + SERIAL_ECHOLNPAIR_P( // PWM-based has 3 values: + PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y + , SP_Z_STR, stepper.motor_current_setting[1] // Z + , SP_E_STR, stepper.motor_current_setting[2] // E + ); + #elif HAS_MOTOR_CURRENT_SPI + SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: + LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default) + SERIAL_CHAR(' ', axis_codes[q]); + SERIAL_ECHO(stepper.motor_current_setting[q]); + } + SERIAL_CHAR(' ', 'B'); // B (maps to E1 by default) + SERIAL_ECHOLN(stepper.motor_current_setting[4]); + #endif + } + +#endif // HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM + +#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_DAC /** * M908: Control digital trimpot directly (M908 P S) diff --git a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp index 5793d73f94..040a09a8e0 100644 --- a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp +++ b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp @@ -29,14 +29,34 @@ /** * M207: Set firmware retraction values + * + * S[+units] retract_length + * W[+units] swap_retract_length (multi-extruder) + * F[units/min] retract_feedrate_mm_s + * Z[units] retract_zraise */ void GcodeSuite::M207() { fwretract.M207(); } +void GcodeSuite::M207_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_RETRACT_S_F_Z)); + fwretract.M207_report(); +} + /** * M208: Set firmware un-retraction values + * + * S[+units] retract_recover_extra (in addition to M207 S*) + * W[+units] swap_retract_recover_extra (multi-extruder) + * F[units/min] retract_recover_feedrate_mm_s + * R[units/min] swap_retract_recover_feedrate_mm_s */ void GcodeSuite::M208() { fwretract.M208(); } +void GcodeSuite::M208_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_RECOVER_S_F)); + fwretract.M208_report(); +} + #if ENABLED(FWRETRACT_AUTORETRACT) /** @@ -47,6 +67,11 @@ void GcodeSuite::M208() { fwretract.M208(); } */ void GcodeSuite::M209() { fwretract.M209(); } + void GcodeSuite::M209_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_AUTO_RETRACT_S)); + fwretract.M209_report(); + } + #endif #endif // FWRETRACT diff --git a/Marlin/src/gcode/feature/network/M552-M554.cpp b/Marlin/src/gcode/feature/network/M552-M554.cpp index 22c718c042..887e67f3bd 100644 --- a/Marlin/src/gcode/feature/network/M552-M554.cpp +++ b/Marlin/src/gcode/feature/network/M552-M554.cpp @@ -64,17 +64,7 @@ void ip_report(const uint16_t cmd, PGM_P const post, const IPAddress &ipo) { if (i < 3) SERIAL_CHAR('.'); } SERIAL_ECHOPGM(" ; "); - SERIAL_ECHOPGM_P(post); - SERIAL_EOL(); -} -void M552_report() { - ip_report(552, PSTR("ip address"), Ethernet.linkStatus() == LinkON ? Ethernet.localIP() : ethernet.ip); -} -void M553_report() { - ip_report(553, PSTR("subnet mask"), Ethernet.linkStatus() == LinkON ? Ethernet.subnetMask() : ethernet.subnet); -} -void M554_report() { - ip_report(554, PSTR("gateway"), Ethernet.linkStatus() == LinkON ? Ethernet.gatewayIP() : ethernet.gateway); + SERIAL_ECHOLNPGM_P(post); } /** @@ -107,20 +97,36 @@ void GcodeSuite::M552() { if (nopar || seenP) M552_report(); } +void GcodeSuite::M552_report() { + ip_report(552, PSTR("ip address"), Ethernet.linkStatus() == LinkON ? Ethernet.localIP() : ethernet.ip); +} + /** * M553 Pnnn - Set netmask */ void GcodeSuite::M553() { - if (parser.seenval('P')) ethernet.subnet.fromString(parser.value_string()); - M553_report(); + if (parser.seenval('P')) + ethernet.subnet.fromString(parser.value_string()); + else + M553_report(); +} + +void GcodeSuite::M553_report() { + ip_report(553, PSTR("subnet mask"), Ethernet.linkStatus() == LinkON ? Ethernet.subnetMask() : ethernet.subnet); } /** * M554 Pnnn - Set Gateway */ void GcodeSuite::M554() { - if (parser.seenval('P')) ethernet.gateway.fromString(parser.value_string()); - M554_report(); + if (parser.seenval('P')) + ethernet.gateway.fromString(parser.value_string()); + else + M554_report(); +} + +void GcodeSuite::M554_report() { + ip_report(554, PSTR("gateway"), Ethernet.linkStatus() == LinkON ? Ethernet.gatewayIP() : ethernet.gateway); } #endif // HAS_ETHERNET diff --git a/Marlin/src/gcode/feature/pause/M603.cpp b/Marlin/src/gcode/feature/pause/M603.cpp index 9c3b774bd2..e26ab1c7b4 100644 --- a/Marlin/src/gcode/feature/pause/M603.cpp +++ b/Marlin/src/gcode/feature/pause/M603.cpp @@ -42,6 +42,8 @@ */ void GcodeSuite::M603() { + if (!parser.seen("TUL")) return M603_report(); + const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -62,4 +64,20 @@ void GcodeSuite::M603() { } } +void GcodeSuite::M603_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_FILAMENT_LOAD_UNLOAD)); + + #if EXTRUDERS == 1 + report_echo_start(forReplay); + SERIAL_ECHOPAIR(" M603 L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length), " ;"); + say_units(); + #else + LOOP_L_N(e, EXTRUDERS) { + report_echo_start(forReplay); + SERIAL_ECHOPAIR(" M603 T", e, " L", LINEAR_UNIT(fc_settings[e].load_length), " U", LINEAR_UNIT(fc_settings[e].unload_length), " ;"); + say_units(); + } + #endif +} + #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 18aeb507b1..b1be80619f 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -40,11 +40,8 @@ void GcodeSuite::M413() { if (parser.seen('S')) recovery.enable(parser.value_bool()); - else { - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Power-loss recovery "); - serialprintln_onoff(recovery.enabled); - } + else + M413_report(); #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) if (parser.seen("RL")) recovery.load(); @@ -59,4 +56,10 @@ void GcodeSuite::M413() { #endif } +void GcodeSuite::M413_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_POWER_LOSS_RECOVERY)); + SERIAL_ECHOPAIR(" M413 S", AS_DIGIT(recovery.enabled), " ; "); + serialprintln_onoff(recovery.enabled); +} + #endif // POWER_LOSS_RECOVERY diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 9a06357132..56c7f03604 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -66,4 +66,16 @@ void GcodeSuite::M412() { } } +void GcodeSuite::M412_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); + SERIAL_ECHOLNPAIR( + " M412 S", runout.enabled + #if HAS_FILAMENT_RUNOUT_DISTANCE + , " D", LINEAR_UNIT(runout.runout_distance()) + #endif + , " ; Sensor " + ); + serialprintln_onoff(runout.enabled); +} + #endif // HAS_FILAMENT_SENSOR diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 9a7f1fbce9..5cadd2d45e 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -138,4 +138,66 @@ void GcodeSuite::M569() { say_stealth_status(); } +void GcodeSuite::M569_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_DRIVER_STEPPING_MODE)); + + auto say_M569 = [](const bool forReplay, const char * const etc=nullptr, const bool eol=false) { + if (!forReplay) SERIAL_ECHO_START(); + SERIAL_ECHOPGM(" M569 S1"); + if (etc) { + SERIAL_CHAR(' '); + SERIAL_ECHOPGM_P(etc); + } + if (eol) SERIAL_EOL(); + }; + + const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()), + chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()), + chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()), + chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()), + chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()), + chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()); + + if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) { + say_M569(forReplay); + LINEAR_AXIS_CODE( + if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR), + if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR), + if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR), + if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR), + if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR), + if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR) + ); + SERIAL_EOL(); + } + + const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()), + chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()), + chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop()); + + if (chop_x2 || chop_y2 || chop_z2) { + say_M569(forReplay, PSTR("I1")); + if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR); + if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR); + if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR); + SERIAL_EOL(); + } + + if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); } + + if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); } + if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); } + if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); } + + if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); } + if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); } + if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); } + if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); } + if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); } + if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); } + if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); } + if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); } +} + #endif // HAS_STEALTHCHOP diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 9e56e51358..243cf46560 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -198,4 +198,99 @@ void GcodeSuite::M906() { } } +void GcodeSuite::M906_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_STEPPER_DRIVER_CURRENT)); + + auto say_M906 = [](const bool forReplay) { + report_echo_start(forReplay); + SERIAL_ECHOPGM(" M906"); + }; + + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) + say_M906(forReplay); + #if AXIS_IS_TMC(X) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.getMilliamps()); + #endif + #if AXIS_IS_TMC(Y) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.getMilliamps()); + #endif + #if AXIS_IS_TMC(Z) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); + #endif + SERIAL_EOL(); + #endif + + #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) + say_M906(forReplay); + SERIAL_ECHOPGM(" I1"); + #if AXIS_IS_TMC(X2) + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.getMilliamps()); + #endif + #if AXIS_IS_TMC(Y2) + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.getMilliamps()); + #endif + #if AXIS_IS_TMC(Z2) + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); + #endif + SERIAL_EOL(); + #endif + + #if AXIS_IS_TMC(Z3) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps()); + #endif + + #if AXIS_IS_TMC(Z4) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); + #endif + + #if AXIS_IS_TMC(I) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); + #endif + #if AXIS_IS_TMC(J) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); + #endif + #if AXIS_IS_TMC(K) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); + #endif + + #if AXIS_IS_TMC(E0) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); + #endif + #if AXIS_IS_TMC(E1) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T1 E", stepperE1.getMilliamps()); + #endif + #if AXIS_IS_TMC(E2) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T2 E", stepperE2.getMilliamps()); + #endif + #if AXIS_IS_TMC(E3) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T3 E", stepperE3.getMilliamps()); + #endif + #if AXIS_IS_TMC(E4) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T4 E", stepperE4.getMilliamps()); + #endif + #if AXIS_IS_TMC(E5) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T5 E", stepperE5.getMilliamps()); + #endif + #if AXIS_IS_TMC(E6) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T6 E", stepperE6.getMilliamps()); + #endif + #if AXIS_IS_TMC(E7) + say_M906(forReplay); + SERIAL_ECHOLNPAIR(" T7 E", stepperE7.getMilliamps()); + #endif + SERIAL_EOL(); +} + #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 fca16c0630..d711865480 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -227,6 +227,7 @@ * M913: Set HYBRID_THRESHOLD speed. */ #if ENABLED(HYBRID_THRESHOLD) + void GcodeSuite::M913() { #define TMC_SAY_PWMTHRS(A,Q) tmc_print_pwmthrs(stepper##Q) #define TMC_SET_PWMTHRS(A,Q) stepper##Q.set_pwm_thrs(value) @@ -308,12 +309,109 @@ TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7)); } } + + void GcodeSuite::M913_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_HYBRID_THRESHOLD)); + + auto say_M913 = [](const bool forReplay) { + report_echo_start(forReplay); + SERIAL_ECHOPGM(" M913"); + }; + + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP + say_M913(forReplay); + #if X_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); + #endif + #if Y_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); + #endif + #if Z_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); + #endif + SERIAL_EOL(); + #endif + + #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOPGM(" I1"); + #if X2_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); + #endif + #if Y2_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); + #endif + #if Z2_HAS_STEALTHCHOP + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); + #endif + SERIAL_EOL(); + #endif + + #if Z3_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); + #endif + + #if Z4_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); + #endif + + #if I_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); + #endif + #if J_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); + #endif + #if K_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); + #endif + + #if E0_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); + #endif + #if E1_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); + #endif + #if E2_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); + #endif + #if E3_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); + #endif + #if E4_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); + #endif + #if E5_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); + #endif + #if E6_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); + #endif + #if E7_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); + #endif + SERIAL_EOL(); + } + #endif // HYBRID_THRESHOLD /** * M914: Set StallGuard sensitivity. */ #if USE_SENSORLESS + void GcodeSuite::M914() { bool report = true; @@ -412,6 +510,68 @@ #endif } } + + void GcodeSuite::M914_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_STALLGUARD_THRESHOLD)); + + auto say_M914 = [](const bool forReplay) { + report_echo_start(forReplay); + SERIAL_ECHOPGM(" M914"); + }; + + #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS + say_M914(forReplay); + #if X_SENSORLESS + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.homing_threshold()); + #endif + #if Y_SENSORLESS + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.homing_threshold()); + #endif + #if Z_SENSORLESS + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.homing_threshold()); + #endif + SERIAL_EOL(); + #endif + + #if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOPGM(" I1"); + #if X2_SENSORLESS + SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.homing_threshold()); + #endif + #if Y2_SENSORLESS + SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.homing_threshold()); + #endif + #if Z2_SENSORLESS + SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.homing_threshold()); + #endif + SERIAL_EOL(); + #endif + + #if Z3_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold()); + #endif + + #if Z4_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); + #endif + + #if I_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); + #endif + #if J_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); + #endif + #if K_SENSORLESS + say_M914(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); + #endif + } + #endif // USE_SENSORLESS #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 94496f2b25..4c03fd9f85 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -102,6 +102,24 @@ uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( xyz_pos_t GcodeSuite::coordinate_system[MAX_COORDINATE_SYSTEMS]; #endif +void GcodeSuite::report_echo_start(const bool forReplay) { if (!forReplay) SERIAL_ECHO_START(); } +void GcodeSuite::report_heading(const bool forReplay, PGM_P const pstr, const bool eol/*=true*/) { + if (forReplay) return; + if (pstr) { + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("; "); + SERIAL_ECHOPGM_P(pstr); + } + if (eol) { SERIAL_CHAR(':'); SERIAL_EOL(); } +} + +void GcodeSuite::say_units() { + SERIAL_ECHOLNPGM_P( + TERN_(INCH_MODE_SUPPORT, parser.linear_unit_factor != 1.0 ? PSTR(" (in)") :) + PSTR(" (mm)") + ); +} + /** * Get the target extruder from the T parameter or the active_extruder * Return -1 if the T parameter is out of range @@ -180,7 +198,7 @@ void GcodeSuite::get_destination_from_command() { recovery.save(); #endif - if (parser.linearval('F') > 0) + if (parser.floatval('F') > 0) feedrate_mm_s = parser.value_feedrate(); #if ENABLED(PRINTCOUNTER) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index ccbeda6474..cd190387b0 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -383,6 +383,14 @@ public: return ELAPSED(ms, previous_move_ms + stepper_inactive_time); } + static void report_echo_start(const bool forReplay); + static void report_heading(const bool forReplay, PGM_P const pstr, const bool eol=true); + static inline void report_heading_etc(const bool forReplay, PGM_P const pstr, const bool eol=true) { + report_heading(forReplay, pstr, eol); + report_echo_start(forReplay); + } + static void say_units(); + static int8_t get_target_extruder_from_command(); static int8_t get_target_e_stepper_from_command(); static void get_destination_from_command(); @@ -438,6 +446,8 @@ public: private: + friend class MarlinSettings; + #if ENABLED(MARLIN_DEV_MODE) static void D(const int16_t dcode); #endif @@ -518,6 +528,7 @@ private: #if ENABLED(Z_STEPPER_AUTO_ALIGN) static void M422(); + static void M422_report(const bool forReplay=true); #endif #if ENABLED(ASSISTED_TRAMMING) @@ -662,6 +673,7 @@ private: static void M85(); static void M92(); + static void M92_report(const bool forReplay=true, const int8_t e=-1); #if ENABLED(M100_FREE_MEMORY_WATCHER) static void M100(); @@ -741,10 +753,12 @@ private: #if PREHEAT_COUNT static void M145(); + static void M145_report(const bool forReplay=true); #endif #if ENABLED(TEMPERATURE_UNITS_SUPPORT) static void M149(); + static void M149_report(const bool forReplay=true); #endif #if HAS_COLOR_LEDS @@ -770,37 +784,51 @@ private: #endif #endif - static void M200(); + #if DISABLED(NO_VOLUMETRICS) + static void M200(); + static void M200_report(const bool forReplay=true); + #endif static void M201(); + static void M201_report(const bool forReplay=true); #if 0 static void M202(); // Not used for Sprinter/grbl gen6 #endif static void M203(); + static void M203_report(const bool forReplay=true); static void M204(); + static void M204_report(const bool forReplay=true); static void M205(); + static void M205_report(const bool forReplay=true); #if HAS_M206_COMMAND static void M206(); + static void M206_report(const bool forReplay=true); #endif #if ENABLED(FWRETRACT) static void M207(); + static void M207_report(const bool forReplay=true); static void M208(); + static void M208_report(const bool forReplay=true); #if ENABLED(FWRETRACT_AUTORETRACT) static void M209(); + static void M209_report(const bool forReplay=true); #endif #endif static void M211(); + static void M211_report(const bool forReplay=true); #if HAS_MULTI_EXTRUDER static void M217(); + static void M217_report(const bool forReplay=true); #endif #if HAS_HOTEND_OFFSET static void M218(); + static void M218_report(const bool forReplay=true); #endif static void M220(); @@ -819,10 +847,12 @@ private: #if HAS_LCD_CONTRAST static void M250(); + static void M250_report(const bool forReplay=true); #endif #if HAS_LCD_BRIGHTNESS static void M256(); + static void M256_report(const bool forReplay=true); #endif #if ENABLED(EXPERIMENTAL_I2CBUS) @@ -834,6 +864,7 @@ private: static void M280(); #if ENABLED(EDITABLE_SERVO_ANGLES) static void M281(); + static void M281_report(const bool forReplay=true); #endif #endif @@ -847,6 +878,7 @@ private: #if ENABLED(PIDTEMP) static void M301(); + static void M301_report(const bool forReplay=true, const int8_t eindex=-1); #endif #if ENABLED(PREVENT_COLD_EXTRUSION) @@ -859,6 +891,7 @@ private: #if ENABLED(PIDTEMPBED) static void M304(); + static void M304_report(const bool forReplay=true); #endif #if HAS_USER_THERMISTORS @@ -867,6 +900,7 @@ private: #if ENABLED(PIDTEMPCHAMBER) static void M309(); + static void M309_report(const bool forReplay=true); #endif #if HAS_MICROSTEPS @@ -915,19 +949,23 @@ private: #if HAS_FILAMENT_SENSOR static void M412(); + static void M412_report(const bool forReplay=true); #endif #if HAS_MULTI_LANGUAGE static void M414(); + static void M414_report(const bool forReplay=true); #endif #if HAS_LEVELING static void M420(); + static void M420_report(const bool forReplay=true); static void M421(); #endif #if ENABLED(BACKLASH_GCODE) static void M425(); + static void M425_report(const bool forReplay=true); #endif #if HAS_M206_COMMAND @@ -972,8 +1010,16 @@ private: #if HAS_ETHERNET static void M552(); + static void M552_report(); static void M553(); + static void M553_report(); static void M554(); + static void M554_report(); + #endif + + #if HAS_STEALTHCHOP + static void M569(); + static void M569_report(const bool forReplay=true); #endif #if ENABLED(BAUD_RATE_GCODE) @@ -983,6 +1029,7 @@ private: #if ENABLED(ADVANCED_PAUSE_FEATURE) static void M600(); static void M603(); + static void M603_report(const bool forReplay=true); #endif #if HAS_DUPLICATION_MODE @@ -991,10 +1038,12 @@ private: #if IS_KINEMATIC static void M665(); + static void M665_report(const bool forReplay=true); #endif - #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS + #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) static void M666(); + static void M666_report(const bool forReplay=true); #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) @@ -1016,10 +1065,12 @@ private: #if HAS_BED_PROBE static void M851(); + static void M851_report(const bool forReplay=true); #endif #if ENABLED(SKEW_CORRECTION_GCODE) static void M852(); + static void M852_report(const bool forReplay=true); #endif #if ENABLED(I2C_POSITION_ENCODERS) @@ -1042,23 +1093,24 @@ private: #if ENABLED(LIN_ADVANCE) static void M900(); + static void M900_report(const bool forReplay=true); #endif #if HAS_TRINAMIC_CONFIG static void M122(); static void M906(); - #if HAS_STEALTHCHOP - static void M569(); - #endif + static void M906_report(const bool forReplay=true); #if ENABLED(MONITOR_DRIVER_STATUS) static void M911(); static void M912(); #endif #if ENABLED(HYBRID_THRESHOLD) static void M913(); + static void M913_report(const bool forReplay=true); #endif #if ENABLED(USE_SENSORLESS) static void M914(); + static void M914_report(const bool forReplay=true); #endif #endif @@ -1070,16 +1122,19 @@ private: static void M918(); #endif - #if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC) + #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM || HAS_MOTOR_CURRENT_I2C || HAS_MOTOR_CURRENT_DAC static void M907(); - #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) - static void M908(); - #if HAS_MOTOR_CURRENT_DAC - static void M909(); - static void M910(); - #endif + #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM + static void M907_report(const bool forReplay=true); #endif #endif + #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_DAC + static void M908(); + #endif + #if HAS_MOTOR_CURRENT_DAC + static void M909(); + static void M910(); + #endif #if ENABLED(SDSUPPORT) static void M928(); @@ -1106,6 +1161,7 @@ private: #if ENABLED(POWER_LOSS_RECOVERY) static void M413(); + static void M413_report(const bool forReplay=true); static void M1000(); #endif @@ -1127,6 +1183,7 @@ private: #if ENABLED(CONTROLLER_FAN_EDITABLE) static void M710(); + static void M710_report(const bool forReplay=true); #endif static void T(const int8_t tool_index); diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 51f3e7c14c..ce142dacdf 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -30,19 +30,6 @@ #include "../../libs/buzzer.h" #include "../../MarlinCore.h" -void M206_report() { - SERIAL_ECHOLNPAIR_P( - LIST_N(DOUBLE(LINEAR_AXES), - PSTR("M206 X"), home_offset.x, - SP_Y_STR, home_offset.y, - SP_Z_STR, home_offset.z, - SP_I_STR, home_offset.i, - SP_J_STR, home_offset.j, - SP_K_STR, home_offset.k, - ) - ); -} - /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y * @@ -51,6 +38,8 @@ void M206_report() { * *** In the 2.0 release, it will simply be disabled by default. */ void GcodeSuite::M206() { + if (!parser.seen_any()) return M206_report(); + LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) set_home_offset((AxisEnum)i, parser.value_linear_units()); @@ -60,10 +49,25 @@ void GcodeSuite::M206() { if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi #endif - if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K"))) - M206_report(); - else - report_current_position(); + report_current_position(); +} + +void GcodeSuite::M206_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_HOME_OFFSET)); + SERIAL_ECHOLNPAIR_P( + #if IS_CARTESIAN + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), + SP_Y_STR, LINEAR_UNIT(home_offset.y), + SP_Z_STR, LINEAR_UNIT(home_offset.z), + SP_I_STR, LINEAR_UNIT(home_offset.i), + SP_J_STR, LINEAR_UNIT(home_offset.j), + SP_K_STR, LINEAR_UNIT(home_offset.k) + ) + #else + PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z) + #endif + ); } /** diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index d6a57d2215..cbd752d245 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -60,4 +60,23 @@ void GcodeSuite::M145() { } } +void GcodeSuite::M145_report(const bool forReplay/*=true*/) { + report_heading(forReplay, PSTR(STR_MATERIAL_HEATUP)); + LOOP_L_N(i, PREHEAT_COUNT) { + report_echo_start(forReplay); + SERIAL_ECHOLNPAIR_P( + PSTR(" M145 S"), i + #if HAS_HOTEND + , PSTR(" H"), parser.to_temp_units(ui.material_preset[i].hotend_temp) + #endif + #if HAS_HEATED_BED + , SP_B_STR, parser.to_temp_units(ui.material_preset[i].bed_temp) + #endif + #if HAS_FAN + , PSTR(" F"), ui.material_preset[i].fan_speed + #endif + ); + } +} + #endif // PREHEAT_COUNT diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index f553044d31..2b7e3dc994 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #include "../../inc/MarlinConfig.h" #if HAS_LCD_CONTRAST @@ -31,8 +30,15 @@ * M250: Read and optionally set the LCD contrast */ void GcodeSuite::M250() { - if (parser.seen('C')) ui.set_contrast(parser.value_int()); - SERIAL_ECHOLNPAIR("LCD Contrast: ", ui.contrast); + if (parser.seenval('C')) + ui.set_contrast(parser.value_int()); + else + M250_report(); +} + +void GcodeSuite::M250_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_LCD_CONTRAST)); + SERIAL_ECHOLNPAIR(" M250 C", ui.contrast); } #endif // HAS_LCD_CONTRAST diff --git a/Marlin/src/gcode/lcd/M256.cpp b/Marlin/src/gcode/lcd/M256.cpp index e292acc4ed..ff7c59fc9a 100644 --- a/Marlin/src/gcode/lcd/M256.cpp +++ b/Marlin/src/gcode/lcd/M256.cpp @@ -30,8 +30,15 @@ * M256: Set the LCD brightness */ void GcodeSuite::M256() { - if (parser.seenval('B')) ui.set_brightness(parser.value_int()); - SERIAL_ECHOLNPAIR("LCD Brightness: ", ui.brightness); + if (parser.seenval('B')) + ui.set_brightness(parser.value_int()); + else + M256_report(); +} + +void GcodeSuite::M256_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_LCD_BRIGHTNESS)); + SERIAL_ECHOLNPAIR(" M256 B", ui.brightness); } #endif // HAS_LCD_BRIGHTNESS diff --git a/Marlin/src/gcode/lcd/M414.cpp b/Marlin/src/gcode/lcd/M414.cpp index 760028a899..26ecea2083 100644 --- a/Marlin/src/gcode/lcd/M414.cpp +++ b/Marlin/src/gcode/lcd/M414.cpp @@ -38,7 +38,14 @@ void GcodeSuite::M414() { if (parser.seenval('S')) ui.set_language(parser.value_byte()); + else + M414_report(); } +void GcodeSuite::M414_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_UI_LANGUAGE)); + SERIAL_ECHOLNPAIR(" M414 S", ui.language); +} + #endif // HAS_MULTI_LANGUAGE diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index a819de6127..f8fb890695 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -225,9 +225,7 @@ public: #endif // !FASTER_GCODE_PARSER // Seen any axis parameter - static inline bool seen_axis() { - return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)); - } + static inline bool seen_axis() { return seen(LOGICAL_AXES_STRING); } #if ENABLED(GCODE_QUOTED_STRINGS) static char* unescape_string(char* &src); @@ -350,14 +348,15 @@ public: static inline void set_input_temp_units(const TempUnit units) { input_temp_units = units; } + static inline char temp_units_code() { + return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'; + } + static inline PGM_P temp_units_name() { + return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius"); + } + #if HAS_LCD_MENU && DISABLED(DISABLE_M503) - static inline char temp_units_code() { - return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'; - } - static inline PGM_P temp_units_name() { - return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius"); - } static inline float to_temp_units(celsius_t c) { switch (input_temp_units) { default: diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index ee6244932e..e7261b5a14 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -32,19 +32,8 @@ * M851: Set the nozzle-to-probe offsets in current units */ void GcodeSuite::M851() { - - // Show usage with no parameters - if (!parser.seen("XYZ")) { - SERIAL_ECHOLNPAIR_P( - #if HAS_PROBE_XY_OFFSET - PSTR(STR_PROBE_OFFSET " X"), probe.offset_xy.x, SP_Y_STR, probe.offset_xy.y, SP_Z_STR - #else - PSTR(STR_PROBE_OFFSET " X0 Y0 Z") - #endif - , probe.offset.z - ); - return; - } + // No parameters? Show current state. + if (!parser.seen("XYZ")) return M851_report(); // Start with current offsets and modify xyz_pos_t offs = probe.offset; @@ -94,4 +83,20 @@ void GcodeSuite::M851() { if (ok) probe.offset = offs; } +void GcodeSuite::M851_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_Z_PROBE_OFFSET)); + SERIAL_ECHOPAIR_P( + #if HAS_PROBE_XY_OFFSET + PSTR(" M851 X"), LINEAR_UNIT(probe.offset_xy.x), + SP_Y_STR, LINEAR_UNIT(probe.offset_xy.y), + SP_Z_STR + #else + PSTR(" M851 X0 Y0 Z") + #endif + , LINEAR_UNIT(probe.offset.z) + , " ;" + ); + say_units(); +} + #endif // HAS_BED_PROBE diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index 5d9f832069..eeca59088f 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -33,6 +33,13 @@ void GcodeSuite::M149() { if (parser.seenval('C')) parser.set_input_temp_units(TEMPUNIT_C); else if (parser.seenval('K')) parser.set_input_temp_units(TEMPUNIT_K); else if (parser.seenval('F')) parser.set_input_temp_units(TEMPUNIT_F); + else M149_report(); +} + +void GcodeSuite::M149_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_TEMPERATURE_UNITS)); + SERIAL_ECHOPAIR(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); + SERIAL_ECHOLNPGM_P(parser.temp_units_name()); } #endif // TEMPERATURE_UNITS_SUPPORT diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 0f4716ed87..8ca19e4361 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -578,13 +578,13 @@ void _O2 Endstops::report_states() { default: continue; REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_RUNOUT) } - SERIAL_ECHOPGM(STR_FILAMENT_RUNOUT_SENSOR); + SERIAL_ECHOPGM(STR_FILAMENT); if (i > 1) SERIAL_CHAR(' ', '0' + i); print_es_state(extDigitalRead(pin) != state); } #undef _CASE_RUNOUT #elif HAS_FILAMENT_SENSOR - print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); + print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, PSTR(STR_FILAMENT)); #endif TERN_(BLTOUCH, bltouch._reset_SW_mode()); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index c24a63ee51..017b96cc20 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -133,9 +133,6 @@ #endif #include "../feature/controllerfan.h" -#if ENABLED(CONTROLLER_FAN_EDITABLE) - void M710_report(const bool forReplay=true); -#endif #if ENABLED(CASE_LIGHT_ENABLE) #include "../feature/caselight.h" @@ -167,13 +164,6 @@ #if HAS_ETHERNET void ETH0_report(); void MAC_report(); - void M552_report(); - void M553_report(); - void M554_report(); -#endif - -#if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) - void M666_report(const bool forReplay=true); #endif #define _EN_ITEM(N) , E##N @@ -3012,63 +3002,19 @@ void MarlinSettings::reset() { postprocess(); - DEBUG_ECHO_START(); - DEBUG_ECHOLNPGM("Hardcoded Default Settings Loaded"); + DEBUG_ECHO_MSG("Hardcoded Default Settings Loaded"); TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); } #if DISABLED(DISABLE_M503) - static void config_heading(const bool repl, PGM_P const pstr, const bool eol=true) { - if (!repl) { - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("; "); - SERIAL_ECHOPGM_P(pstr); - if (eol) SERIAL_EOL(); - } - } - - #define CONFIG_ECHO_START() do{ if (!forReplay) SERIAL_ECHO_START(); }while(0) + #define CONFIG_ECHO_START() gcode.report_echo_start(forReplay) #define CONFIG_ECHO_MSG(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0) - #define CONFIG_ECHO_HEADING(STR) config_heading(forReplay, PSTR(STR)) + #define CONFIG_ECHO_MSG_P(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P(V); }while(0) + #define CONFIG_ECHO_HEADING(STR) gcode.report_heading(forReplay, PSTR(STR)) - #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) { - CONFIG_ECHO_START(); - SERIAL_ECHOPGM(" M569 S1"); - if (etc) { - SERIAL_CHAR(' '); - SERIAL_ECHOPGM_P(etc); - } - if (newLine) SERIAL_EOL(); - } - #endif - #if ENABLED(HYBRID_THRESHOLD) - inline void say_M913(const bool forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" M913"); } - #endif - #if USE_SENSORLESS - inline void say_M914() { SERIAL_ECHOPGM(" M914"); } - #endif - #endif - - #if ENABLED(ADVANCED_PAUSE_FEATURE) - inline void say_M603(const bool forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" M603 "); } - #endif - - inline void say_units(const bool colon) { - SERIAL_ECHOPGM_P( - #if ENABLED(INCH_MODE_SUPPORT) - parser.linear_unit_factor != 1.0 ? PSTR(" (in)") : - #endif - PSTR(" (mm)") - ); - if (colon) SERIAL_ECHOLNPGM(":"); - } - - void report_M92(const bool echo=true, const int8_t e=-1); + void M92_report(const bool echo=true, const int8_t e=-1); /** * M503 - Report current settings in RAM @@ -3076,228 +3022,73 @@ void MarlinSettings::reset() { * Unless specifically disabled, M503 is available even without EEPROM */ void MarlinSettings::report(const bool forReplay) { - /** - * Announce current units, in case inches are being displayed - */ - CONFIG_ECHO_START(); + // + // Announce current units, in case inches are being displayed + // + CONFIG_ECHO_HEADING("Linear Units"); #if ENABLED(INCH_MODE_SUPPORT) - SERIAL_ECHOPGM(" G2"); - SERIAL_CHAR(parser.linear_unit_factor == 1.0 ? '1' : '0'); - SERIAL_ECHOPGM(" ;"); - say_units(false); + SERIAL_ECHOPAIR(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); #else - SERIAL_ECHOPGM(" G21 ; Units in mm"); - say_units(false); + SERIAL_ECHOPGM(" G21 ;"); #endif - SERIAL_EOL(); - - #if HAS_LCD_MENU - - // Temperature units - for Ultipanel temperature options - - CONFIG_ECHO_START(); - #if ENABLED(TEMPERATURE_UNITS_SUPPORT) - SERIAL_ECHOPGM(" M149 "); - SERIAL_CHAR(parser.temp_units_code()); - SERIAL_ECHOPGM(" ; Units in "); - SERIAL_ECHOPGM_P(parser.temp_units_name()); - #else - SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius"); - #endif + gcode.say_units(); + // + // M149 Temperature units + // + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) + gcode.M149_report(forReplay); + #else + CONFIG_ECHO_HEADING(STR_TEMPERATURE_UNITS); + CONFIG_ECHO_MSG(" M149 C ; Units in Celsius"); #endif - SERIAL_EOL(); + // + // M200 Volumetric Extrusion + // + IF_DISABLED(NO_VOLUMETRICS, gcode.M200_report(forReplay)); - #if EXTRUDERS && DISABLED(NO_VOLUMETRICS) + // + // M92 Steps per Unit + // + gcode.M92_report(forReplay); - /** - * Volumetric extrusion M200 - */ - if (!forReplay) { - config_heading(forReplay, PSTR("Filament settings:"), false); - if (parser.volumetric_enabled) - SERIAL_EOL(); - else - SERIAL_ECHOLNPGM(" Disabled"); - } + // + // M203 Maximum feedrates (units/s) + // + gcode.M203_report(forReplay); - #if EXTRUDERS == 1 - CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled - , " D", LINEAR_UNIT(planner.filament_size[0]) - #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) - #endif - ); - #else - LOOP_L_N(i, EXTRUDERS) { - CONFIG_ECHO_MSG(" M200 T", i - , " D", LINEAR_UNIT(planner.filament_size[i]) - #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) - #endif - ); - } - CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled); - #endif + // + // M201 Maximum Acceleration (units/s2) + // + gcode.M201_report(forReplay); - #endif // EXTRUDERS && !NO_VOLUMETRICS + // + // M204 Acceleration (units/s2) + // + gcode.M204_report(forReplay); - CONFIG_ECHO_HEADING("Steps per unit:"); - report_M92(!forReplay); + // + // M205 "Advanced" Settings + // + gcode.M205_report(forReplay); - CONFIG_ECHO_HEADING("Maximum feedrates (units/s):"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - LIST_N(DOUBLE(LINEAR_AXES), - PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), - SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), - SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), - SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) - #endif - ); - #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M203 T"), i - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) - ); - } - #endif + // + // M206 Home Offset + // + TERN_(HAS_M206_COMMAND, gcode.M206_report(forReplay)); - CONFIG_ECHO_HEADING("Maximum Acceleration (units/s2):"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - LIST_N(DOUBLE(LINEAR_AXES), - PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), - SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), - SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), - SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) - #endif - ); - #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M201 T"), i - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) - ); - } - #endif + // + // M218 Hotend offsets + // + TERN_(HAS_HOTEND_OFFSET, gcode.M218_report(forReplay)); - CONFIG_ECHO_HEADING("Acceleration (units/s2): P R T"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration) - , PSTR(" R"), LINEAR_UNIT(planner.settings.retract_acceleration) - , SP_T_STR, LINEAR_UNIT(planner.settings.travel_acceleration) - ); - - CONFIG_ECHO_HEADING( - "Advanced: B S T" - TERN_(HAS_JUNCTION_DEVIATION, " J") - #if HAS_CLASSIC_JERK - " X Y Z" - TERN_(HAS_CLASSIC_E_JERK, " E") - #endif - ); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M205 B"), LINEAR_UNIT(planner.settings.min_segment_time_us) - , PSTR(" S"), LINEAR_UNIT(planner.settings.min_feedrate_mm_s) - , SP_T_STR, LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s) - #if HAS_JUNCTION_DEVIATION - , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) - #endif - #if HAS_CLASSIC_JERK - , LIST_N(DOUBLE(LINEAR_AXES), - SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), - SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), - SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), - SP_I_STR, LINEAR_UNIT(planner.max_jerk.i), - SP_J_STR, LINEAR_UNIT(planner.max_jerk.j), - SP_K_STR, LINEAR_UNIT(planner.max_jerk.k) - ) - #if HAS_CLASSIC_E_JERK - , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e) - #endif - #endif - ); - - #if HAS_M206_COMMAND - CONFIG_ECHO_HEADING("Home offset:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - #if IS_CARTESIAN - LIST_N(DOUBLE(LINEAR_AXES), - PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), - SP_Y_STR, LINEAR_UNIT(home_offset.y), - SP_Z_STR, LINEAR_UNIT(home_offset.z), - SP_I_STR, LINEAR_UNIT(home_offset.i), - SP_J_STR, LINEAR_UNIT(home_offset.j), - SP_K_STR, LINEAR_UNIT(home_offset.k) - ) - #else - PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z) - #endif - ); - #endif - - #if HAS_HOTEND_OFFSET - CONFIG_ECHO_HEADING("Hotend offsets:"); - CONFIG_ECHO_START(); - LOOP_S_L_N(e, 1, HOTENDS) { - SERIAL_ECHOPAIR_P( - PSTR(" M218 T"), e, - SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), - SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) - ); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(hotend_offset[e].z), 3); - } - #endif - - /** - * Bed Leveling - */ + // + // Bed Leveling + // #if HAS_LEVELING - #if ENABLED(MESH_BED_LEVELING) - - CONFIG_ECHO_HEADING("Mesh Bed Leveling:"); - - #elif ENABLED(AUTO_BED_LEVELING_UBL) - - config_heading(forReplay, NUL_STR, false); - if (!forReplay) { - ubl.echo_name(); - SERIAL_CHAR(':'); - SERIAL_EOL(); - } - - #elif HAS_ABL_OR_UBL - - CONFIG_ECHO_HEADING("Auto Bed Leveling:"); - - #endif - - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M420 S"), planner.leveling_active - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) - #endif - ); + gcode.M420_report(forReplay); #if ENABLED(MESH_BED_LEVELING) @@ -3318,11 +3109,8 @@ void MarlinSettings::reset() { if (!forReplay) { SERIAL_EOL(); ubl.report_state(); - config_heading(false, PSTR("Active Mesh Slot: "), false); - SERIAL_ECHOLN(ubl.storage_slot); - config_heading(false, PSTR("EEPROM can hold "), false); - SERIAL_ECHO(calc_num_meshes()); - SERIAL_ECHOLNPGM(" meshes.\n"); + SERIAL_ECHO_MSG("Active Mesh Slot ", ubl.storage_slot); + SERIAL_ECHO_MSG("EEPROM can hold ", calc_num_meshes(), " meshes.\n"); } //ubl.report_current_mesh(); // This is too verbose for large meshes. A better (more terse) @@ -3343,602 +3131,150 @@ void MarlinSettings::reset() { #endif // HAS_LEVELING - #if ENABLED(EDITABLE_SERVO_ANGLES) + // + // Editable Servo Angles + // + TERN_(EDITABLE_SERVO_ANGLES, gcode.M281_report(forReplay)); - CONFIG_ECHO_HEADING("Servo Angles:"); - LOOP_L_N(i, NUM_SERVOS) { - switch (i) { - #if ENABLED(SWITCHING_EXTRUDER) - case SWITCHING_EXTRUDER_SERVO_NR: - #if EXTRUDERS > 3 - case SWITCHING_EXTRUDER_E23_SERVO_NR: - #endif - #elif ENABLED(SWITCHING_NOZZLE) - case SWITCHING_NOZZLE_SERVO_NR: - #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) - case Z_PROBE_SERVO_NR: - #endif - CONFIG_ECHO_MSG(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]); - default: break; - } - } - - #endif // EDITABLE_SERVO_ANGLES - - #if HAS_SCARA_OFFSET - - CONFIG_ECHO_HEADING("SCARA settings: S P T"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M665 S"), segments_per_second - , SP_P_STR, scara_home_offset.a - , SP_T_STR, scara_home_offset.b - , SP_Z_STR, LINEAR_UNIT(scara_home_offset.z) - ); - - #elif ENABLED(DELTA) - - CONFIG_ECHO_HEADING("Delta settings: L R H S XYZ ABC"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) - , PSTR(" R"), LINEAR_UNIT(delta_radius) - , PSTR(" H"), LINEAR_UNIT(delta_height) - , PSTR(" S"), segments_per_second - , SP_X_STR, LINEAR_UNIT(delta_tower_angle_trim.a) - , SP_Y_STR, LINEAR_UNIT(delta_tower_angle_trim.b) - , SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c) - , PSTR(" A"), LINEAR_UNIT(delta_diagonal_rod_trim.a) - , PSTR(" B"), LINEAR_UNIT(delta_diagonal_rod_trim.b) - , PSTR(" C"), LINEAR_UNIT(delta_diagonal_rod_trim.c) - ); - - #endif + // + // Delta / SCARA Kinematics + // + TERN_(IS_KINEMATIC, gcode.M665_report(forReplay)); + // + // M666 Endstops Adjustment + // #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) - M666_report(forReplay); + gcode.M666_report(forReplay); #endif + // + // Z Auto-Align + // + TERN_(Z_STEPPER_AUTO_ALIGN, gcode.M422_report(forReplay)); + + // + // LCD Preheat Settings + // #if PREHEAT_COUNT - - CONFIG_ECHO_HEADING("Material heatup parameters:"); - LOOP_L_N(i, PREHEAT_COUNT) { - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M145 S"), i - #if HAS_HOTEND - , PSTR(" H"), parser.to_temp_units(ui.material_preset[i].hotend_temp) - #endif - #if HAS_HEATED_BED - , SP_B_STR, parser.to_temp_units(ui.material_preset[i].bed_temp) - #endif - #if HAS_FAN - , PSTR(" F"), ui.material_preset[i].fan_speed - #endif - ); - } - + gcode.M145_report(forReplay); #endif - #if HAS_PID_HEATING - - CONFIG_ECHO_HEADING("PID settings:"); - - #if ENABLED(PIDTEMP) - HOTEND_LOOP() { - CONFIG_ECHO_START(); - SERIAL_ECHOPAIR_P( - #if ENABLED(PID_PARAMS_PER_HOTEND) - PSTR(" M301 E"), e, - SP_P_STR - #else - PSTR(" M301 P") - #endif - , PID_PARAM(Kp, e) - , PSTR(" I"), unscalePID_i(PID_PARAM(Ki, e)) - , PSTR(" D"), unscalePID_d(PID_PARAM(Kd, e)) - ); - #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPAIR_P(SP_C_STR, PID_PARAM(Kc, e)); - if (e == 0) SERIAL_ECHOPAIR(" L", thermalManager.lpq_len); - #endif - #if ENABLED(PID_FAN_SCALING) - SERIAL_ECHOPAIR(" F", PID_PARAM(Kf, e)); - #endif - SERIAL_EOL(); - } - #endif // PIDTEMP - - #if ENABLED(PIDTEMPBED) - CONFIG_ECHO_MSG( - " M304 P", thermalManager.temp_bed.pid.Kp - , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) - , " D", unscalePID_d(thermalManager.temp_bed.pid.Kd) - ); - #endif - - #if ENABLED(PIDTEMPCHAMBER) - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR( - " M309 P", thermalManager.temp_chamber.pid.Kp - , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) - , " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd) - ); - #endif - - #endif // PIDTEMP || PIDTEMPBED || PIDTEMPCHAMBER + // + // PID + // + TERN_(PIDTEMP, gcode.M301_report(forReplay)); + TERN_(PIDTEMPBED, gcode.M304_report(forReplay)); + TERN_(PIDTEMPCHAMBER, gcode.M309_report(forReplay)); #if HAS_USER_THERMISTORS - CONFIG_ECHO_HEADING("User thermistors:"); LOOP_L_N(i, USER_THERMISTORS) - thermalManager.log_user_thermistor(i, true); + thermalManager.M305_report(i, forReplay); #endif - #if HAS_LCD_CONTRAST - CONFIG_ECHO_HEADING("LCD Contrast:"); - CONFIG_ECHO_MSG(" M250 C", ui.contrast); - #endif + // + // LCD Contrast + // + TERN_(HAS_LCD_CONTRAST, gcode.M250_report(forReplay)); - #if HAS_LCD_BRIGHTNESS - CONFIG_ECHO_HEADING("LCD Brightness:"); - CONFIG_ECHO_MSG(" M256 B", ui.brightness); - #endif + // + // LCD Brightness + // + TERN_(HAS_LCD_BRIGHTNESS, gcode.M256_report(forReplay)); - TERN_(CONTROLLER_FAN_EDITABLE, M710_report(forReplay)); + // + // Controller Fan + // + TERN_(CONTROLLER_FAN_EDITABLE, gcode.M710_report(forReplay)); - #if ENABLED(POWER_LOSS_RECOVERY) - CONFIG_ECHO_HEADING("Power-Loss Recovery:"); - CONFIG_ECHO_MSG(" M413 S", recovery.enabled); - #endif + // + // Power-Loss Recovery + // + TERN_(POWER_LOSS_RECOVERY, gcode.M413_report(forReplay)); + // + // Firmware Retraction + // #if ENABLED(FWRETRACT) - fwretract.M207_report(forReplay); - fwretract.M208_report(forReplay); - TERN_(FWRETRACT_AUTORETRACT, fwretract.M209_report(forReplay)); + gcode.M207_report(forReplay); + gcode.M208_report(forReplay); + TERN_(FWRETRACT_AUTORETRACT, gcode.M209_report(forReplay)); #endif - /** - * Probe Offset - */ - #if HAS_BED_PROBE - config_heading(forReplay, PSTR("Z-Probe Offset"), false); - if (!forReplay) say_units(true); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - #if HAS_PROBE_XY_OFFSET - PSTR(" M851 X"), LINEAR_UNIT(probe.offset_xy.x), - SP_Y_STR, LINEAR_UNIT(probe.offset_xy.y), - SP_Z_STR - #else - PSTR(" M851 X0 Y0 Z") - #endif - , LINEAR_UNIT(probe.offset.z) - ); - #endif + // + // Probe Offset + // + TERN_(HAS_BED_PROBE, gcode.M851_report(forReplay)); - /** - * Bed Skew Correction - */ - #if ENABLED(SKEW_CORRECTION_GCODE) - CONFIG_ECHO_HEADING("Skew Factor: "); - CONFIG_ECHO_START(); - #if ENABLED(SKEW_CORRECTION_FOR_Z) - SERIAL_ECHOPAIR_F(" M852 I", LINEAR_UNIT(planner.skew_factor.xy), 6); - SERIAL_ECHOPAIR_F(" J", LINEAR_UNIT(planner.skew_factor.xz), 6); - SERIAL_ECHOLNPAIR_F(" K", LINEAR_UNIT(planner.skew_factor.yz), 6); - #else - SERIAL_ECHOLNPAIR_F(" M852 S", LINEAR_UNIT(planner.skew_factor.xy), 6); - #endif - #endif + // + // Bed Skew Correction + // + TERN_(SKEW_CORRECTION_GCODE, gcode.M852_report(forReplay)); #if HAS_TRINAMIC_CONFIG + // + // TMC Stepper driver current + // + gcode.M906_report(forReplay); - /** - * TMC stepper driver current - */ - CONFIG_ECHO_HEADING("Stepper driver current:"); + // + // TMC Hybrid Threshold + // + TERN_(HYBRID_THRESHOLD, gcode.M913_report(forReplay)); - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) - say_M906(forReplay); - #if AXIS_IS_TMC(X) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.getMilliamps()); - #endif - #if AXIS_IS_TMC(Y) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.getMilliamps()); - #endif - #if AXIS_IS_TMC(Z) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); - #endif - SERIAL_EOL(); - #endif - - #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) - say_M906(forReplay); - SERIAL_ECHOPGM(" I1"); - #if AXIS_IS_TMC(X2) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.getMilliamps()); - #endif - #if AXIS_IS_TMC(Y2) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.getMilliamps()); - #endif - #if AXIS_IS_TMC(Z2) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); - #endif - SERIAL_EOL(); - #endif - - #if AXIS_IS_TMC(Z3) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps()); - #endif - - #if AXIS_IS_TMC(Z4) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); - #endif - - #if AXIS_IS_TMC(I) - say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); - #endif - #if AXIS_IS_TMC(J) - say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); - #endif - #if AXIS_IS_TMC(K) - say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); - #endif - - #if AXIS_IS_TMC(E0) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); - #endif - #if AXIS_IS_TMC(E1) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T1 E", stepperE1.getMilliamps()); - #endif - #if AXIS_IS_TMC(E2) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T2 E", stepperE2.getMilliamps()); - #endif - #if AXIS_IS_TMC(E3) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T3 E", stepperE3.getMilliamps()); - #endif - #if AXIS_IS_TMC(E4) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T4 E", stepperE4.getMilliamps()); - #endif - #if AXIS_IS_TMC(E5) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T5 E", stepperE5.getMilliamps()); - #endif - #if AXIS_IS_TMC(E6) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T6 E", stepperE6.getMilliamps()); - #endif - #if AXIS_IS_TMC(E7) - say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T7 E", stepperE7.getMilliamps()); - #endif - SERIAL_EOL(); - - /** - * TMC Hybrid Threshold - */ - #if ENABLED(HYBRID_THRESHOLD) - CONFIG_ECHO_HEADING("Hybrid Threshold:"); - #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP - say_M913(forReplay); - #if X_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); - #endif - #if Y_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); - #endif - #if Z_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); - #endif - SERIAL_EOL(); - #endif - - #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOPGM(" I1"); - #if X2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); - #endif - #if Y2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); - #endif - #if Z2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); - #endif - SERIAL_EOL(); - #endif - - #if Z3_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); - #endif - - #if Z4_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); - #endif - - #if I_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); - #endif - #if J_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); - #endif - #if K_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); - #endif - - #if E0_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); - #endif - #if E1_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); - #endif - #if E2_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); - #endif - #if E3_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); - #endif - #if E4_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); - #endif - #if E5_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); - #endif - #if E6_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); - #endif - #if E7_HAS_STEALTHCHOP - say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); - #endif - SERIAL_EOL(); - #endif // HYBRID_THRESHOLD - - /** - * TMC Sensorless homing thresholds - */ - #if USE_SENSORLESS - CONFIG_ECHO_HEADING("StallGuard threshold:"); - #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - #if X_SENSORLESS - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.homing_threshold()); - #endif - #if Y_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.homing_threshold()); - #endif - #if Z_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.homing_threshold()); - #endif - SERIAL_EOL(); - #endif - - #if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOPGM(" I1"); - #if X2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.homing_threshold()); - #endif - #if Y2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.homing_threshold()); - #endif - #if Z2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.homing_threshold()); - #endif - SERIAL_EOL(); - #endif - - #if Z3_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold()); - #endif - - #if Z4_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); - #endif - - #if I_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); - #endif - #if J_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); - #endif - #if K_SENSORLESS - CONFIG_ECHO_START(); - say_M914(); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); - #endif - - #endif // USE_SENSORLESS - - /** - * TMC stepping mode - */ - #if HAS_STEALTHCHOP - CONFIG_ECHO_HEADING("Driver stepping mode:"); - const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()), - chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()), - chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()), - chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()), - chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()), - chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()); - - if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) { - say_M569(forReplay); - LINEAR_AXIS_CODE( - if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR), - if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR), - if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR), - if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR), - if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR), - if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR) - ); - SERIAL_EOL(); - } - - const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()), - chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()), - chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop()); - - if (chop_x2 || chop_y2 || chop_z2) { - say_M569(forReplay, PSTR("I1")); - if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR); - if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR); - if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR); - SERIAL_EOL(); - } - - if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); } - if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); } - - if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); } - if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); } - if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); } - - if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); } - if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); } - if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); } - if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); } - if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); } - if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); } - if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); } - if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); } - - #endif // HAS_STEALTHCHOP - - #endif // HAS_TRINAMIC_CONFIG - - /** - * Linear Advance - */ - #if ENABLED(LIN_ADVANCE) - CONFIG_ECHO_HEADING("Linear Advance:"); - #if EXTRUDERS < 2 - CONFIG_ECHO_MSG(" M900 K", planner.extruder_advance_K[0]); - #else - LOOP_L_N(i, EXTRUDERS) - CONFIG_ECHO_MSG(" M900 T", i, " K", planner.extruder_advance_K[i]); - #endif + // + // TMC Sensorless homing thresholds + // + TERN_(USE_SENSORLESS, gcode.M914_report(forReplay)); #endif - #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM) - CONFIG_ECHO_HEADING("Stepper motor currents:"); - CONFIG_ECHO_START(); - #if HAS_MOTOR_CURRENT_PWM - SERIAL_ECHOLNPAIR_P( // PWM-based has 3 values: - PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y - , SP_Z_STR, stepper.motor_current_setting[1] // Z - , SP_E_STR, stepper.motor_current_setting[2] // E - ); - #elif HAS_MOTOR_CURRENT_SPI - SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: - LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default) - SERIAL_CHAR(' ', axis_codes[q]); - SERIAL_ECHO(stepper.motor_current_setting[q]); - } - SERIAL_CHAR(' ', 'B'); // B (maps to E1 by default) - SERIAL_ECHOLN(stepper.motor_current_setting[4]); - #endif - #elif HAS_MOTOR_CURRENT_I2C // i2c-based has any number of values - // Values sent over i2c are not stored. - // Indexes map directly to drivers, not axes. - #elif HAS_MOTOR_CURRENT_DAC // DAC-based has 4 values, for X Y Z (I J K) E - // Values sent over i2c are not stored. Uses indirect mapping. + // + // TMC stepping mode + // + TERN_(HAS_STEALTHCHOP, gcode.M569_report(forReplay)); + + // + // Linear Advance + // + TERN_(LIN_ADVANCE, gcode.M900_report(forReplay)); + + // + // Motor Current (SPI or PWM) + // + #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM + gcode.M907_report(forReplay); #endif - /** - * Advanced Pause filament load & unload lengths - */ - #if ENABLED(ADVANCED_PAUSE_FEATURE) - CONFIG_ECHO_HEADING("Filament load/unload lengths:"); - #if EXTRUDERS == 1 - say_M603(forReplay); - SERIAL_ECHOLNPAIR("L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length)); - #else - auto echo_603 = [](const bool f, const uint8_t n) { say_M603(f); SERIAL_ECHOLNPAIR("T", n, " L", LINEAR_UNIT(fc_settings[n].load_length), " U", LINEAR_UNIT(fc_settings[n].unload_length)); }; - LOOP_L_N(i, EXTRUDERS) echo_603(forReplay, i); - #endif - #endif + // + // Advanced Pause filament load & unload lengths + // + TERN_(ADVANCED_PAUSE_FEATURE, gcode.M603_report(forReplay)); - #if HAS_MULTI_EXTRUDER - CONFIG_ECHO_HEADING("Tool-changing:"); - CONFIG_ECHO_START(); - M217_report(true); - #endif + // + // Tool-changing Parameters + // + TERN_(HAS_MULTI_EXTRUDER, gcode.M217_report(forReplay)); - #if ENABLED(BACKLASH_GCODE) - CONFIG_ECHO_HEADING("Backlash compensation:"); - CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR_P( - PSTR(" M425 F"), backlash.get_correction() - , LIST_N(DOUBLE(LINEAR_AXES), - SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), - SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), - SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), - SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), - SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), - SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) - ) - #ifdef BACKLASH_SMOOTHING_MM - , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) - #endif - ); - #endif + // + // Backlash Compensation + // + TERN_(BACKLASH_GCODE, gcode.M425_report(forReplay)); - #if HAS_FILAMENT_SENSOR - CONFIG_ECHO_HEADING("Filament runout sensor:"); - CONFIG_ECHO_MSG( - " M412 S", runout.enabled - #if HAS_FILAMENT_RUNOUT_DISTANCE - , " D", LINEAR_UNIT(runout.runout_distance()) - #endif - ); - #endif + // + // Filament Runout Sensor + // + TERN_(HAS_FILAMENT_SENSOR, gcode.M412_report(forReplay)); #if HAS_ETHERNET - CONFIG_ECHO_HEADING("Ethernet:"); - if (!forReplay) { CONFIG_ECHO_START(); ETH0_report(); } + CONFIG_ECHO_HEADING("Ethernet"); + if (!forReplay) ETH0_report(); CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); MAC_report(); - CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M552_report(); - CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M553_report(); - CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); M554_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); gcode.M552_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); gcode.M553_report(); + CONFIG_ECHO_START(); SERIAL_ECHO_SP(2); gcode.M554_report(); #endif - #if HAS_MULTI_LANGUAGE - CONFIG_ECHO_HEADING("UI Language:"); - CONFIG_ECHO_MSG(" M414 S", ui.language); - #endif + TERN_(HAS_MULTI_LANGUAGE, gcode.M414_report(forReplay)); } #endif // !DISABLE_M503 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1bb86ed4c7..934f734e9c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -59,6 +59,10 @@ #include "../feature/host_actions.h" #endif +#if HAS_TEMP_SENSOR + #include "../gcode/gcode.h" +#endif + // MAX TC related macros #define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) #define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) @@ -1722,13 +1726,9 @@ void Temperature::manage_heater() { COPY(user_thermistor, default_user_thermistor); } - void Temperature::log_user_thermistor(const uint8_t t_index, const bool eprom/*=false*/) { - - if (eprom) - SERIAL_ECHOPGM(" M305 "); - else - SERIAL_ECHO_START(); - SERIAL_CHAR('P', '0' + t_index); + void Temperature::M305_report(const uint8_t t_index, const bool forReplay/*=true*/) { + gcode.report_heading_etc(forReplay, PSTR(STR_USER_THERMISTORS)); + SERIAL_ECHOPAIR(" M305 P", AS_DIGIT(t_index)); const user_thermistor_t &t = user_thermistor[t_index]; @@ -1794,13 +1794,13 @@ void Temperature::manage_heater() { // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. celsius_float_t Temperature::analog_to_celsius_hotend(const int16_t raw, const uint8_t e) { - if (e >= HOTENDS) { - SERIAL_ERROR_START(); - SERIAL_ECHO(e); - SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); - kill(); - return 0; - } + if (e >= HOTENDS) { + SERIAL_ERROR_START(); + SERIAL_ECHO(e); + SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); + kill(); + return 0; + } switch (e) { case 0: @@ -3490,9 +3490,6 @@ void Temperature::isr() { } #if HAS_TEMP_SENSOR - - #include "../gcode/gcode.h" - /** * Print a single heater state in the form: * Bed: " B:nnn.nn /nnn.nn" diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index c78dfa9372..1675507f86 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -527,7 +527,7 @@ class Temperature { #if HAS_USER_THERMISTORS static user_thermistor_t user_thermistor[USER_THERMISTORS]; - static void log_user_thermistor(const uint8_t t_index, const bool eprom=false); + static void M305_report(const uint8_t t_index, const bool forReplay=true); static void reset_user_thermistors(); static celsius_float_t user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw); static inline bool set_pull_up_res(int8_t t_index, float value) { From 754b31918a73cb08c322102be5d3926d2ac59c18 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Sep 2021 04:57:05 -0500 Subject: [PATCH 0650/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fewer=20serial=20macro?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/fastio.cpp | 10 +-- Marlin/src/HAL/AVR/pinsDebug.h | 16 ++-- Marlin/src/HAL/DUE/eeprom_flash.cpp | 34 ++++----- Marlin/src/HAL/DUE/pinsDebug.h | 2 +- Marlin/src/HAL/ESP32/wifi.cpp | 2 +- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 8 +- Marlin/src/HAL/SAMD51/pinsDebug.h | 2 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 16 ++-- Marlin/src/HAL/STM32/pinsDebug.h | 2 +- Marlin/src/HAL/STM32/usb_host.cpp | 6 +- Marlin/src/HAL/shared/Delay.cpp | 6 +- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/core/bug_on.h | 12 +-- Marlin/src/core/debug_out.h | 22 ++---- Marlin/src/core/serial.cpp | 2 +- Marlin/src/core/serial.h | 36 ++++----- Marlin/src/core/utility.cpp | 12 +-- Marlin/src/feature/backlash.cpp | 4 +- Marlin/src/feature/bedlevel/abl/abl.cpp | 10 +-- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 2 +- Marlin/src/feature/bedlevel/ubl/ubl.h | 8 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 60 +++++++-------- Marlin/src/feature/binary_stream.h | 14 ++-- Marlin/src/feature/bltouch.cpp | 8 +- Marlin/src/feature/dac/stepper_dac.cpp | 8 +- Marlin/src/feature/encoder_i2c.cpp | 54 +++++++------- Marlin/src/feature/encoder_i2c.h | 12 +-- Marlin/src/feature/fwretract.cpp | 34 ++++----- Marlin/src/feature/joystick.cpp | 6 +- Marlin/src/feature/max7219.cpp | 2 +- Marlin/src/feature/meatpack.cpp | 2 +- Marlin/src/feature/mixing.cpp | 4 +- Marlin/src/feature/mixing.h | 2 +- Marlin/src/feature/mmu/mmu2.cpp | 18 ++--- Marlin/src/feature/pause.cpp | 18 ++--- Marlin/src/feature/powerloss.cpp | 34 ++++----- Marlin/src/feature/probe_temp_comp.cpp | 4 +- Marlin/src/feature/repeat.cpp | 8 +- Marlin/src/feature/runout.cpp | 2 +- Marlin/src/feature/runout.h | 6 +- Marlin/src/feature/tmc_util.cpp | 4 +- Marlin/src/feature/tmc_util.h | 4 +- Marlin/src/feature/twibus.cpp | 2 +- Marlin/src/gcode/bedlevel/G26.cpp | 2 +- Marlin/src/gcode/bedlevel/G35.cpp | 14 ++-- Marlin/src/gcode/bedlevel/M420.cpp | 10 +-- Marlin/src/gcode/bedlevel/abl/G29.cpp | 18 ++--- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 6 +- Marlin/src/gcode/calibrate/G28.cpp | 4 +- Marlin/src/gcode/calibrate/G33.cpp | 6 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 26 +++---- Marlin/src/gcode/calibrate/G425.cpp | 74 +++++++++---------- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 10 +-- Marlin/src/gcode/calibrate/M100.cpp | 36 ++++----- Marlin/src/gcode/calibrate/M425.cpp | 6 +- Marlin/src/gcode/calibrate/M48.cpp | 8 +- Marlin/src/gcode/calibrate/M665.cpp | 4 +- Marlin/src/gcode/calibrate/M666.cpp | 18 ++--- Marlin/src/gcode/config/M200-M205.cpp | 18 ++--- Marlin/src/gcode/config/M217.cpp | 20 ++--- Marlin/src/gcode/config/M218.cpp | 2 +- Marlin/src/gcode/config/M220.cpp | 2 +- Marlin/src/gcode/config/M221.cpp | 2 +- Marlin/src/gcode/config/M281.cpp | 2 +- Marlin/src/gcode/config/M301.cpp | 8 +- Marlin/src/gcode/config/M302.cpp | 2 +- Marlin/src/gcode/config/M309.cpp | 2 +- Marlin/src/gcode/config/M43.cpp | 12 +-- Marlin/src/gcode/config/M92.cpp | 10 +-- Marlin/src/gcode/control/M111.cpp | 8 +- Marlin/src/gcode/control/M211.cpp | 2 +- Marlin/src/gcode/control/M605.cpp | 30 ++++---- Marlin/src/gcode/control/M993_M994.cpp | 4 +- Marlin/src/gcode/control/T.cpp | 2 +- Marlin/src/gcode/eeprom/M500-M504.cpp | 6 +- Marlin/src/gcode/feature/L6470/M122.cpp | 2 +- Marlin/src/gcode/feature/L6470/M906.cpp | 12 +-- Marlin/src/gcode/feature/L6470/M916-918.cpp | 28 +++---- Marlin/src/gcode/feature/advance/M900.cpp | 10 +-- .../src/gcode/feature/controllerfan/M710.cpp | 2 +- .../src/gcode/feature/digipot/M907-M910.cpp | 2 +- .../src/gcode/feature/filwidth/M404-M407.cpp | 4 +- Marlin/src/gcode/feature/mixing/M166.cpp | 6 +- .../src/gcode/feature/password/M510-M512.cpp | 2 +- Marlin/src/gcode/feature/pause/G60.cpp | 2 +- Marlin/src/gcode/feature/pause/G61.cpp | 4 +- Marlin/src/gcode/feature/pause/M603.cpp | 4 +- .../src/gcode/feature/power_monitor/M430.cpp | 2 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 2 +- Marlin/src/gcode/feature/runout/M412.cpp | 4 +- Marlin/src/gcode/feature/trinamic/M906.cpp | 38 +++++----- .../src/gcode/feature/trinamic/M911-M914.cpp | 60 +++++++-------- Marlin/src/gcode/gcode.cpp | 6 +- Marlin/src/gcode/gcode_d.cpp | 6 +- Marlin/src/gcode/geometry/G53-G59.cpp | 4 +- Marlin/src/gcode/geometry/M206_M428.cpp | 2 +- Marlin/src/gcode/host/M114.cpp | 2 +- Marlin/src/gcode/host/M115.cpp | 2 +- Marlin/src/gcode/host/M360.cpp | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/gcode/lcd/M250.cpp | 2 +- Marlin/src/gcode/lcd/M256.cpp | 2 +- Marlin/src/gcode/lcd/M414.cpp | 2 +- Marlin/src/gcode/motion/M290.cpp | 8 +- Marlin/src/gcode/parser.cpp | 16 ++-- Marlin/src/gcode/parser.h | 4 +- Marlin/src/gcode/probe/G30.cpp | 2 +- Marlin/src/gcode/probe/M851.cpp | 12 +-- Marlin/src/gcode/probe/M951.cpp | 14 ++-- Marlin/src/gcode/queue.cpp | 14 ++-- Marlin/src/gcode/units/M149.cpp | 2 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 2 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- .../extui/anycubic_chiron/FileNavigator.cpp | 14 ++-- .../extui/anycubic_chiron/chiron_extui.cpp | 4 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 58 +++++++-------- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 6 +- Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp | 18 ++--- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 60 +++++++-------- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 20 ++--- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 20 ++--- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 48 ++++++------ .../extui/dgus/origin/DGUSScreenHandler.cpp | 20 ++--- .../lcd/extui/dgus_reloaded/DGUSDisplay.cpp | 26 +++---- .../archim2-flash/flash_storage.cpp | 12 +-- .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 2 +- .../ftdi_eve_lib/basic/commands.cpp | 4 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 8 +- .../ftdi_eve_lib/extended/dl_cache.cpp | 12 +-- .../ftdi_eve_lib/extended/screen_types.cpp | 2 +- .../ftdi_eve_lib/extended/screen_types.h | 2 +- Marlin/src/lcd/extui/malyan/malyan.cpp | 14 ++-- Marlin/src/lcd/extui/malyan/malyan_extui.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 12 +-- .../src/lcd/extui/nextion/FileNavigator.cpp | 8 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 12 +-- Marlin/src/lcd/marlinui.cpp | 12 +-- Marlin/src/lcd/menu/menu_configuration.cpp | 2 +- Marlin/src/lcd/menu/menu_tramming.cpp | 6 +- Marlin/src/lcd/tft/tft_string.cpp | 30 ++++---- Marlin/src/lcd/tft_io/touch_calibration.cpp | 10 +-- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 14 ++-- Marlin/src/libs/MAX31865.cpp | 10 +-- Marlin/src/libs/bresenham.h | 4 +- Marlin/src/module/delta.cpp | 4 +- Marlin/src/module/endstops.cpp | 4 +- Marlin/src/module/motion.cpp | 60 +++++++-------- Marlin/src/module/planner.cpp | 46 ++++++------ Marlin/src/module/printcounter.cpp | 14 ++-- Marlin/src/module/probe.cpp | 20 ++--- Marlin/src/module/scara.cpp | 24 +++--- Marlin/src/module/settings.cpp | 22 +++--- Marlin/src/module/stepper.cpp | 4 +- Marlin/src/module/temperature.cpp | 44 +++++------ Marlin/src/module/tool_change.cpp | 34 ++++----- Marlin/src/sd/cardreader.cpp | 50 ++++++------- .../sd/usb_flashdrive/Sd2Card_FlashDrive.cpp | 20 ++--- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 2 +- docs/Serial.md | 8 +- 159 files changed, 1002 insertions(+), 1014 deletions(-) diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp index 70132e71ee..8af3ef805e 100644 --- a/Marlin/src/HAL/AVR/fastio.cpp +++ b/Marlin/src/HAL/AVR/fastio.cpp @@ -267,11 +267,11 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb SET_WGM(5, FAST_PWM_ICRn); // Fast PWM with ICR5 as TOP //SERIAL_ECHOLNPGM("Timer 5 Settings:"); - //SERIAL_ECHOLNPAIR(" Prescaler=", prescaler); - //SERIAL_ECHOLNPAIR(" TOP=", ICR5); - //SERIAL_ECHOLNPAIR(" OCR5A=", OCR5A); - //SERIAL_ECHOLNPAIR(" OCR5B=", OCR5B); - //SERIAL_ECHOLNPAIR(" OCR5C=", OCR5C); + //SERIAL_ECHOLNPGM(" Prescaler=", prescaler); + //SERIAL_ECHOLNPGM(" TOP=", ICR5); + //SERIAL_ECHOLNPGM(" OCR5A=", OCR5A); + //SERIAL_ECHOLNPGM(" OCR5B=", OCR5B); + //SERIAL_ECHOLNPGM(" OCR5C=", OCR5C); } else { // Restore the default for Timer 5 diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 50da32292b..5fc48a1edc 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -235,9 +235,9 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); inline void com_print(const uint8_t N, const uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); - SERIAL_ECHOPAIR(" COM", AS_DIGIT(N)); + SERIAL_ECHOPGM(" COM", AS_DIGIT(N)); SERIAL_CHAR(Z); - SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03)); + SERIAL_ECHOPGM(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03)); } void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - WGM bit layout @@ -247,7 +247,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1)))); if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1); - SERIAL_ECHOPAIR(" TIMER", AS_DIGIT(T)); + SERIAL_ECHOPGM(" TIMER", AS_DIGIT(T)); SERIAL_CHAR(L); SERIAL_ECHO_SP(3); @@ -259,14 +259,14 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - const uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A'); PWM_PRINT(*OCRVAL16); } - SERIAL_ECHOPAIR(" WGM: ", WGM); + SERIAL_ECHOPGM(" WGM: ", WGM); com_print(T,L); - SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) )); - SERIAL_ECHOPAIR(" TCCR", AS_DIGIT(T), "A: ", *TCCRA); - SERIAL_ECHOPAIR(" TCCR", AS_DIGIT(T), "B: ", *TCCRB); + SERIAL_ECHOPGM(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) )); + SERIAL_ECHOPGM(" TCCR", AS_DIGIT(T), "A: ", *TCCRA); + SERIAL_ECHOPGM(" TCCR", AS_DIGIT(T), "B: ", *TCCRB); const uint8_t *TMSK = (uint8_t*)TIMSK(T); - SERIAL_ECHOPAIR(" TIMSK", AS_DIGIT(T), ": ", *TMSK); + SERIAL_ECHOPGM(" TIMSK", AS_DIGIT(T), ": ", *TMSK); const uint8_t OCIE = L - 'A' + 1; if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); } diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index b4cb9912b2..7ce4a84df5 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -200,9 +200,9 @@ static bool ee_PageWrite(uint16_t page, const void *data) { pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i])); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page); - DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_ECHOLNPGM("EEPROM PageWrite ", page); + DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0)); DEBUG_FLUSH(); // Get the page relative to the start of the EFC controller, and the EFC controller to use @@ -246,7 +246,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { __enable_irq(); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page); + DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ", page); return false; } @@ -271,7 +271,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { __enable_irq(); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page); + DEBUG_ECHOLNPGM("EEPROM Write failure for page ", page); return false; } @@ -287,7 +287,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { #ifdef EE_EMU_DEBUG DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page); + DEBUG_ECHOLNPGM("EEPROM Verify Write failure for page ", page); ee_Dump( page, (uint32_t *)addrflash); ee_Dump(-page, data); @@ -306,7 +306,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { } } } - DEBUG_ECHOLNPAIR("--> Differing bits: ", count); + DEBUG_ECHOLNPGM("--> Differing bits: ", count); #endif return false; @@ -326,9 +326,9 @@ static bool ee_PageErase(uint16_t page) { uint32_t addrflash = uint32_t(getFlashStorage(page)); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM PageErase ", page); - DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash); - DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0)); + DEBUG_ECHOLNPGM("EEPROM PageErase ", page); + DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash); + DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0)); DEBUG_FLUSH(); // Get the page relative to the start of the EFC controller, and the EFC controller to use @@ -371,7 +371,7 @@ static bool ee_PageErase(uint16_t page) { __enable_irq(); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page); + DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ",page); return false; } @@ -395,7 +395,7 @@ static bool ee_PageErase(uint16_t page) { __enable_irq(); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page); + DEBUG_ECHOLNPGM("EEPROM Erase failure for page ",page); return false; } @@ -411,7 +411,7 @@ static bool ee_PageErase(uint16_t page) { for (i = 0; i < PageSize >> 2; i++) { if (*aligned_src++ != 0xFFFFFFFF) { DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page); + DEBUG_ECHOLNPGM("EEPROM Verify Erase failure for page ",page); ee_Dump(page, (uint32_t *)addrflash); return false; } @@ -922,7 +922,7 @@ static void ee_Init() { if (curGroup >= GroupCount) curGroup = 0; DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup); + DEBUG_ECHOLNPGM("EEPROM Current Group: ",curGroup); DEBUG_FLUSH(); // Now, validate that all the other group pages are empty @@ -932,7 +932,7 @@ static void ee_Init() { for (int page = 0; page < PagesPerGroup; page++) { if (!ee_IsPageClean(grp * PagesPerGroup + page)) { DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp); + DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on group ", grp); DEBUG_FLUSH(); ee_PageErase(grp * PagesPerGroup + page); } @@ -949,14 +949,14 @@ static void ee_Init() { } DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage); + DEBUG_ECHOLNPGM("EEPROM Active page: ", curPage); DEBUG_FLUSH(); // Make sure the pages following the first clean one are also clean for (int page = curPage + 1; page < PagesPerGroup; page++) { if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) { DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup); + DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on active group ", curGroup); DEBUG_FLUSH(); ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page)); ee_PageErase(curGroup * PagesPerGroup + page); diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index 02a5e6646f..225ba95ce9 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -87,7 +87,7 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input void pwm_details(int32_t pin) { if (pwm_status(pin)) { uint32_t chan = g_APinDescription[pin].ulPWMChannel; - SERIAL_ECHOPAIR("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY); + SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY); } } diff --git a/Marlin/src/HAL/ESP32/wifi.cpp b/Marlin/src/HAL/ESP32/wifi.cpp index f4cf5a606a..060f3bdb48 100644 --- a/Marlin/src/HAL/ESP32/wifi.cpp +++ b/Marlin/src/HAL/ESP32/wifi.cpp @@ -59,7 +59,7 @@ void wifi_init() { MDNS.addService("http", "tcp", 80); - SERIAL_ECHOLNPAIR("Successfully connected to WiFi with SSID '" WIFI_SSID "', hostname: '" WIFI_HOSTNAME "', IP address: ", WiFi.localIP().toString().c_str()); + SERIAL_ECHOLNPGM("Successfully connected to WiFi with SSID '" WIFI_SSID "', hostname: '" WIFI_HOSTNAME "', IP address: ", WiFi.localIP().toString().c_str()); } #endif // WIFISUPPORT diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index 70395251df..122c8ef81a 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -84,15 +84,15 @@ static void debug_rw(const bool write, int &pos, const uint8_t *value, const siz PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); SERIAL_CHAR(' '); SERIAL_ECHOPGM_P(rw_str); - SERIAL_ECHOLNPAIR("_data(", pos, ",", value, ",", size, ", ...)"); + SERIAL_ECHOLNPGM("_data(", pos, ",", value, ",", size, ", ...)"); if (total) { SERIAL_ECHOPGM(" f_"); SERIAL_ECHOPGM_P(rw_str); - SERIAL_ECHOPAIR("()=", s, "\n size=", size, "\n bytes_"); - SERIAL_ECHOLNPAIR_P(write ? PSTR("written=") : PSTR("read="), total); + SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_"); + SERIAL_ECHOLNPGM_P(write ? PSTR("written=") : PSTR("read="), total); } else - SERIAL_ECHOLNPAIR(" f_lseek()=", s); + SERIAL_ECHOLNPGM(" f_lseek()=", s); } // File function return codes for type FRESULT. This goes away soon, but diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h index 5c86d0c071..f0a46fd7c5 100644 --- a/Marlin/src/HAL/SAMD51/pinsDebug.h +++ b/Marlin/src/HAL/SAMD51/pinsDebug.h @@ -48,7 +48,7 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input void pwm_details(int32_t pin) { if (pwm_status(pin)) { //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; - //SERIAL_ECHOPAIR("PWM = ", duty); + //SERIAL_ECHOPGM("PWM = ", duty); } } diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index e785e59249..252b057362 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -133,7 +133,7 @@ bool PersistentStore::access_start() { // load current settings uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot); for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i]; - DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, "."); + DEBUG_ECHOLNPGM("EEPROM loaded from slot ", current_slot, "."); } eeprom_data_written = false; } @@ -179,9 +179,9 @@ bool PersistentStore::access_finish() { ENABLE_ISRS(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { - DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status); - DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError()); - DEBUG_ECHOLNPAIR("SectorError=", SectorError); + DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); + DEBUG_ECHOLNPGM("GetError=", HAL_FLASH_GetError()); + DEBUG_ECHOLNPGM("SectorError=", SectorError); LOCK_FLASH(); return false; } @@ -204,9 +204,9 @@ bool PersistentStore::access_finish() { offset += sizeof(uint32_t); } else { - DEBUG_ECHOLNPAIR("HAL_FLASH_Program=", status); - DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError()); - DEBUG_ECHOLNPAIR("address=", address); + DEBUG_ECHOLNPGM("HAL_FLASH_Program=", status); + DEBUG_ECHOLNPGM("GetError=", HAL_FLASH_GetError()); + DEBUG_ECHOLNPGM("address=", address); success = false; break; } @@ -216,7 +216,7 @@ bool PersistentStore::access_finish() { if (success) { eeprom_data_written = false; - DEBUG_ECHOLNPAIR("EEPROM saved to slot ", current_slot, "."); + DEBUG_ECHOLNPGM("EEPROM saved to slot ", current_slot, "."); } return success; diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index ff671a6ebf..c77dbc4c75 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -237,7 +237,7 @@ void pwm_details(const pin_t Ard_num) { if (over_7) pin_number -= 8; uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F; - SERIAL_ECHOPAIR("Alt Function: ", alt_func); + SERIAL_ECHOPGM("Alt Function: ", alt_func); if (alt_func < 10) SERIAL_CHAR(' '); SERIAL_ECHOPGM(" - "); switch (alt_func) { diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index d2d1d69a1a..f0879a36a4 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -88,9 +88,9 @@ void USBHost::setUsbTaskState(uint8_t state) { capacity = info.capacity.block_nbr / 2000; block_size = info.capacity.block_size; block_count = info.capacity.block_nbr; - // SERIAL_ECHOLNPAIR("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr); - // SERIAL_ECHOLNPAIR("info.capacity.block_size: %d\n", info.capacity.block_size); - // SERIAL_ECHOLNPAIR("capacity : %d MB\n", capacity); + //SERIAL_ECHOLNPGM("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr); + //SERIAL_ECHOLNPGM("info.capacity.block_size: %d\n", info.capacity.block_size); + //SERIAL_ECHOLNPGM("capacity : %d MB\n", capacity); } }; diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index 129698fd30..05af38307b 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -110,16 +110,16 @@ auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) { SERIAL_ECHOPGM("Calling "); SERIAL_ECHOPGM_P(name); - SERIAL_ECHOLNPAIR(" for ", cycles); + SERIAL_ECHOLNPGM(" for ", cycles); SERIAL_ECHOPGM_P(unit); - SERIAL_ECHOLNPAIR(" took: ", total); + SERIAL_ECHOLNPGM(" took: ", total); SERIAL_ECHOPGM_P(unit); if (do_flush) SERIAL_FLUSHTX(); }; uint32_t s, e; - SERIAL_ECHOLNPAIR("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION); + SERIAL_ECHOLNPGM("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION); SERIAL_FLUSH(); // Display the results of the calibration above constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 }; diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 49db8c61b9..5bbfcd087b 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -798,7 +798,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { void idle(bool no_stepper_sleep/*=false*/) { #if ENABLED(MARLIN_DEV_MODE) static uint16_t idle_depth = 0; - if (++idle_depth > 5) SERIAL_ECHOLNPAIR("idle() call depth: ", idle_depth); + if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth); #endif // Core Marlin activities @@ -1623,7 +1623,7 @@ void setup() { #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) const millis_t elapsed = millis() - bootscreen_ms; #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPAIR("elapsed=", elapsed); + SERIAL_ECHOLNPGM("elapsed=", elapsed); #endif SETUP_RUN(ui.bootscreen_completion(elapsed)); #endif diff --git a/Marlin/src/core/bug_on.h b/Marlin/src/core/bug_on.h index cc745f259b..7f1243ed40 100644 --- a/Marlin/src/core/bug_on.h +++ b/Marlin/src/core/bug_on.h @@ -20,19 +20,19 @@ */ #pragma once -// We need SERIAL_ECHOPAIR and macros.h +// We need SERIAL_ECHOPGM and macros.h #include "serial.h" #if ENABLED(POSTMORTEM_DEBUGGING) // Useful macro for stopping the CPU on an unexpected condition - // This is used like SERIAL_ECHOPAIR, that is: a key-value call of the local variables you want + // This is used like SERIAL_ECHOPGM, that is: a key-value call of the local variables you want // to dump to the serial port before stopping the CPU. - // \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building - #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0) + // \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building + #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0) #elif ENABLED(MARLIN_DEV_MODE) // Don't stop the CPU here, but at least dump the bug on the serial port - // \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building - #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); } while(0) + // \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building + #define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); } while(0) #else // Release mode, let's ignore the bug #define BUG_ON(V...) NOOP diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index a7dc32622d..3187e03254 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -27,7 +27,6 @@ // #undef DEBUG_SECTION -#undef DEBUG_ECHOPGM_P #undef DEBUG_ECHO_START #undef DEBUG_ERROR_START #undef DEBUG_CHAR @@ -37,12 +36,10 @@ #undef DEBUG_ECHOLN #undef DEBUG_ECHOPGM #undef DEBUG_ECHOLNPGM -#undef DEBUG_ECHOPAIR -#undef DEBUG_ECHOPAIR_P +#undef DEBUG_ECHOPGM_P +#undef DEBUG_ECHOLNPGM_P #undef DEBUG_ECHOPAIR_F #undef DEBUG_ECHOPAIR_F_P -#undef DEBUG_ECHOLNPAIR -#undef DEBUG_ECHOLNPAIR_P #undef DEBUG_ECHOLNPAIR_F #undef DEBUG_ECHOLNPAIR_F_P #undef DEBUG_ECHO_MSG @@ -69,12 +66,12 @@ #define DEBUG_ECHOLN SERIAL_ECHOLN #define DEBUG_ECHOPGM SERIAL_ECHOPGM #define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM - #define DEBUG_ECHOPAIR SERIAL_ECHOPAIR - #define DEBUG_ECHOPAIR_P SERIAL_ECHOPAIR_P + #define DEBUG_ECHOPGM SERIAL_ECHOPGM + #define DEBUG_ECHOPGM_P SERIAL_ECHOPGM_P #define DEBUG_ECHOPAIR_F SERIAL_ECHOPAIR_F #define DEBUG_ECHOPAIR_F_P SERIAL_ECHOPAIR_F_P - #define DEBUG_ECHOLNPAIR SERIAL_ECHOLNPAIR - #define DEBUG_ECHOLNPAIR_P SERIAL_ECHOLNPAIR_P + #define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM + #define DEBUG_ECHOLNPGM_P SERIAL_ECHOLNPGM_P #define DEBUG_ECHOLNPAIR_F SERIAL_ECHOLNPAIR_F #define DEBUG_ECHOLNPAIR_F_P SERIAL_ECHOLNPAIR_F_P #define DEBUG_ECHO_MSG SERIAL_ECHO_MSG @@ -89,7 +86,6 @@ #else #define DEBUG_SECTION(...) NOOP - #define DEBUG_ECHOPGM_P(P) NOOP #define DEBUG_ECHO_START() NOOP #define DEBUG_ERROR_START() NOOP #define DEBUG_CHAR(...) NOOP @@ -99,12 +95,10 @@ #define DEBUG_ECHOLN(...) NOOP #define DEBUG_ECHOPGM(...) NOOP #define DEBUG_ECHOLNPGM(...) NOOP - #define DEBUG_ECHOPAIR(...) NOOP - #define DEBUG_ECHOPAIR_P(...) NOOP + #define DEBUG_ECHOPGM_P(...) NOOP + #define DEBUG_ECHOLNPGM_P(...) NOOP #define DEBUG_ECHOPAIR_F(...) NOOP #define DEBUG_ECHOPAIR_F_P(...) NOOP - #define DEBUG_ECHOLNPAIR(...) NOOP - #define DEBUG_ECHOLNPAIR_P(...) NOOP #define DEBUG_ECHOLNPAIR_F(...) NOOP #define DEBUG_ECHOLNPAIR_F_P(...) NOOP #define DEBUG_ECHO_MSG(...) NOOP diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 50cc50ad57..8c9f4a8e4d 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -96,7 +96,7 @@ void print_bin(uint16_t val) { void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); - SERIAL_ECHOPAIR_P( + SERIAL_ECHOPGM_P( LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k) ); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index a3d640ee1a..05d80a4829 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -188,44 +188,44 @@ inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } void serialprintPGM(PGM_P str); // -// SERIAL_ECHOPAIR... macros are used to output string-value pairs. +// SERIAL_ECHOPGM... macros are used to output string-value pairs. // // Print up to 20 pairs of values. Odd elements must be literal strings. #define __SEP_N(N,V...) _SEP_##N(V) #define _SEP_N(N,V...) __SEP_N(N,V) #define _SEP_N_REF() _SEP_N -#define _SEP_1(s) SERIAL_ECHOPGM(s); +#define _SEP_1(s) serialprintPGM(PSTR(s)); #define _SEP_2(s,v) serial_echopair_PGM(PSTR(s),v); #define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V); -#define SERIAL_ECHOPAIR(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) +#define SERIAL_ECHOPGM(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) // Print up to 20 pairs of values followed by newline. Odd elements must be literal strings. #define __SELP_N(N,V...) _SELP_##N(V) #define _SELP_N(N,V...) __SELP_N(N,V) #define _SELP_N_REF() _SELP_N -#define _SELP_1(s) SERIAL_ECHOLNPGM(s); +#define _SELP_1(s) serialprintPGM(PSTR(s "\n")); #define _SELP_2(s,v) serial_echopair_PGM(PSTR(s),v); SERIAL_EOL(); #define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V); -#define SERIAL_ECHOLNPAIR(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) +#define SERIAL_ECHOLNPGM(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) // Print up to 20 pairs of values. Odd elements must be PSTR pointers. #define __SEP_N_P(N,V...) _SEP_##N##_P(V) #define _SEP_N_P(N,V...) __SEP_N_P(N,V) #define _SEP_N_P_REF() _SEP_N_P -#define _SEP_1_P(s) serialprintPGM(s); -#define _SEP_2_P(s,v) serial_echopair_PGM(s,v); -#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); -#define SERIAL_ECHOPAIR_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) +#define _SEP_1_P(p) serialprintPGM(p); +#define _SEP_2_P(p,v) serial_echopair_PGM(p,v); +#define _SEP_3_P(p,v,V...) _SEP_2_P(p,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOPGM_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) // Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers. #define __SELP_N_P(N,V...) _SELP_##N##_P(V) #define _SELP_N_P(N,V...) __SELP_N_P(N,V) #define _SELP_N_P_REF() _SELP_N_P -#define _SELP_1_P(s) { serialprintPGM(s); SERIAL_EOL(); } -#define _SELP_2_P(s,v) { serial_echopair_PGM(s,v); SERIAL_EOL(); } -#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } -#define SERIAL_ECHOLNPAIR_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) +#define _SELP_1_P(p) { serialprintPGM(p); SERIAL_EOL(); } +#define _SELP_2_P(p,v) { serial_echopair_PGM(p,v); SERIAL_EOL(); } +#define _SELP_3_P(p,v,V...) { _SEP_2_P(p,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } +#define SERIAL_ECHOLNPGM_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) #ifdef AllowDifferentTypeInList @@ -261,12 +261,6 @@ void serialprintPGM(PGM_P str); #endif -#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P)) -#define SERIAL_ECHOLNPGM_P(P) do{ serialprintPGM(P); SERIAL_EOL(); }while(0) - -#define SERIAL_ECHOPGM(S) (serialprintPGM(PSTR(S))) -#define SERIAL_ECHOLNPGM(S) (serialprintPGM(PSTR(S "\n"))) - #define SERIAL_ECHOPAIR_F_P(P,V...) do{ serialprintPGM(P); SERIAL_ECHO_F(V); }while(0) #define SERIAL_ECHOLNPAIR_F_P(V...) do{ SERIAL_ECHOPAIR_F_P(V); SERIAL_EOL(); }while(0) @@ -277,8 +271,8 @@ void serialprintPGM(PGM_P str); #define SERIAL_ERROR_START() serial_error_start() #define SERIAL_EOL() SERIAL_CHAR('\n') -#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0) -#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPAIR(V); }while(0) +#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) +#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0) #define SERIAL_ECHO_SP(C) serial_spaces(C) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index b810855d52..8aeec89f02 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -79,9 +79,9 @@ void safe_delay(millis_t ms) { #if HAS_BED_PROBE #if !HAS_PROBE_XY_OFFSET - SERIAL_ECHOPAIR("Probe Offset X0 Y0 Z", probe.offset.z, " ("); + SERIAL_ECHOPGM("Probe Offset X0 Y0 Z", probe.offset.z, " ("); #else - SERIAL_ECHOPAIR_P(PSTR("Probe Offset X"), probe.offset_xy.x, SP_Y_STR, probe.offset_xy.y, SP_Z_STR, probe.offset.z); + SERIAL_ECHOPGM_P(PSTR("Probe Offset X"), probe.offset_xy.x, SP_Y_STR, probe.offset_xy.y, SP_Z_STR, probe.offset.z); if (probe.offset_xy.x > 0) SERIAL_ECHOPGM(" (Right"); else if (probe.offset_xy.x < 0) @@ -119,7 +119,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOLNPGM(" (enabled)"); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) - SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height); + SERIAL_ECHOLNPGM("Z Fade: ", planner.z_fade_height); #endif #if ABL_PLANAR SERIAL_ECHOPGM("ABL Adjustment"); @@ -140,7 +140,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHO(ftostr43sign(rz, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { - SERIAL_ECHOPAIR(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+')); + SERIAL_ECHOPGM(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+')); SERIAL_CHAR(')'); } #endif @@ -156,10 +156,10 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("Mesh Bed Leveling"); if (planner.leveling_active) { SERIAL_ECHOLNPGM(" (enabled)"); - SERIAL_ECHOPAIR("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+')); + SERIAL_ECHOPGM("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { - SERIAL_ECHOPAIR(" (", ftostr43sign( + SERIAL_ECHOPGM(" (", ftostr43sign( mbl.get_z(current_position, planner.fade_scaling_factor_for_z(current_position.z)), '+' )); SERIAL_CHAR(')'); diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 5ab95d1577..23dc973049 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -134,12 +134,12 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const switch (axis) { case CORE_AXIS_1: //block->steps[CORE_AXIS_2] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_2]; - //SERIAL_ECHOLNPAIR("CORE_AXIS_1 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], + //SERIAL_ECHOLNPGM("CORE_AXIS_1 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], // " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction); break; case CORE_AXIS_2: //block->steps[CORE_AXIS_1] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_1];; - //SERIAL_ECHOLNPAIR("CORE_AXIS_2 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], + //SERIAL_ECHOLNPGM("CORE_AXIS_2 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis], // " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction); break; case NORMAL_AXIS: break; diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index 7390656563..ece7481981 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -336,11 +336,11 @@ float bilinear_z_offset(const xy_pos_t &raw) { /* static float last_offset = 0; if (ABS(last_offset - offset) > 0.2) { - SERIAL_ECHOLNPAIR("Sudden Shift at x=", rel.x, " / ", bilinear_grid_spacing.x, " -> thisg.x=", thisg.x); - SERIAL_ECHOLNPAIR(" y=", rel.y, " / ", bilinear_grid_spacing.y, " -> thisg.y=", thisg.y); - SERIAL_ECHOLNPAIR(" ratio.x=", ratio.x, " ratio.y=", ratio.y); - SERIAL_ECHOLNPAIR(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4); - SERIAL_ECHOLNPAIR(" L=", L, " R=", R, " offset=", offset); + SERIAL_ECHOLNPGM("Sudden Shift at x=", rel.x, " / ", bilinear_grid_spacing.x, " -> thisg.x=", thisg.x); + SERIAL_ECHOLNPGM(" y=", rel.y, " / ", bilinear_grid_spacing.y, " -> thisg.y=", thisg.y); + SERIAL_ECHOLNPGM(" ratio.x=", ratio.x, " ratio.y=", ratio.y); + SERIAL_ECHOLNPGM(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4); + SERIAL_ECHOLNPGM(" L=", L, " R=", R, " offset=", offset); } last_offset = offset; //*/ diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 37c8be5bd8..00cb5ed738 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -51,7 +51,7 @@ void unified_bed_leveling::report_current_mesh() { GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M421 I", x, " J", y); + SERIAL_ECHOPGM(" M421 I", x, " J", y); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); serial_delay(75); // Prevent Printrun from exploding } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index cf00a282cf..ffabadd990 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -208,7 +208,7 @@ public: if (DEBUGGING(LEVELING)) { if (WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("yi"); else DEBUG_ECHOPGM("x1_i"); - DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")"); + DEBUG_ECHOLNPGM(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")"); } // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. @@ -231,7 +231,7 @@ public: if (DEBUGGING(LEVELING)) { if (WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("y1_i"); else DEBUG_ECHOPGM("xi"); - DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")"); + DEBUG_ECHOLNPGM(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")"); } // The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN. @@ -275,11 +275,11 @@ public: // because part of the Mesh is undefined and we don't have the // information we need to complete the height correction. - if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPAIR("??? Yikes! NAN in "); + if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPGM("??? Yikes! NAN in "); } if (DEBUGGING(MESH_ADJUST)) { - DEBUG_ECHOPAIR("get_z_correction(", rx0, ", ", ry0); + DEBUG_ECHOPGM("get_z_correction(", rx0, ", ", ry0); DEBUG_ECHOLNPAIR_F(") => ", z0, 6); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index ceedd316e3..747c61a8b9 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -428,7 +428,7 @@ void unified_bed_leveling::G29() { SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); } if (param.V_verbosity > 1) { - SERIAL_ECHOPAIR("Probing around (", param.XY_pos.x); + SERIAL_ECHOPGM("Probing around (", param.XY_pos.x); SERIAL_CHAR(','); SERIAL_DECIMAL(param.XY_pos.y); SERIAL_ECHOLNPGM(").\n"); @@ -602,7 +602,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); return; } @@ -630,7 +630,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); goto LEAVE; } @@ -653,7 +653,7 @@ void unified_bed_leveling::G29() { #endif #ifdef Z_PROBE_END_SCRIPT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); if (probe_deployed) { planner.synchronize(); gcode.process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); @@ -690,7 +690,7 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t o if (!isnan(z_values[x][y])) sum_of_diff_squared += sq(z_values[x][y] - mean); - SERIAL_ECHOLNPAIR("# of samples: ", n); + SERIAL_ECHOLNPGM("# of samples: ", n); SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6); const float sigma = SQRT(sum_of_diff_squared / (n + 1)); @@ -735,7 +735,7 @@ void unified_bed_leveling::shift_mesh_height() { if (do_ubl_mesh_map) display_map(param.T_map_type); const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; - SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); + SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); #if HAS_LCD_MENU @@ -1450,7 +1450,7 @@ void unified_bed_leveling::smart_fill_mesh() { #endif if (param.V_verbosity > 3) { serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); + SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } incremental_LSF(&lsf_results, points[0], measured_z); } @@ -1469,7 +1469,7 @@ void unified_bed_leveling::smart_fill_mesh() { measured_z -= get_z_correction(points[1]); if (param.V_verbosity > 3) { serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); + SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } incremental_LSF(&lsf_results, points[1], measured_z); } @@ -1489,7 +1489,7 @@ void unified_bed_leveling::smart_fill_mesh() { measured_z -= get_z_correction(points[2]); if (param.V_verbosity > 3) { serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); + SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } incremental_LSF(&lsf_results, points[2], measured_z); } @@ -1517,7 +1517,7 @@ void unified_bed_leveling::smart_fill_mesh() { rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy); if (!abort_flag) { - SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); + SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n"); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling @@ -1545,7 +1545,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (param.V_verbosity > 3) { serial_spaces(16); - SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); + SERIAL_ECHOLNPGM("Corrected_Z=", measured_z); } incremental_LSF(&lsf_results, rpos, measured_z); } @@ -1648,7 +1648,7 @@ void unified_bed_leveling::smart_fill_mesh() { DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); d_from(); DEBUG_ECHOPGM("safe home with Z="); DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6); - DEBUG_ECHOPAIR(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); + DEBUG_ECHOPGM(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6); #endif } // DEBUGGING(LEVELING) @@ -1722,7 +1722,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (storage_slot == -1) SERIAL_ECHOPGM("No Mesh Loaded."); else - SERIAL_ECHOPAIR("Mesh ", storage_slot, " Loaded."); + SERIAL_ECHOPGM("Mesh ", storage_slot, " Loaded."); SERIAL_EOL(); serial_delay(50); @@ -1736,14 +1736,14 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe.offset.z, 7); #endif - SERIAL_ECHOLNPAIR("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50); - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50); - SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); - SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); + SERIAL_ECHOLNPGM("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); + SERIAL_ECHOLNPGM("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50); + SERIAL_ECHOLNPGM("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50); + SERIAL_ECHOLNPGM("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50); + SERIAL_ECHOLNPGM("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50); + SERIAL_ECHOLNPGM("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50); + SERIAL_ECHOLNPGM("MESH_X_DIST ", MESH_X_DIST); + SERIAL_ECHOLNPGM("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); SERIAL_ECHOPGM("X-Axis Mesh Points at: "); LOOP_L_N(i, GRID_MAX_POINTS_X) { @@ -1762,27 +1762,27 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_EOL(); #if HAS_KILL - SERIAL_ECHOLNPAIR("Kill pin on :", KILL_PIN, " state:", kill_state()); + SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", kill_state()); #endif SERIAL_EOL(); serial_delay(50); #if ENABLED(UBL_DEVEL_DEBUGGING) - SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); + SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); serial_delay(50); - SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); + SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); serial_delay(50); - SERIAL_ECHOLNPAIR("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); - SERIAL_ECHOLNPAIR("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); + SERIAL_ECHOLNPGM("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); + SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); serial_delay(25); - SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); + SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); serial_delay(50); - SERIAL_ECHOLNPAIR("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); + SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); serial_delay(25); #endif // UBL_DEVEL_DEBUGGING @@ -1829,7 +1829,7 @@ void unified_bed_leveling::smart_fill_mesh() { } if (!parser.has_value() || !WITHIN(parser.value_int(), 0, a - 1)) { - SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); return; } @@ -1838,7 +1838,7 @@ void unified_bed_leveling::smart_fill_mesh() { float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; settings.load_mesh(param.KLS_storage_slot, &tmp_z_values); - SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", param.KLS_storage_slot, " from current mesh."); + SERIAL_ECHOLNPGM("Subtracting mesh in slot ", param.KLS_storage_slot, " from current mesh."); GRID_LOOP(x, y) { z_values[x][y] -= tmp_z_values[x][y]; diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index cef8a3c902..417e39c745 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -146,9 +146,9 @@ public: transfer_timeout = millis() + TIMEOUT; switch (static_cast(packet_type)) { case FileTransfer::QUERY: - SERIAL_ECHOPAIR("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); + SERIAL_ECHOPGM("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); #if ENABLED(BINARY_STREAM_COMPRESSION) - SERIAL_ECHOLNPAIR(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); + SERIAL_ECHOLNPGM(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS); #else SERIAL_ECHOLNPGM(":compression:none"); #endif @@ -322,7 +322,7 @@ public: if (packet.header.checksum == packet.header_checksum) { // The SYNC control packet is a special case in that it doesn't require the stream sync to be correct if (static_cast(packet.header.protocol()) == Protocol::CONTROL && static_cast(packet.header.type()) == ProtocolControl::SYNC) { - SERIAL_ECHOLNPAIR("ss", sync, ",", buffer_size, ",", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); + SERIAL_ECHOLNPGM("ss", sync, ",", buffer_size, ",", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH); stream_state = StreamState::PACKET_RESET; break; } @@ -337,7 +337,7 @@ public: stream_state = StreamState::PACKET_PROCESS; } else if (packet.header.sync == sync - 1) { // ok response must have been lost - SERIAL_ECHOLNPAIR("ok", packet.header.sync); // transmit valid packet received and drop the payload + SERIAL_ECHOLNPGM("ok", packet.header.sync); // transmit valid packet received and drop the payload stream_state = StreamState::PACKET_RESET; } else if (packet_retries) { @@ -393,7 +393,7 @@ public: packet_retries = 0; bytes_received += packet.header.size; - SERIAL_ECHOLNPAIR("ok", packet.header.sync); // transmit valid packet received + SERIAL_ECHOLNPGM("ok", packet.header.sync); // transmit valid packet received dispatch(); stream_state = StreamState::PACKET_RESET; break; @@ -402,7 +402,7 @@ public: packet_retries++; stream_state = StreamState::PACKET_RESET; SERIAL_ECHO_MSG("Resend request ", packet_retries); - SERIAL_ECHOLNPAIR("rs", sync); + SERIAL_ECHOLNPGM("rs", sync); } else stream_state = StreamState::PACKET_ERROR; @@ -412,7 +412,7 @@ public: stream_state = StreamState::PACKET_RESEND; break; case StreamState::PACKET_ERROR: - SERIAL_ECHOLNPAIR("fe", packet.header.sync); + SERIAL_ECHOLNPGM("fe", packet.header.sync); reset(); // reset everything, resync required stream_state = StreamState::PACKET_RESET; break; diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 7fccc52d05..49a10f62b1 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -39,7 +39,7 @@ void stop(); #include "../core/debug_out.h" bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) { - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("BLTouch Command :", cmd); + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch Command :", cmd); MOVE_SERVO(Z_PROBE_SERVO_NR, cmd); safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay return triggered(); @@ -64,7 +64,7 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR("last_written_mode - ", last_written_mode); + DEBUG_ECHOLNPGM("last_written_mode - ", last_written_mode); DEBUG_ECHOLNPGM("config mode - " #if ENABLED(BLTOUCH_SET_5V_MODE) "BLTOUCH_SET_5V_MODE" @@ -175,7 +175,7 @@ bool BLTouch::status_proc() { _set_SW_mode(); // Incidentally, _set_SW_mode() will also RESET any active alarm const bool tr = triggered(); // If triggered in SW mode, the pin is up, it is STOWED - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", tr); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("BLTouch is ", tr); if (tr) _stow(); else _deploy(); // Turn off SW mode, reset any trigger, honor pin state return !tr; @@ -187,7 +187,7 @@ void BLTouch::mode_conv_proc(const bool M5V) { * BLTOUCH V3.0: This will set the mode (twice) and sadly, a STOW is needed at the end, because of the deploy * BLTOUCH V3.1: This will set the mode and store it in the eeprom. The STOW is not needed but does not hurt */ - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", M5V); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("BLTouch Set Mode - ", M5V); _deploy(); if (M5V) _set_5V_mode(); else _set_OD_mode(); _mode_store(); diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 6d03808b82..ff730e93c6 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -85,15 +85,15 @@ void StepperDAC::print_values() { if (!dac_present) return; SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR_P(SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); + SERIAL_ECHOPGM_P(SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); #if HAS_Y_AXIS - SERIAL_ECHOPAIR_P(SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); + SERIAL_ECHOPGM_P(SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); #endif #if HAS_Z_AXIS - SERIAL_ECHOPAIR_P(SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); + SERIAL_ECHOPGM_P(SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); #endif #if HAS_EXTRUDERS - SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + SERIAL_ECHOLNPGM_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); #endif } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 283092e344..e6b127e03c 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -49,7 +49,7 @@ void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { initialized = true; - SERIAL_ECHOLNPAIR("Setting up encoder on ", AS_CHAR(axis_codes[encoderAxis]), " axis, addr = ", address); + SERIAL_ECHOLNPGM("Setting up encoder on ", AS_CHAR(axis_codes[encoderAxis]), " axis, addr = ", address); position = get_position(); } @@ -67,7 +67,7 @@ void I2CPositionEncoder::update() { /* if (trusted) { //commented out as part of the note below trusted = false; - SERIAL_ECHOLNPAIR("Fault detected on ", AS_CHAR(axis_codes[encoderAxis]), " axis encoder. Disengaging error correction until module is trusted again."); + SERIAL_ECHOLNPGM("Fault detected on ", AS_CHAR(axis_codes[encoderAxis]), " axis encoder. Disengaging error correction until module is trusted again."); } */ return; @@ -92,7 +92,7 @@ void I2CPositionEncoder::update() { if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { trusted = true; - SERIAL_ECHOLNPAIR("Untrusted encoder module on ", AS_CHAR(axis_codes[encoderAxis]), " axis has been fault-free for set duration, reinstating error correction."); + SERIAL_ECHOLNPGM("Untrusted encoder module on ", AS_CHAR(axis_codes[encoderAxis]), " axis has been fault-free for set duration, reinstating error correction."); //the encoder likely lost its place when the error occurred, so we'll reset and use the printer's //idea of where it the axis is to re-initialize @@ -103,10 +103,10 @@ void I2CPositionEncoder::update() { zeroOffset -= (positionInTicks - get_position()); #ifdef I2CPE_DEBUG - SERIAL_ECHOLNPAIR("Current position is ", pos); - SERIAL_ECHOLNPAIR("Position in encoder ticks is ", positionInTicks); - SERIAL_ECHOLNPAIR("New zero-offset of ", zeroOffset); - SERIAL_ECHOPAIR("New position reads as ", get_position()); + SERIAL_ECHOLNPGM("Current position is ", pos); + SERIAL_ECHOLNPGM("Position in encoder ticks is ", positionInTicks); + SERIAL_ECHOLNPGM("New zero-offset of ", zeroOffset); + SERIAL_ECHOPGM("New position reads as ", get_position()); SERIAL_CHAR('('); SERIAL_DECIMAL(mm_from_count(get_position())); SERIAL_ECHOLNPGM(")"); @@ -149,12 +149,12 @@ void I2CPositionEncoder::update() { const int32_t error = get_axis_error_steps(false); #endif - //SERIAL_ECHOLNPAIR("Axis error steps: ", error); + //SERIAL_ECHOLNPGM("Axis error steps: ", error); #ifdef I2CPE_ERR_THRESH_ABORT if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.settings.axis_steps_per_mm[encoderAxis]) { //kill(PSTR("Significant Error")); - SERIAL_ECHOLNPAIR("Axis error over threshold, aborting!", error); + SERIAL_ECHOLNPGM("Axis error over threshold, aborting!", error); safe_delay(5000); } #endif @@ -173,7 +173,7 @@ void I2CPositionEncoder::update() { LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm"); + SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm"); babystep.add_steps(encoderAxis, -LROUND(errorP)); errPrstIdx = 0; } @@ -193,7 +193,7 @@ void I2CPositionEncoder::update() { const millis_t ms = millis(); if (ELAPSED(ms, nextErrorCountTime)) { SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" : LARGE ERR ", error, "; diffSum=", diffSum); + SERIAL_ECHOLNPGM(" : LARGE ERR ", error, "; diffSum=", diffSum); errorCount++; nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS; } @@ -213,7 +213,7 @@ void I2CPositionEncoder::set_homed() { #ifdef I2CPE_DEBUG SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" axis encoder homed, offset of ", zeroOffset, " ticks."); + SERIAL_ECHOLNPGM(" axis encoder homed, offset of ", zeroOffset, " ticks."); #endif } } @@ -253,7 +253,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) { if (report) { SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm"); + SERIAL_ECHOLNPGM(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm"); } return error; @@ -288,7 +288,7 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) { if (report) { SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPAIR(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error); + SERIAL_ECHOLNPGM(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error); } if (suppressOutput) { @@ -424,15 +424,15 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelledDistance = mm_from_count(ABS(stopCount - startCount)); - SERIAL_ECHOLNPAIR("Attempted travel: ", travelDistance, "mm"); - SERIAL_ECHOLNPAIR(" Actual travel: ", travelledDistance, "mm"); + SERIAL_ECHOLNPGM("Attempted travel: ", travelDistance, "mm"); + SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); //Calculate new axis steps per unit old_steps_mm = planner.settings.axis_steps_per_mm[encoderAxis]; new_steps_mm = (old_steps_mm * travelDistance) / travelledDistance; - SERIAL_ECHOLNPAIR("Old steps/mm: ", old_steps_mm); - SERIAL_ECHOLNPAIR("New steps/mm: ", new_steps_mm); + SERIAL_ECHOLNPGM("Old steps/mm: ", old_steps_mm); + SERIAL_ECHOLNPGM("New steps/mm: ", new_steps_mm); //Save new value planner.settings.axis_steps_per_mm[encoderAxis] = new_steps_mm; @@ -449,7 +449,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { if (iter > 1) { total /= (float)iter; - SERIAL_ECHOLNPAIR("Average steps/mm: ", total); + SERIAL_ECHOLNPGM("Average steps/mm: ", total); } ec = oldec; @@ -675,18 +675,18 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const // First check 'new' address is not in use Wire.beginTransmission(I2C_ADDRESS(newaddr)); if (!Wire.endTransmission()) { - SERIAL_ECHOLNPAIR("?There is already a device with that address on the I2C bus! (", newaddr, ")"); + SERIAL_ECHOLNPGM("?There is already a device with that address on the I2C bus! (", newaddr, ")"); return; } // Now check that we can find the module on the oldaddr address Wire.beginTransmission(I2C_ADDRESS(oldaddr)); if (Wire.endTransmission()) { - SERIAL_ECHOLNPAIR("?No module detected at this address! (", oldaddr, ")"); + SERIAL_ECHOLNPGM("?No module detected at this address! (", oldaddr, ")"); return; } - SERIAL_ECHOLNPAIR("Module found at ", oldaddr, ", changing address to ", newaddr); + SERIAL_ECHOLNPGM("Module found at ", oldaddr, ", changing address to ", newaddr); // Change the modules address Wire.beginTransmission(I2C_ADDRESS(oldaddr)); @@ -722,11 +722,11 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) { // First check there is a module Wire.beginTransmission(I2C_ADDRESS(address)); if (Wire.endTransmission()) { - SERIAL_ECHOLNPAIR("?No module detected at this address! (", address, ")"); + SERIAL_ECHOLNPGM("?No module detected at this address! (", address, ")"); return; } - SERIAL_ECHOLNPAIR("Requesting version info from module at address ", address, ":"); + SERIAL_ECHOLNPGM("Requesting version info from module at address ", address, ":"); Wire.beginTransmission(I2C_ADDRESS(address)); Wire.write(I2CPE_SET_REPORT_MODE); @@ -773,13 +773,13 @@ int8_t I2CPositionEncodersMgr::parse() { else if (parser.seenval('I')) { if (!parser.has_value()) { - SERIAL_ECHOLNPAIR("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1, "]"); + SERIAL_ECHOLNPGM("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1, "]"); return I2CPE_PARSE_ERR; }; I2CPE_idx = parser.value_byte(); if (I2CPE_idx >= I2CPE_ENCODER_CNT) { - SERIAL_ECHOLNPAIR("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1, "]"); + SERIAL_ECHOLNPGM("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1, "]"); return I2CPE_PARSE_ERR; } @@ -954,7 +954,7 @@ void I2CPositionEncodersMgr::M864() { else return; } - SERIAL_ECHOLNPAIR("Changing module at address ", I2CPE_addr, " to address ", newAddress); + SERIAL_ECHOLNPGM("Changing module at address ", I2CPE_addr, " to address ", newAddress); change_module_address(I2CPE_addr, newAddress); } diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h index 20871af98c..50fb27a135 100644 --- a/Marlin/src/feature/encoder_i2c.h +++ b/Marlin/src/feature/encoder_i2c.h @@ -236,7 +236,7 @@ class I2CPositionEncodersMgr { static void report_status(const int8_t idx) { CHECK_IDX(); - SERIAL_ECHOLNPAIR("Encoder ", idx, ": "); + SERIAL_ECHOLNPGM("Encoder ", idx, ": "); encoders[idx].get_raw_count(); encoders[idx].passes_test(true); } @@ -261,32 +261,32 @@ class I2CPositionEncodersMgr { static void report_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); - SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[axis]), " axis is ", encoders[idx].get_error_count()); + SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(axis_codes[axis]), " axis is ", encoders[idx].get_error_count()); } static void reset_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_error_count(0); - SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[axis]), " axis has been reset."); + SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(axis_codes[axis]), " axis has been reset."); } static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_enabled(enabled); - SERIAL_ECHOPAIR("Error correction on ", AS_CHAR(axis_codes[axis])); + SERIAL_ECHOPGM("Error correction on ", AS_CHAR(axis_codes[axis])); SERIAL_ECHO_TERNARY(encoders[idx].get_ec_enabled(), " axis is ", "en", "dis", "abled.\n"); } static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_threshold(newThreshold); - SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis set to ", newThreshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis set to ", newThreshold, "mm."); } static void get_ec_threshold(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); const float threshold = encoders[idx].get_ec_threshold(); - SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis is ", threshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis is ", threshold, "mm."); } static int8_t idx_from_axis(const AxisEnum axis) { diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 71630d30ac..26817b9ed2 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -106,20 +106,20 @@ void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool sw #endif /* // debugging - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "retracting ", AS_DIGIT(retracting), " swapping ", swapping, " active extruder ", active_extruder ); LOOP_L_N(i, EXTRUDERS) { - SERIAL_ECHOLNPAIR("retracted[", i, "] ", AS_DIGIT(retracted[i])); + SERIAL_ECHOLNPGM("retracted[", i, "] ", AS_DIGIT(retracted[i])); #if HAS_MULTI_EXTRUDER - SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); + SERIAL_ECHOLNPGM("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); #endif } - SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); - SERIAL_ECHOLNPAIR("current_position.e ", current_position.e); - SERIAL_ECHOLNPAIR("current_hop ", current_hop); + SERIAL_ECHOLNPGM("current_position.z ", current_position.z); + SERIAL_ECHOLNPGM("current_position.e ", current_position.e); + SERIAL_ECHOLNPGM("current_hop ", current_hop); //*/ const float base_retract = TERN1(RETRACT_SYNC_MIXING, (MIXING_STEPPERS)) @@ -181,18 +181,18 @@ void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool sw #endif /* // debugging - SERIAL_ECHOLNPAIR("retracting ", AS_DIGIT(retracting)); - SERIAL_ECHOLNPAIR("swapping ", AS_DIGIT(swapping)); - SERIAL_ECHOLNPAIR("active_extruder ", active_extruder); + SERIAL_ECHOLNPGM("retracting ", AS_DIGIT(retracting)); + SERIAL_ECHOLNPGM("swapping ", AS_DIGIT(swapping)); + SERIAL_ECHOLNPGM("active_extruder ", active_extruder); LOOP_L_N(i, EXTRUDERS) { - SERIAL_ECHOLNPAIR("retracted[", i, "] ", AS_DIGIT(retracted[i])); + SERIAL_ECHOLNPGM("retracted[", i, "] ", AS_DIGIT(retracted[i])); #if HAS_MULTI_EXTRUDER - SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); + SERIAL_ECHOLNPGM("retracted_swap[", i, "] ", AS_DIGIT(retracted_swap[i])); #endif } - SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); - SERIAL_ECHOLNPAIR("current_position.e ", current_position.e); - SERIAL_ECHOLNPAIR("current_hop ", current_hop); + SERIAL_ECHOLNPGM("current_position.z ", current_position.z); + SERIAL_ECHOLNPGM("current_position.e ", current_position.e); + SERIAL_ECHOLNPGM("current_hop ", current_hop); //*/ } @@ -215,7 +215,7 @@ void FWRetract::M207() { } void FWRetract::M207_report() { - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M207 S"), LINEAR_UNIT(settings.retract_length) , PSTR(" W"), LINEAR_UNIT(settings.swap_retract_length) , PSTR(" F"), LINEAR_UNIT(MMS_TO_MMM(settings.retract_feedrate_mm_s)) @@ -240,7 +240,7 @@ void FWRetract::M208() { } void FWRetract::M208_report() { - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " M208 S", LINEAR_UNIT(settings.retract_recover_extra) , " W", LINEAR_UNIT(settings.swap_retract_recover_extra) , " F", LINEAR_UNIT(MMS_TO_MMM(settings.retract_recover_feedrate_mm_s)) @@ -261,7 +261,7 @@ void FWRetract::M208_report() { } void FWRetract::M209_report() { - SERIAL_ECHOLNPAIR(" M209 S", AS_DIGIT(autoretract_enabled)); + SERIAL_ECHOLNPGM(" M209 S", AS_DIGIT(autoretract_enabled)); } #endif // FWRETRACT_AUTORETRACT diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index d8e6cef3b6..7f91c1549b 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -68,13 +68,13 @@ Joystick joystick; void Joystick::report() { SERIAL_ECHOPGM("Joystick"); #if HAS_JOY_ADC_X - SERIAL_ECHOPAIR_P(SP_X_STR, JOY_X(x.raw)); + SERIAL_ECHOPGM_P(SP_X_STR, JOY_X(x.raw)); #endif #if HAS_JOY_ADC_Y - SERIAL_ECHOPAIR_P(SP_Y_STR, JOY_Y(y.raw)); + SERIAL_ECHOPGM_P(SP_Y_STR, JOY_Y(y.raw)); #endif #if HAS_JOY_ADC_Z - SERIAL_ECHOPAIR_P(SP_Z_STR, JOY_Z(z.raw)); + SERIAL_ECHOPGM_P(SP_Z_STR, JOY_Z(z.raw)); #endif #if HAS_JOY_ADC_EN SERIAL_ECHO_TERNARY(READ(JOY_EN_PIN), " EN=", "HIGH (dis", "LOW (en", "abled)"); diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 200e6b580d..e13c6f5b97 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -130,7 +130,7 @@ void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/ SERIAL_ECHOPGM_P(func); SERIAL_CHAR('('); SERIAL_ECHO(v1); - if (v2 > 0) SERIAL_ECHOPAIR(", ", v2); + if (v2 > 0) SERIAL_ECHOPGM(", ", v2); SERIAL_CHAR(')'); SERIAL_EOL(); #else diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index 6803a0de7d..2edcd7478a 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -140,7 +140,7 @@ void MeatPack::handle_output_char(const uint8_t c) { #if ENABLED(MP_DEBUG) if (chars_decoded < 1024) { ++chars_decoded; - DEBUG_ECHOLNPAIR("RB: ", AS_CHAR(c)); + DEBUG_ECHOLNPGM("RB: ", AS_CHAR(c)); } #endif } diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 0013797ad5..9ebc90127f 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -154,11 +154,11 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= cmax = _MAX(cmax, v); csum += v; } - //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", t, ") cmax=", cmax, " csum=", csum, " color"); + //SERIAL_ECHOPGM("Mixer::refresh_collector(", proportion, ", ", t, ") cmax=", cmax, " csum=", csum, " color"); const float inv_prop = proportion / csum; MIXER_STEPPER_LOOP(i) { c[i] = color[t][i] * inv_prop; - //SERIAL_ECHOPAIR(" [", t, "][", i, "] = ", color[t][i], " (", c[i], ") "); + //SERIAL_ECHOPGM(" [", t, "][", i, "] = ", color[t][i], " (", c[i], ") "); } //SERIAL_EOL(); } diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 573b61cb68..f700c7b65b 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -152,7 +152,7 @@ class Mixer { MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot); #ifdef MIXER_NORMALIZER_DEBUG - SERIAL_ECHOPAIR("V-tool ", j, " [ "); + SERIAL_ECHOPGM("V-tool ", j, " [ "); SERIAL_ECHOLIST_N(MIXING_STEPPERS, color[j][0], color[j][1], color[j][2], color[j][3], color[j][4], color[j][5]); SERIAL_ECHOPGM(" ] to Mix [ "); SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]); diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 1acd26f331..31e64f4953 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -169,7 +169,7 @@ void MMU2::mmu_loop() { if (rx_ok()) { sscanf(rx_buffer, "%huok\n", &version); - DEBUG_ECHOLNPAIR("MMU => ", version, "\nMMU <= 'S2'"); + DEBUG_ECHOLNPGM("MMU => ", version, "\nMMU <= 'S2'"); MMU2_COMMAND("S2"); // Read Build Number state = -3; @@ -180,7 +180,7 @@ void MMU2::mmu_loop() { if (rx_ok()) { sscanf(rx_buffer, "%huok\n", &buildnr); - DEBUG_ECHOLNPAIR("MMU => ", buildnr); + DEBUG_ECHOLNPGM("MMU => ", buildnr); check_version(); @@ -217,7 +217,7 @@ void MMU2::mmu_loop() { if (rx_ok()) { sscanf(rx_buffer, "%hhuok\n", &finda); - DEBUG_ECHOLNPAIR("MMU => ", finda, "\nMMU - ENABLED"); + DEBUG_ECHOLNPGM("MMU => ", finda, "\nMMU - ENABLED"); _enabled = true; state = 1; @@ -230,7 +230,7 @@ void MMU2::mmu_loop() { if (WITHIN(cmd, MMU_CMD_T0, MMU_CMD_T0 + EXTRUDERS - 1)) { // tool change int filament = cmd - MMU_CMD_T0; - DEBUG_ECHOLNPAIR("MMU <= T", filament); + DEBUG_ECHOLNPGM("MMU <= T", filament); tx_printf_P(PSTR("T%d\n"), filament); TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any state = 3; // wait for response @@ -238,7 +238,7 @@ void MMU2::mmu_loop() { else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L0 + EXTRUDERS - 1)) { // load int filament = cmd - MMU_CMD_L0; - DEBUG_ECHOLNPAIR("MMU <= L", filament); + DEBUG_ECHOLNPGM("MMU <= L", filament); tx_printf_P(PSTR("L%d\n"), filament); state = 3; // wait for response } @@ -258,7 +258,7 @@ void MMU2::mmu_loop() { else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E0 + EXTRUDERS - 1)) { // eject filament int filament = cmd - MMU_CMD_E0; - DEBUG_ECHOLNPAIR("MMU <= E", filament); + DEBUG_ECHOLNPGM("MMU <= E", filament); tx_printf_P(PSTR("E%d\n"), filament); state = 3; // wait for response } @@ -271,7 +271,7 @@ void MMU2::mmu_loop() { else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F0 + EXTRUDERS - 1)) { // filament type int filament = cmd - MMU_CMD_F0; - DEBUG_ECHOLNPAIR("MMU <= F", filament, " ", cmd_arg); + DEBUG_ECHOLNPGM("MMU <= F", filament, " ", cmd_arg); tx_printf_P(PSTR("F%d %d\n"), filament, cmd_arg); state = 3; // wait for response } @@ -647,7 +647,7 @@ static void mmu2_not_responding() { void MMU2::mmu_continue_loading() { for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) { - DEBUG_ECHOLNPAIR("Additional load attempt #", i); + DEBUG_ECHOLNPGM("Additional load attempt #", i); if (FILAMENT_PRESENT()) break; command(MMU_CMD_C0); manage_response(true, true); @@ -1025,7 +1025,7 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("E step ", es, "/", fr_mm_m); + DEBUG_ECHOLNPGM("E step ", es, "/", fr_mm_m); current_position.e += es; line_to_current_position(MMM_TO_MMS(fr_mm_m)); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index f1d6dbb985..d9b2521403 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -132,7 +132,7 @@ fil_change_settings_t fc_settings[EXTRUDERS]; */ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) { DEBUG_SECTION(est, "ensure_safe_temperature", true); - DEBUG_ECHOLNPAIR("... wait:", wait, " mode:", mode); + DEBUG_ECHOLNPGM("... wait:", wait, " mode:", mode); #if ENABLED(PREVENT_COLD_EXTRUSION) if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) @@ -178,7 +178,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load DXC_ARGS ) { DEBUG_SECTION(lf, "load_filament", true); - DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY); + DEBUG_ECHOLNPGM("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY); if (!ensure_safe_temperature(false, mode)) { if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS, mode); @@ -315,7 +315,7 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, #endif ) { DEBUG_SECTION(uf, "unload_filament", true); - DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode + DEBUG_ECHOLNPGM("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , " mixmult:", mix_multiplier #endif @@ -379,7 +379,7 @@ uint8_t did_pause_print = 0; bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const_float_t unload_length/*=0*/ DXC_ARGS) { DEBUG_SECTION(pp, "pause_print", true); - DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); + DEBUG_ECHOLNPGM("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); UNUSED(show_lcd); @@ -430,7 +430,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Initial retract before move to filament change position if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) { - DEBUG_ECHOLNPAIR("... retract:", retract); + DEBUG_ECHOLNPGM("... retract:", retract); unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); } @@ -472,7 +472,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool void show_continue_prompt(const bool is_reload) { DEBUG_SECTION(scp, "pause_print", true); - DEBUG_ECHOLNPAIR("... is_reload:", is_reload); + DEBUG_ECHOLNPGM("... is_reload:", is_reload); ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); SERIAL_ECHO_START(); @@ -481,7 +481,7 @@ void show_continue_prompt(const bool is_reload) { void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { DEBUG_SECTION(wfc, "wait_for_confirmation", true); - DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", max_beep_count DXC_SAY); + DEBUG_ECHOLNPGM("... is_reload:", is_reload, " maxbeep:", max_beep_count DXC_SAY); bool nozzle_timed_out = false; @@ -584,10 +584,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep */ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, const celsius_t targetTemp/*=0*/ DXC_ARGS) { DEBUG_SECTION(rp, "resume_print", true); - DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " targetTemp:", targetTemp DXC_SAY); + DEBUG_ECHOLNPGM("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " targetTemp:", targetTemp DXC_SAY); /* - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "start of resume_print()\ndual_x_carriage_mode:", dual_x_carriage_mode, "\nextruder_duplication_enabled:", extruder_duplication_enabled, "\nactive_extruder:", active_extruder, diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index c86cb4f0d6..159121ba45 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -577,7 +577,7 @@ void PrintJobRecovery::resume() { void PrintJobRecovery::debug(PGM_P const prefix) { DEBUG_ECHOPGM_P(prefix); - DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot); + DEBUG_ECHOLNPGM(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot); if (info.valid_head) { if (info.valid_head == info.valid_foot) { DEBUG_ECHOPGM("current_position: "); @@ -587,14 +587,14 @@ void PrintJobRecovery::resume() { } DEBUG_EOL(); - DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); + DEBUG_ECHOLNPGM("feedrate: ", info.feedrate); - DEBUG_ECHOLNPAIR("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : ""); + DEBUG_ECHOLNPGM("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : ""); #if ENABLED(GCODE_REPEAT_MARKERS) - DEBUG_ECHOLNPAIR("repeat index: ", info.stored_repeat.index); + DEBUG_ECHOLNPGM("repeat index: ", info.stored_repeat.index); LOOP_L_N(i, info.stored_repeat.index) - DEBUG_ECHOLNPAIR("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); + DEBUG_ECHOLNPGM("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); #endif #if HAS_HOME_OFFSET @@ -616,12 +616,12 @@ void PrintJobRecovery::resume() { #endif #if HAS_MULTI_EXTRUDER - DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder); + DEBUG_ECHOLNPGM("active_extruder: ", info.active_extruder); #endif #if DISABLED(NO_VOLUMETRICS) DEBUG_ECHOPGM("filament_size:"); - LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPAIR(" ", info.filament_size[i]); + LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPGM(" ", info.filament_size[i]); DEBUG_EOL(); #endif @@ -635,7 +635,7 @@ void PrintJobRecovery::resume() { #endif #if HAS_HEATED_BED - DEBUG_ECHOLNPAIR("target_temperature_bed: ", info.target_temperature_bed); + DEBUG_ECHOLNPGM("target_temperature_bed: ", info.target_temperature_bed); #endif #if HAS_FAN @@ -648,7 +648,7 @@ void PrintJobRecovery::resume() { #endif #if HAS_LEVELING - DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade); + DEBUG_ECHOLNPGM("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade); #endif #if ENABLED(FWRETRACT) @@ -658,17 +658,17 @@ void PrintJobRecovery::resume() { if (e < EXTRUDERS - 1) DEBUG_CHAR(','); } DEBUG_EOL(); - DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop); + DEBUG_ECHOLNPGM("retract_hop: ", info.retract_hop); #endif // Mixing extruder and gradient #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) - DEBUG_ECHOLNPAIR("gradient: ", info.gradient.enabled ? "ON" : "OFF"); + DEBUG_ECHOLNPGM("gradient: ", info.gradient.enabled ? "ON" : "OFF"); #endif - DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename); - DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos); - DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed); + DEBUG_ECHOLNPGM("sd_filename: ", info.sd_filename); + DEBUG_ECHOLNPGM("sdpos: ", info.sdpos); + DEBUG_ECHOLNPGM("print_job_elapsed: ", info.print_job_elapsed); DEBUG_ECHOPGM("axis_relative:"); if (TEST(info.axis_relative, REL_X)) DEBUG_ECHOPGM(" REL_X"); @@ -679,9 +679,9 @@ void PrintJobRecovery::resume() { if (TEST(info.axis_relative, E_MODE_REL)) DEBUG_ECHOPGM(" E_MODE_REL"); DEBUG_EOL(); - DEBUG_ECHOLNPAIR("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); - DEBUG_ECHOLNPAIR("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); - DEBUG_ECHOLNPAIR("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); + DEBUG_ECHOLNPGM("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); + DEBUG_ECHOLNPGM("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); + DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 6f2dad58b9..68984fe756 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -75,7 +75,7 @@ void ProbeTempComp::print_offsets() { #endif PSTR("Probe") ); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " temp: ", temp, "C; Offset: ", i < 0 ? 0.0f : sensor_z_offsets[s][i], " um" ); @@ -117,7 +117,7 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { // Extrapolate float k, d; if (calib_idx < measurements) { - SERIAL_ECHOLNPAIR("Got ", calib_idx, " measurements. "); + SERIAL_ECHOLNPGM("Got ", calib_idx, " measurements. "); if (linear_regression(tsi, k, d)) { SERIAL_ECHOPGM("Applying linear extrapolation"); calib_idx--; diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp index 11e4dd6a93..b52feb4a00 100644 --- a/Marlin/src/feature/repeat.cpp +++ b/Marlin/src/feature/repeat.cpp @@ -43,7 +43,7 @@ void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) { marker[index].sdpos = sdpos; marker[index].counter = count ?: -1; index++; - DEBUG_ECHOLNPAIR("Add Marker ", index, " at ", sdpos, " (", count, ")"); + DEBUG_ECHOLNPGM("Add Marker ", index, " at ", sdpos, " (", count, ")"); } } @@ -53,14 +53,14 @@ void Repeat::loop() { else { const uint8_t ind = index - 1; // Active marker's index if (!marker[ind].counter) { // Did its counter run out? - DEBUG_ECHOLNPAIR("Pass Marker ", index); + DEBUG_ECHOLNPGM("Pass Marker ", index); index--; // Carry on. Previous marker on the next 'M808'. } else { card.setIndex(marker[ind].sdpos); // Loop back to the marker. if (marker[ind].counter > 0) // Ignore a negative (or zero) counter. --marker[ind].counter; // Decrement the counter. If zero this 'M808' will be skipped next time. - DEBUG_ECHOLNPAIR("Goto Marker ", index, " at ", marker[ind].sdpos, " (", marker[ind].counter, ")"); + DEBUG_ECHOLNPGM("Goto Marker ", index, " at ", marker[ind].sdpos, " (", marker[ind].counter, ")"); } } } @@ -69,7 +69,7 @@ void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } void Repeat::early_parse_M808(char * const cmd) { if (is_command_M808(cmd)) { - DEBUG_ECHOLNPAIR("Parsing \"", cmd, "\""); + DEBUG_ECHOLNPGM("Parsing \"", cmd, "\""); parser.parse(cmd); if (parser.seen('L')) add_marker(card.getIndex(), parser.value_ushort()); diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index ef1f876bdf..1c56378359 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -132,7 +132,7 @@ void event_filament_runout(const uint8_t extruder) { char script[strlen(FILAMENT_RUNOUT_SCRIPT) + 1]; sprintf_P(script, PSTR(FILAMENT_RUNOUT_SCRIPT), tool); #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) - SERIAL_ECHOLNPAIR("Runout Command: ", script); + SERIAL_ECHOLNPGM("Runout Command: ", script); #endif queue.inject(script); #else diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 93eb59c2a5..d88e81d9d9 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -145,7 +145,7 @@ class TFilamentMonitor : public FilamentMonitorBase { if (runout_flags) { SERIAL_ECHOPGM("Runout Sensors: "); LOOP_L_N(i, 8) SERIAL_ECHO('0' + TEST(runout_flags, i)); - SERIAL_ECHOPAIR(" -> ", extruder); + SERIAL_ECHOPGM(" -> ", extruder); if (ran_out) SERIAL_ECHOPGM(" RUN OUT"); SERIAL_EOL(); } @@ -317,7 +317,7 @@ class FilamentSensorBase { static uint8_t was_out; // = 0 if (out != TEST(was_out, s)) { TBI(was_out, s); - SERIAL_ECHOLNPAIR_P(PSTR("Filament Sensor "), '0' + s, out ? PSTR(" OUT") : PSTR(" IN")); + SERIAL_ECHOLNPGM_P(PSTR("Filament Sensor "), '0' + s, out ? PSTR(" OUT") : PSTR(" IN")); } #endif } @@ -352,7 +352,7 @@ class FilamentSensorBase { if (ELAPSED(ms, t)) { t = millis() + 1000UL; LOOP_L_N(i, NUM_RUNOUT_SENSORS) - SERIAL_ECHOPAIR_P(i ? PSTR(", ") : PSTR("Remaining mm: "), runout_mm_countdown[i]); + SERIAL_ECHOPGM_P(i ? PSTR(", ") : PSTR("Remaining mm: "), runout_mm_countdown[i]); SERIAL_EOL(); } #endif diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 99cfd996c8..97fedf13c5 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -226,7 +226,7 @@ SERIAL_ECHO(timestamp); SERIAL_ECHOPGM(": "); st.printLabel(); - SERIAL_ECHOLNPAIR(" driver overtemperature warning! (", st.getMilliamps(), "mA)"); + SERIAL_ECHOLNPGM(" driver overtemperature warning! (", st.getMilliamps(), "mA)"); } template @@ -271,7 +271,7 @@ st.rms_current(I_rms); #if ENABLED(REPORT_CURRENT_CHANGE) st.printLabel(); - SERIAL_ECHOLNPAIR(" current decreased to ", I_rms); + SERIAL_ECHOLNPGM(" current decreased to ", I_rms); #endif } } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 87780486eb..1f7d5cf1a5 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -300,7 +300,7 @@ class TMCMarlin : public TMC266 template void tmc_print_current(TMC &st) { st.printLabel(); - SERIAL_ECHOLNPAIR(" driver current: ", st.getMilliamps()); + SERIAL_ECHOLNPGM(" driver current: ", st.getMilliamps()); } #if ENABLED(MONITOR_DRIVER_STATUS) @@ -322,7 +322,7 @@ void tmc_print_current(TMC &st) { template void tmc_print_pwmthrs(TMC &st) { st.printLabel(); - SERIAL_ECHOLNPAIR(" stealthChop max speed: ", st.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" stealthChop max speed: ", st.get_pwm_thrs()); } #endif #if USE_SENSORLESS diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 755224544c..5f5209cdd4 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -84,7 +84,7 @@ void TWIBus::send() { void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) { SERIAL_ECHO_START(); SERIAL_ECHOPGM_P(pref); - SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:"); + SERIAL_ECHOPGM(": from:", adr, " bytes:", bytes, " data:"); } // static diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 882197139e..ba14e6f0b4 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -539,7 +539,7 @@ void GcodeSuite::G26() { if (bedtemp) { if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) { - SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C)."); + SERIAL_ECHOLNPGM("?Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C)."); return; } g26.bed_temp = bedtemp; diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 3a4e1bdd5a..8d5c057361 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -106,19 +106,19 @@ void GcodeSuite::G35() { const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { - SERIAL_ECHOPAIR("G35 failed at point ", i + 1, " ("); + SERIAL_ECHOPGM("G35 failed at point ", i + 1, " ("); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); SERIAL_CHAR(')'); - SERIAL_ECHOLNPAIR_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y); + SERIAL_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y); err_break = true; break; } if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("Probing point ", i + 1, " ("); + DEBUG_ECHOPGM("Probing point ", i + 1, " ("); DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); DEBUG_CHAR(')'); - DEBUG_ECHOLNPAIR_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height); + DEBUG_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height); } z_measured[i] = z_probed_height; @@ -138,9 +138,9 @@ void GcodeSuite::G35() { SERIAL_ECHOPGM("Turn "); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); - SERIAL_ECHOPAIR(" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", " by ", ABS(full_turns), " turns"); - if (minutes) SERIAL_ECHOPAIR(" and ", ABS(minutes), " minutes"); - if (ENABLED(REPORT_TRAMMING_MM)) SERIAL_ECHOPAIR(" (", -diff, "mm)"); + SERIAL_ECHOPGM(" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW", " by ", ABS(full_turns), " turns"); + if (minutes) SERIAL_ECHOPGM(" and ", ABS(minutes), " minutes"); + if (ENABLED(REPORT_TRAMMING_MM)) SERIAL_ECHOPGM(" (", -diff, "mm)"); SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 55055a5b02..1110ce7ccf 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -76,9 +76,9 @@ void GcodeSuite::M420() { TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y))); } SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh "); - SERIAL_ECHOPAIR(" (", x_min); + SERIAL_ECHOPGM(" (", x_min); SERIAL_CHAR(','); SERIAL_ECHO(y_min); - SERIAL_ECHOPAIR(")-(", x_max); + SERIAL_ECHOPGM(")-(", x_max); SERIAL_CHAR(','); SERIAL_ECHO(y_max); SERIAL_ECHOLNPGM(")"); } @@ -108,7 +108,7 @@ void GcodeSuite::M420() { if (!WITHIN(storage_slot, 0, a - 1)) { SERIAL_ECHOLNPGM("?Invalid storage slot."); - SERIAL_ECHOLNPAIR("?Use 0 to ", a - 1); + SERIAL_ECHOLNPGM("?Use 0 to ", a - 1); return; } @@ -128,7 +128,7 @@ void GcodeSuite::M420() { ubl.display_map(parser.byteval('T')); SERIAL_ECHOPGM("Mesh is "); if (!ubl.mesh_is_valid()) SERIAL_ECHOPGM("in"); - SERIAL_ECHOLNPAIR("valid\nStorage slot: ", ubl.storage_slot); + SERIAL_ECHOLNPGM("valid\nStorage slot: ", ubl.storage_slot); } #endif // AUTO_BED_LEVELING_UBL @@ -246,7 +246,7 @@ void GcodeSuite::M420_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR( TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) )); - SERIAL_ECHOPAIR_P( + SERIAL_ECHOPGM_P( PSTR(" M420 S"), planner.leveling_active #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index f756aa89df..0eb13dba96 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -379,7 +379,7 @@ G29_TYPE GcodeSuite::G29() { if (!probe.good_bounds(abl.probe_position_lf, abl.probe_position_rb)) { if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR("G29 L", abl.probe_position_lf.x, " R", abl.probe_position_rb.x, + DEBUG_ECHOLNPGM("G29 L", abl.probe_position_lf.x, " R", abl.probe_position_rb.x, " F", abl.probe_position_lf.y, " B", abl.probe_position_rb.y); } SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds."); @@ -470,7 +470,7 @@ G29_TYPE GcodeSuite::G29() { if (abl.verbose_level || seenQ) { SERIAL_ECHOPGM("Manual G29 "); if (g29_in_progress) - SERIAL_ECHOLNPAIR("point ", _MIN(abl.abl_probe_index + 1, abl.abl_points), " of ", abl.abl_points); + SERIAL_ECHOLNPGM("point ", _MIN(abl.abl_probe_index + 1, abl.abl_points), " of ", abl.abl_points); else SERIAL_ECHOLNPGM("idle"); } @@ -513,7 +513,7 @@ G29_TYPE GcodeSuite::G29() { z_values[abl.meshCount.x][abl.meshCount.y] = newz; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, newz)); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_P(PSTR("Save X"), abl.meshCount.x, SP_Y_STR, abl.meshCount.y, SP_Z_STR, abl.measured_z + abl.Z_offset); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(PSTR("Save X"), abl.meshCount.x, SP_Y_STR, abl.meshCount.y, SP_Z_STR, abl.measured_z + abl.Z_offset); #endif } @@ -635,7 +635,7 @@ G29_TYPE GcodeSuite::G29() { // Avoid probing outside the round or hexagonal area if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue; - if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", pt_index, "/", abl.abl_points, "."); + if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); @@ -680,7 +680,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points LOOP_L_N(i, 3) { - if (abl.verbose_level) SERIAL_ECHOLNPAIR("Probing point ", i + 1, "/3."); + if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); // Retain the last probe position @@ -842,7 +842,7 @@ G29_TYPE GcodeSuite::G29() { && NEAR(current_position.y, abl.probePos.y - probe.offset_xy.y) ) { const float simple_z = current_position.z - abl.measured_z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Probed Z", simple_z, " Matrix Z", converted.z, " Discrepancy ", simple_z - converted.z); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Probed Z", simple_z, " Matrix Z", converted.z, " Discrepancy ", simple_z - converted.z); converted.z = simple_z; } @@ -855,14 +855,14 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) if (!abl.dryrun) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("G29 uncorrected Z:", current_position.z); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("G29 uncorrected Z:", current_position.z); // Unapply the offset because it is going to be immediately applied // and cause compensation movement in Z const float fade_scaling_factor = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.fade_scaling_factor_for_z(current_position.z), 1); current_position.z -= fade_scaling_factor * bilinear_z_offset(current_position); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(" corrected Z:", current_position.z); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(" corrected Z:", current_position.z); } #endif // ABL_PLANAR @@ -880,7 +880,7 @@ G29_TYPE GcodeSuite::G29() { TERN_(HAS_BED_PROBE, probe.move_z_after_probing()); #ifdef Z_PROBE_END_SCRIPT - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); planner.synchronize(); process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); #endif diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index adfe61d3d2..11e503f013 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -173,7 +173,7 @@ void GcodeSuite::G29() { if (parser.seenval('I')) { ix = parser.value_int(); if (!WITHIN(ix, 0, (GRID_MAX_POINTS_X) - 1)) { - SERIAL_ECHOLNPAIR("I out of range (0-", (GRID_MAX_POINTS_X) - 1, ")"); + SERIAL_ECHOLNPGM("I out of range (0-", (GRID_MAX_POINTS_X) - 1, ")"); return; } } @@ -183,7 +183,7 @@ void GcodeSuite::G29() { if (parser.seenval('J')) { iy = parser.value_int(); if (!WITHIN(iy, 0, (GRID_MAX_POINTS_Y) - 1)) { - SERIAL_ECHOLNPAIR("J out of range (0-", (GRID_MAX_POINTS_Y) - 1, ")"); + SERIAL_ECHOLNPGM("J out of range (0-", (GRID_MAX_POINTS_Y) - 1, ")"); return; } } @@ -213,7 +213,7 @@ void GcodeSuite::G29() { } // switch(state) if (state == MeshNext) { - SERIAL_ECHOLNPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); + SERIAL_ECHOLNPGM("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index d85c0306d4..dc93ba3d2f 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -270,7 +270,7 @@ void GcodeSuite::G28() { #if HAS_HOMING_CURRENT auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b) { - DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); + DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) const int16_t tmc_save_current_X = stepperX.getMilliamps(); @@ -371,7 +371,7 @@ void GcodeSuite::G28() { if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); TERN_(BLTOUCH, bltouch.init()); } diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index a897a10115..597801cf52 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -107,14 +107,14 @@ void print_signed_float(PGM_P const prefix, const_float_t f) { * - Print the delta settings */ static void print_calibration_settings(const bool end_stops, const bool tower_angles) { - SERIAL_ECHOPAIR(".Height:", delta_height); + SERIAL_ECHOPGM(".Height:", delta_height); if (end_stops) { print_signed_float(PSTR("Ex"), delta_endstop_adj.a); print_signed_float(PSTR("Ey"), delta_endstop_adj.b); print_signed_float(PSTR("Ez"), delta_endstop_adj.c); } if (end_stops && tower_angles) { - SERIAL_ECHOPAIR(" Radius:", delta_radius); + SERIAL_ECHOPGM(" Radius:", delta_radius); SERIAL_EOL(); SERIAL_CHAR('.'); SERIAL_ECHO_SP(13); @@ -125,7 +125,7 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an print_signed_float(PSTR("Tz"), delta_tower_angle_trim.c); } if ((!end_stops && tower_angles) || (end_stops && !tower_angles)) { // XOR - SERIAL_ECHOPAIR(" Radius:", delta_radius); + SERIAL_ECHOPGM(" Radius:", delta_radius); } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index c5f5e582a9..dd1dd5622a 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -201,7 +201,7 @@ void GcodeSuite::G34() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> probing all positions."); const int iter = iteration + 1; - SERIAL_ECHOLNPAIR("\nG34 Iteration: ", iter); + SERIAL_ECHOLNPGM("\nG34 Iteration: ", iter); #if HAS_STATUS_MESSAGE char str[iter_str_len + 2 + 1]; sprintf_P(str, msg_iteration, iter); @@ -221,7 +221,7 @@ void GcodeSuite::G34() { if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe); if (DEBUGGING(LEVELING)) - DEBUG_ECHOLNPAIR_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y); + DEBUG_ECHOLNPGM_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. // Probing sanity check is disabled, as it would trigger even in normal cases because @@ -238,7 +238,7 @@ void GcodeSuite::G34() { // the next iteration of probing. This allows adjustments to be made away from the bed. z_measured[iprobe] = z_probed_height + Z_CLEARANCE_BETWEEN_PROBES; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]); // Remember the minimum measurement to calculate the correction later on z_measured_min = _MIN(z_measured_min, z_measured[iprobe]); @@ -267,7 +267,7 @@ void GcodeSuite::G34() { linear_fit_data lfd; incremental_LSF_reset(&lfd); LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { - SERIAL_ECHOLNPAIR("PROBEPT_", i, ": ", z_measured[i]); + SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); @@ -278,7 +278,7 @@ void GcodeSuite::G34() { z_measured_min = _MIN(z_measured_min, z_measured[i]); } - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS), "Calculated Z1=", z_measured[0], " Z2=", z_measured[1], @@ -288,7 +288,7 @@ void GcodeSuite::G34() { ); #endif - SERIAL_ECHOLNPAIR("\n" + SERIAL_ECHOLNPGM("\n" "Z2-Z1=", ABS(z_measured[1] - z_measured[0]) #if TRIPLE_Z , " Z3-Z2=", ABS(z_measured[2] - z_measured[1]) @@ -372,8 +372,8 @@ void GcodeSuite::G34() { // Check for less accuracy compared to last move if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " last_z_align_move = ", last_z_align_move[zstepper]); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " z_align_abs = ", z_align_abs); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " last_z_align_move = ", last_z_align_move[zstepper]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " z_align_abs = ", z_align_abs); adjustment_reverse = !adjustment_reverse; } @@ -385,7 +385,7 @@ void GcodeSuite::G34() { // Stop early if all measured points achieve accuracy target if (z_align_abs > z_auto_align_accuracy) success_break = false; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " corrected by ", z_align_move); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " corrected by ", z_align_move); // Lock all steppers except one stepper.set_all_z_lock(true, zstepper); @@ -395,7 +395,7 @@ void GcodeSuite::G34() { // Will match reversed Z steppers on dual steppers. Triple will need more work to map. if (adjustment_reverse) { z_align_move = -z_align_move; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " correction reversed to ", z_align_move); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " correction reversed to ", z_align_move); } #endif @@ -421,7 +421,7 @@ void GcodeSuite::G34() { if (err_break) SERIAL_ECHOLNPGM("G34 aborted."); else { - SERIAL_ECHOLNPAIR("Did ", iteration + (iteration != z_auto_align_iterations), " of ", z_auto_align_iterations); + SERIAL_ECHOLNPGM("Did ", iteration + (iteration != z_auto_align_iterations), " of ", z_auto_align_iterations); SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); } @@ -541,7 +541,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { report_heading(forReplay, PSTR(STR_Z_AUTO_ALIGN)); LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M422 S"), i + 1, SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y @@ -550,7 +550,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_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 diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index c8efea858c..23a66dd0c5 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -354,44 +354,44 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) - SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); + SERIAL_ECHOLNPGM(" Top: ", m.obj_side[TOP]); #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPAIR(" Left: ", m.obj_side[LEFT]); + SERIAL_ECHOLNPGM(" Left: ", m.obj_side[LEFT]); #endif #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]); + SERIAL_ECHOLNPGM(" Right: ", m.obj_side[RIGHT]); #endif #if HAS_Y_AXIS #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + SERIAL_ECHOLNPGM(" Front: ", m.obj_side[FRONT]); #endif #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + SERIAL_ECHOLNPGM(" Back: ", m.obj_side[BACK]); #endif #endif #if LINEAR_AXES >= 4 #if ENABLED(CALIBRATION_MEASURE_IMIN) - SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_IMAX) - SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); #endif #endif #if LINEAR_AXES >= 5 #if ENABLED(CALIBRATION_MEASURE_JMIN) - SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_JMAX) - SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); #endif #endif #if LINEAR_AXES >= 6 #if ENABLED(CALIBRATION_MEASURE_KMIN) - SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_KMAX) - SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]); #endif #endif SERIAL_EOL(); @@ -400,20 +400,20 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_center(const measurements_t &m) { SERIAL_ECHOLNPGM("Center:"); #if HAS_X_CENTER - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.obj_center.x); + SERIAL_ECHOLNPGM_P(SP_X_STR, m.obj_center.x); #endif #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y); + SERIAL_ECHOLNPGM_P(SP_Y_STR, m.obj_center.y); #endif - SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z); + SERIAL_ECHOLNPGM_P(SP_Z_STR, m.obj_center.z); #if HAS_I_CENTER - SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i); + SERIAL_ECHOLNPGM_P(SP_I_STR, m.obj_center.i); #endif #if HAS_J_CENTER - SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j); + SERIAL_ECHOLNPGM_P(SP_J_STR, m.obj_center.j); #endif #if HAS_K_CENTER - SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k); + SERIAL_ECHOLNPGM_P(SP_K_STR, m.obj_center.k); #endif SERIAL_EOL(); } @@ -422,45 +422,45 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM("Backlash:"); #if AXIS_CAN_CALIBRATE(X) #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); + SERIAL_ECHOLNPGM(" Left: ", m.backlash[LEFT]); #endif #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); + SERIAL_ECHOLNPGM(" Right: ", m.backlash[RIGHT]); #endif #endif #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); + SERIAL_ECHOLNPGM(" Front: ", m.backlash[FRONT]); #endif #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); + SERIAL_ECHOLNPGM(" Back: ", m.backlash[BACK]); #endif #endif #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) - SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); + SERIAL_ECHOLNPGM(" Top: ", m.backlash[TOP]); #endif #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) #if ENABLED(CALIBRATION_MEASURE_IMIN) - SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_IMAX) - SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); #endif #endif #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) #if ENABLED(CALIBRATION_MEASURE_JMIN) - SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_JMAX) - SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); #endif #endif #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) #if ENABLED(CALIBRATION_MEASURE_KMIN) - SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); + SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); #endif #if ENABLED(CALIBRATION_MEASURE_KMAX) - SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); + SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); #endif #endif SERIAL_EOL(); @@ -471,22 +471,22 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHO(active_extruder); SERIAL_ECHOLNPGM(" Positional Error:"); #if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X) - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x); + SERIAL_ECHOLNPGM_P(SP_X_STR, m.pos_error.x); #endif #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); + SERIAL_ECHOLNPGM_P(SP_Y_STR, m.pos_error.y); #endif #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) - SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z); #endif #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) - SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i); + SERIAL_ECHOLNPGM_P(SP_I_STR, m.pos_error.i); #endif #if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J) - SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j); + SERIAL_ECHOLNPGM_P(SP_J_STR, m.pos_error.j); #endif #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K) - SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z); #endif SERIAL_EOL(); } @@ -494,10 +494,10 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_nozzle_dimensions(const measurements_t &m) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); #if HAS_X_CENTER - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); + SERIAL_ECHOLNPGM_P(SP_X_STR, m.nozzle_outer_dimension.x); #endif #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); + SERIAL_ECHOLNPGM_P(SP_Y_STR, m.nozzle_outer_dimension.y); #endif SERIAL_EOL(); UNUSED(m); @@ -509,7 +509,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // inline void report_hotend_offsets() { LOOP_S_L_N(e, 1, HOTENDS) - SERIAL_ECHOLNPAIR_P(PSTR("T"), e, PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); + SERIAL_ECHOLNPGM_P(PSTR("T"), 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_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 2d1b9443bf..170958cab4 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -171,7 +171,7 @@ void GcodeSuite::G76() { millis_t next_temp_report = millis() + 1000; auto report_targets = [&](const celsius_t tb, const celsius_t tp) { - SERIAL_ECHOLNPAIR("Target Bed:", tb, " Probe:", tp); + SERIAL_ECHOLNPGM("Target Bed:", tb, " Probe:", tp); }; if (do_bed_cal) { @@ -211,7 +211,7 @@ void GcodeSuite::G76() { if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break; } - SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); + SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index()); if (temp_comp.finish_calibration(TSI_BED)) { say_successfully_calibrated(); SERIAL_ECHOLNPGM(" bed."); @@ -255,7 +255,7 @@ void GcodeSuite::G76() { do_blocking_move_to(noz_pos_xyz); say_waiting_for_probe_heating(); - SERIAL_ECHOLNPAIR(" Bed:", target_bed, " Probe:", target_probe); + SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { @@ -270,7 +270,7 @@ void GcodeSuite::G76() { if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break; } - SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); + SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index()); if (temp_comp.finish_calibration(TSI_PROBE)) say_successfully_calibrated(); else @@ -325,7 +325,7 @@ void GcodeSuite::M871() { TSI_PROBE ); if (idx > 0 && temp_comp.set_offset(mod, idx - 1, offset_val)) - SERIAL_ECHOLNPAIR("Set value: ", offset_val); + SERIAL_ECHOLNPGM("Set value: ", offset_val); else SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant)."); diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index ee572e033d..0e2d42907a 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -202,7 +202,7 @@ inline int check_for_free_memory_corruption(PGM_P const title) { char *start_free_memory = free_memory_start, *end_free_memory = free_memory_end; int n = end_free_memory - start_free_memory; - SERIAL_ECHOLNPAIR("\nfmc() n=", n, + SERIAL_ECHOLNPGM("\nfmc() n=", n, "\nfree_memory_start=", hex_address(free_memory_start), " end=", hex_address(end_free_memory)); @@ -227,15 +227,15 @@ inline int check_for_free_memory_corruption(PGM_P const title) { if (start_free_memory[i] == TEST_BYTE) { int32_t j = count_test_bytes(start_free_memory + i); if (j > 8) { - //SERIAL_ECHOPAIR("Found ", j); - //SERIAL_ECHOLNPAIR(" bytes free at ", hex_address(start_free_memory + i)); + //SERIAL_ECHOPGM("Found ", j); + //SERIAL_ECHOLNPGM(" bytes free at ", hex_address(start_free_memory + i)); i += j; block_cnt++; - SERIAL_ECHOLNPAIR(" (", block_cnt, ") found=", j); + SERIAL_ECHOLNPGM(" (", block_cnt, ") found=", j); } } } - SERIAL_ECHOPAIR(" block_found=", block_cnt); + SERIAL_ECHOPGM(" block_found=", block_cnt); if (block_cnt != 1) SERIAL_ECHOLNPGM("\nMemory Corruption detected in free memory area."); @@ -267,7 +267,7 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ if (*addr == TEST_BYTE) { const int32_t j = count_test_bytes(addr); if (j > 8) { - SERIAL_ECHOLNPAIR("Found ", j, " bytes free at ", hex_address(addr)); + SERIAL_ECHOLNPGM("Found ", j, " bytes free at ", hex_address(addr)); if (j > max_cnt) { max_cnt = j; max_addr = addr; @@ -277,11 +277,11 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ } } } - if (block_cnt > 1) SERIAL_ECHOLNPAIR( + if (block_cnt > 1) SERIAL_ECHOLNPGM( "\nMemory Corruption detected in free memory area." "\nLargest free block is ", max_cnt, " bytes at ", hex_address(max_addr) ); - SERIAL_ECHOLNPAIR("check_for_free_memory_corruption() = ", check_for_free_memory_corruption(PSTR("M100 F "))); + SERIAL_ECHOLNPGM("check_for_free_memory_corruption() = ", check_for_free_memory_corruption(PSTR("M100 F "))); } #if ENABLED(M100_FREE_MEMORY_CORRUPTOR) @@ -299,7 +299,7 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_ for (uint32_t i = 1; i <= size; i++) { char * const addr = start_free_memory + i * j; *addr = i; - SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr)); + SERIAL_ECHOPGM("\nCorrupting address: ", hex_address(addr)); } SERIAL_EOL(); } @@ -327,8 +327,8 @@ inline void init_free_memory(char *start_free_memory, int32_t size) { for (int32_t i = 0; i < size; i++) { if (start_free_memory[i] != TEST_BYTE) { - SERIAL_ECHOPAIR("? address : ", hex_address(start_free_memory + i)); - SERIAL_ECHOLNPAIR("=", hex_byte(start_free_memory[i])); + SERIAL_ECHOPGM("? address : ", hex_address(start_free_memory + i)); + SERIAL_ECHOLNPGM("=", hex_byte(start_free_memory[i])); SERIAL_EOL(); } } @@ -340,14 +340,14 @@ inline void init_free_memory(char *start_free_memory, int32_t size) { void GcodeSuite::M100() { char *sp = top_of_stack(); if (!free_memory_end) free_memory_end = sp - MEMORY_END_CORRECTION; - SERIAL_ECHOPAIR("\nbss_end : ", hex_address(end_bss)); - if (heaplimit) SERIAL_ECHOPAIR("\n__heaplimit : ", hex_address(heaplimit)); - SERIAL_ECHOPAIR("\nfree_memory_start : ", hex_address(free_memory_start)); - if (stacklimit) SERIAL_ECHOPAIR("\n__stacklimit : ", hex_address(stacklimit)); - SERIAL_ECHOPAIR("\nfree_memory_end : ", hex_address(free_memory_end)); + SERIAL_ECHOPGM("\nbss_end : ", hex_address(end_bss)); + if (heaplimit) SERIAL_ECHOPGM("\n__heaplimit : ", hex_address(heaplimit)); + SERIAL_ECHOPGM("\nfree_memory_start : ", hex_address(free_memory_start)); + if (stacklimit) SERIAL_ECHOPGM("\n__stacklimit : ", hex_address(stacklimit)); + SERIAL_ECHOPGM("\nfree_memory_end : ", hex_address(free_memory_end)); if (MEMORY_END_CORRECTION) - SERIAL_ECHOPAIR("\nMEMORY_END_CORRECTION : ", MEMORY_END_CORRECTION); - SERIAL_ECHOLNPAIR("\nStack Pointer : ", hex_address(sp)); + SERIAL_ECHOPGM("\nMEMORY_END_CORRECTION : ", MEMORY_END_CORRECTION); + SERIAL_ECHOLNPGM("\nStack Pointer : ", hex_address(sp)); // Always init on the first invocation of M100 static bool m100_not_initialized = true; diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 9f7e00738b..1d314a37d3 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -86,7 +86,7 @@ void GcodeSuite::M425() { SERIAL_ECHOPGM("Backlash Correction "); if (!backlash.correction) SERIAL_ECHOPGM("in"); SERIAL_ECHOLNPGM("active:"); - SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); + SERIAL_ECHOLNPGM(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) { SERIAL_CHAR(' ', AXIS_CHAR(a)); @@ -95,7 +95,7 @@ void GcodeSuite::M425() { } #ifdef BACKLASH_SMOOTHING_MM - SERIAL_ECHOLNPAIR(" Smoothing (mm): S", backlash.smoothing_mm); + SERIAL_ECHOLNPGM(" Smoothing (mm): S", backlash.smoothing_mm); #endif #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) @@ -115,7 +115,7 @@ void GcodeSuite::M425() { void GcodeSuite::M425_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_BACKLASH_COMPENSATION)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M425 F"), backlash.get_correction() #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 19b11f602a..9db90c76ac 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -162,7 +162,7 @@ void GcodeSuite::M48() { #endif ); if (verbose_level > 3) { - SERIAL_ECHOPAIR("Start radius:", radius, " angle:", angle, " dir:"); + SERIAL_ECHOPGM("Start radius:", radius, " angle:", angle, " dir:"); if (dir > 0) SERIAL_CHAR('C'); SERIAL_ECHOLNPGM("CW"); } @@ -200,7 +200,7 @@ void GcodeSuite::M48() { 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); + SERIAL_ECHOLNPGM_P(PSTR("Moving inward: X"), next_pos.x, SP_Y_STR, next_pos.y); } #elif HAS_ENDSTOPS // For a rectangular bed just keep the probe in bounds @@ -209,7 +209,7 @@ void GcodeSuite::M48() { #endif if (verbose_level > 3) - SERIAL_ECHOLNPAIR_P(PSTR("Going to: X"), next_pos.x, SP_Y_STR, next_pos.y); + SERIAL_ECHOLNPGM_P(PSTR("Going to: X"), next_pos.x, SP_Y_STR, next_pos.y); do_blocking_move_to_xy(next_pos); } // n_legs loop @@ -241,7 +241,7 @@ void GcodeSuite::M48() { if (verbose_level > 1) { SERIAL_ECHO(n + 1); - SERIAL_ECHOPAIR(" of ", n_samples); + SERIAL_ECHOPGM(" of ", n_samples); SERIAL_ECHOPAIR_F(": z: ", pz, 3); SERIAL_CHAR(' '); dev_report(verbose_level > 2, mean, sigma, min, max); diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index d4d49d6a6c..09b5ec8d4e 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M665_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_DELTA_SETTINGS)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) , PSTR(" R"), LINEAR_UNIT(delta_radius) , PSTR(" H"), LINEAR_UNIT(delta_height) @@ -133,7 +133,7 @@ void GcodeSuite::M665_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_SCARA_S TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M665 S"), segments_per_second #if HAS_SCARA_OFFSET , SP_P_STR, scara_home_offset.a diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 6e1ebfb5db..c4149c2352 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -52,17 +52,17 @@ is_err = true; else { delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); } } } - if (is_err) SERIAL_ECHOLNPAIR("?M666 offsets must be <= 0"); + if (is_err) SERIAL_ECHOLNPGM("?M666 offsets must be <= 0"); if (!is_set) M666_report(); } void GcodeSuite::M666_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) , SP_Z_STR, LINEAR_UNIT(delta_endstop_adj.c) @@ -108,22 +108,22 @@ report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); SERIAL_ECHOPGM(" M666"); #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); + SERIAL_ECHOLNPGM_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); #endif #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); + SERIAL_ECHOLNPGM_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); #endif #if ENABLED(Z_MULTI_ENDSTOPS) #if NUM_Z_STEPPER_DRIVERS >= 3 - SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + SERIAL_ECHOPGM(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); report_echo_start(forReplay); - SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); + SERIAL_ECHOPGM(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); #if NUM_Z_STEPPER_DRIVERS >= 4 report_echo_start(forReplay); - SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); + SERIAL_ECHOPGM(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj)); #endif #else - SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); + SERIAL_ECHOLNPGM_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); #endif #endif } diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 048a2887e6..2880bd9943 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -84,7 +84,7 @@ #if EXTRUDERS == 1 { - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " M200 S", parser.volumetric_enabled, " D", LINEAR_UNIT(planner.filament_size[0]) #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) @@ -92,10 +92,10 @@ ); } #else - SERIAL_ECHOLNPAIR(" M200 S", parser.volumetric_enabled); + SERIAL_ECHOLNPGM(" M200 S", parser.volumetric_enabled); LOOP_L_N(i, EXTRUDERS) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " M200 T", i, " D", LINEAR_UNIT(planner.filament_size[i]) #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) @@ -134,7 +134,7 @@ void GcodeSuite::M201() { void GcodeSuite::M201_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_MAX_ACCELERATION)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), @@ -150,7 +150,7 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(i, E_STEPPERS) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M201 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) ); @@ -179,7 +179,7 @@ void GcodeSuite::M203() { void GcodeSuite::M203_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_MAX_FEEDRATES)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), @@ -195,7 +195,7 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(i, E_STEPPERS) { SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M203 T"), i , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) ); @@ -225,7 +225,7 @@ void GcodeSuite::M204() { void GcodeSuite::M204_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_ACCELERATION_P_R_T)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration) , PSTR(" R"), LINEAR_UNIT(planner.settings.retract_acceleration) , SP_T_STR, LINEAR_UNIT(planner.settings.travel_acceleration) @@ -292,7 +292,7 @@ void GcodeSuite::M205_report(const bool forReplay/*=true*/) { TERN_(HAS_CLASSIC_E_JERK, " E") ")" )); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M205 B"), LINEAR_UNIT(planner.settings.min_segment_time_us) , PSTR(" S"), LINEAR_UNIT(planner.settings.min_feedrate_mm_s) , SP_T_STR, LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s) diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 72b7d16ac0..11d8c43ef0 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -136,33 +136,33 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) { SERIAL_ECHOPGM(" M217"); #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - SERIAL_ECHOPAIR(" S", LINEAR_UNIT(toolchange_settings.swap_length)); - SERIAL_ECHOPAIR_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), + SERIAL_ECHOPGM(" S", LINEAR_UNIT(toolchange_settings.swap_length)); + SERIAL_ECHOPGM_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); - SERIAL_ECHOPAIR(" R", LINEAR_UNIT(toolchange_settings.retract_speed), + SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed), " U", LINEAR_UNIT(toolchange_settings.unretract_speed), " F", toolchange_settings.fan_speed, " G", toolchange_settings.fan_time); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) - SERIAL_ECHOPAIR(" A", migration.automode); - SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); + SERIAL_ECHOPGM(" A", migration.automode); + SERIAL_ECHOPGM(" L", LINEAR_UNIT(migration.last)); #endif #if ENABLED(TOOLCHANGE_PARK) - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(toolchange_settings.enable_park)); - SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)); - SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)); + SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park)); + SERIAL_ECHOPGM_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)); + SERIAL_ECHOPGM_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)); #endif #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) - SERIAL_ECHOPAIR(" V", LINEAR_UNIT(enable_first_prime)); + SERIAL_ECHOPGM(" V", LINEAR_UNIT(enable_first_prime)); #endif #endif - SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(toolchange_settings.z_raise)); + SERIAL_ECHOLNPGM_P(SP_Z_STR, LINEAR_UNIT(toolchange_settings.z_raise)); } #endif // HAS_MULTI_EXTRUDER diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index 249c16622f..c95cd6c1b9 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -60,7 +60,7 @@ void GcodeSuite::M218_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_HOTEND_OFFSETS)); LOOP_S_L_N(e, 1, HOTENDS) { report_echo_start(forReplay); - SERIAL_ECHOPAIR_P( + SERIAL_ECHOPGM_P( PSTR(" M218 T"), e, SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp index 75339f10b9..c9070df803 100644 --- a/Marlin/src/gcode/config/M220.cpp +++ b/Marlin/src/gcode/config/M220.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M220() { if (parser.seenval('S')) feedrate_percentage = parser.value_int(); if (!parser.seen_any()) { - SERIAL_ECHOPAIR("FR:", feedrate_percentage); + SERIAL_ECHOPGM("FR:", feedrate_percentage); SERIAL_CHAR('%'); SERIAL_EOL(); } diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp index e380bfb1c7..f653aded7c 100644 --- a/Marlin/src/gcode/config/M221.cpp +++ b/Marlin/src/gcode/config/M221.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M221() { else { SERIAL_ECHO_START(); SERIAL_CHAR('E', '0' + target_extruder); - SERIAL_ECHOPAIR(" Flow: ", planner.flow_percentage[target_extruder]); + SERIAL_ECHOPGM(" Flow: ", planner.flow_percentage[target_extruder]); SERIAL_CHAR('%'); SERIAL_EOL(); } diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index 36b62f5163..b6644eb4ab 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M281_report(const bool forReplay/*=true*/) { case Z_PROBE_SERVO_NR: #endif report_echo_start(forReplay); - SERIAL_ECHOLNPAIR(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]); + SERIAL_ECHOLNPGM(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]); } } } diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp index 904744c958..19b438309c 100644 --- a/Marlin/src/gcode/config/M301.cpp +++ b/Marlin/src/gcode/config/M301.cpp @@ -83,7 +83,7 @@ void GcodeSuite::M301_report(const bool forReplay/*=true*/, const int8_t eindex/ HOTEND_LOOP() { if (e == eindex || eindex == -1) { report_echo_start(forReplay); - SERIAL_ECHOPAIR_P( + SERIAL_ECHOPGM_P( #if ENABLED(PID_PARAMS_PER_HOTEND) PSTR(" M301 E"), e, SP_P_STR #else @@ -94,11 +94,11 @@ void GcodeSuite::M301_report(const bool forReplay/*=true*/, const int8_t eindex/ , PSTR(" D"), unscalePID_d(PID_PARAM(Kd, e)) ); #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPAIR_P(SP_C_STR, PID_PARAM(Kc, e)); - if (e == 0) SERIAL_ECHOPAIR(" L", thermalManager.lpq_len); + SERIAL_ECHOPGM_P(SP_C_STR, PID_PARAM(Kc, e)); + if (e == 0) SERIAL_ECHOPGM(" L", thermalManager.lpq_len); #endif #if ENABLED(PID_FAN_SCALING) - SERIAL_ECHOPAIR(" F", PID_PARAM(Kf, e)); + SERIAL_ECHOPGM(" F", PID_PARAM(Kf, e)); #endif SERIAL_EOL(); } diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index e3ce5a10ef..57c049e194 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M302() { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Cold extrudes are "); SERIAL_ECHOPGM_P(thermalManager.allow_cold_extrude ? PSTR("en") : PSTR("dis")); - SERIAL_ECHOLNPAIR("abled (min temp ", thermalManager.extrude_min_temp, "C)"); + SERIAL_ECHOLNPGM("abled (min temp ", thermalManager.extrude_min_temp, "C)"); } } diff --git a/Marlin/src/gcode/config/M309.cpp b/Marlin/src/gcode/config/M309.cpp index d5297e9563..01c4e62347 100644 --- a/Marlin/src/gcode/config/M309.cpp +++ b/Marlin/src/gcode/config/M309.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M309() { void GcodeSuite::M309_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_CHAMBER_PID)); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " M309 P", thermalManager.temp_chamber.pid.Kp , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) , " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 84757e7403..b2455c4b60 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -130,7 +130,7 @@ inline void servo_probe_test() { const uint8_t probe_index = parser.byteval('P', Z_PROBE_SERVO_NR); - SERIAL_ECHOLNPAIR("Servo probe test\n" + SERIAL_ECHOLNPGM("Servo probe test\n" ". using index: ", probe_index, ", deploy angle: ", servo_angles[probe_index][0], ", stow angle: ", servo_angles[probe_index][1] @@ -143,7 +143,7 @@ inline void servo_probe_test() { #define PROBE_TEST_PIN Z_MIN_PIN constexpr bool probe_inverting = Z_MIN_ENDSTOP_INVERTING; - SERIAL_ECHOLNPAIR(". Probe Z_MIN_PIN: ", PROBE_TEST_PIN); + SERIAL_ECHOLNPGM(". Probe Z_MIN_PIN: ", PROBE_TEST_PIN); SERIAL_ECHOPGM(". Z_MIN_ENDSTOP_INVERTING: "); #else @@ -151,7 +151,7 @@ inline void servo_probe_test() { #define PROBE_TEST_PIN Z_MIN_PROBE_PIN constexpr bool probe_inverting = Z_MIN_PROBE_ENDSTOP_INVERTING; - SERIAL_ECHOLNPAIR(". Probe Z_MIN_PROBE_PIN: ", PROBE_TEST_PIN); + SERIAL_ECHOLNPGM(". Probe Z_MIN_PROBE_PIN: ", PROBE_TEST_PIN); SERIAL_ECHOPGM( ". Z_MIN_PROBE_ENDSTOP_INVERTING: "); #endif @@ -211,11 +211,11 @@ inline void servo_probe_test() { if (deploy_state != stow_state) { SERIAL_ECHOLNPGM("= Mechanical Switch detected"); if (deploy_state) { - SERIAL_ECHOLNPAIR(" DEPLOYED state: HIGH (logic 1)", + SERIAL_ECHOLNPGM(" DEPLOYED state: HIGH (logic 1)", " STOWED (triggered) state: LOW (logic 0)"); } else { - SERIAL_ECHOLNPAIR(" DEPLOYED state: LOW (logic 0)", + SERIAL_ECHOLNPGM(" DEPLOYED state: LOW (logic 0)", " STOWED (triggered) state: HIGH (logic 1)"); } #if ENABLED(BLTOUCH) @@ -244,7 +244,7 @@ inline void servo_probe_test() { if (probe_counter == 15) SERIAL_ECHOLNPGM(": 30ms or more"); else - SERIAL_ECHOLNPAIR(" (+/- 4ms): ", probe_counter * 2); + SERIAL_ECHOLNPGM(" (+/- 4ms): ", probe_counter * 2); if (probe_counter >= 4) { if (probe_counter == 15) { diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 9f4f2ac65b..ecc5e63a3c 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -78,10 +78,10 @@ void GcodeSuite::M92() { micro_steps = argH ?: Z_MICROSTEPS; const float z_full_step_mm = micro_steps * planner.steps_to_mm[Z_AXIS]; SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("{ micro_steps:", micro_steps, ", z_full_step_mm:", z_full_step_mm); + SERIAL_ECHOPGM("{ micro_steps:", micro_steps, ", z_full_step_mm:", z_full_step_mm); if (wanted) { const float best = uint16_t(wanted / z_full_step_mm) * z_full_step_mm; - SERIAL_ECHOPAIR(", best:[", best); + SERIAL_ECHOPGM(", best:[", best); if (best != wanted) { SERIAL_CHAR(','); SERIAL_DECIMAL(best + z_full_step_mm); } SERIAL_CHAR(']'); } @@ -92,7 +92,7 @@ void GcodeSuite::M92() { void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) { report_heading_etc(forReplay, PSTR(STR_STEPS_PER_UNIT)); - SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), + SERIAL_ECHOPGM_P(LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), @@ -101,7 +101,7 @@ void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/ SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) ); #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); + SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif SERIAL_EOL(); @@ -109,7 +109,7 @@ void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/ LOOP_L_N(i, E_STEPPERS) { if (e >= 0 && i != e) continue; report_echo_start(forReplay); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M92 T"), i, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)]) ); diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index e762e3387f..69d20b4c5d 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -57,19 +57,19 @@ void GcodeSuite::M111() { SERIAL_ECHOPGM(STR_DEBUG_OFF); #if !defined(__AVR__) || !defined(USBCON) #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) - SERIAL_ECHOPAIR("\nBuffer Overruns: ", MYSERIAL1.buffer_overruns()); + SERIAL_ECHOPGM("\nBuffer Overruns: ", MYSERIAL1.buffer_overruns()); #endif #if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) - SERIAL_ECHOPAIR("\nFraming Errors: ", MYSERIAL1.framing_errors()); + SERIAL_ECHOPGM("\nFraming Errors: ", MYSERIAL1.framing_errors()); #endif #if ENABLED(SERIAL_STATS_DROPPED_RX) - SERIAL_ECHOPAIR("\nDropped bytes: ", MYSERIAL1.dropped()); + SERIAL_ECHOPGM("\nDropped bytes: ", MYSERIAL1.dropped()); #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - SERIAL_ECHOPAIR("\nMax RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); + SERIAL_ECHOPGM("\nMax RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif #endif // !__AVR__ || !USBCON } diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index b15cb6ef0a..a837d79533 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -41,7 +41,7 @@ void GcodeSuite::M211() { void GcodeSuite::M211_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_SOFT_ENDSTOPS)); - SERIAL_ECHOPAIR(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); + SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); serialprintln_onoff(soft_endstop._enabled); report_echo_start(forReplay); diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 23d43dd0a6..08efaab59d 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -127,26 +127,26 @@ case DXC_DUPLICATION_MODE: DEBUG_ECHOPGM("DUPLICATION"); break; case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break; } - DEBUG_ECHOPAIR("\nActive Ext: ", active_extruder); + DEBUG_ECHOPGM("\nActive Ext: ", active_extruder); if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); DEBUG_ECHOPGM(" parked."); - DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position.x); - DEBUG_ECHOPAIR("\ninactive_extruder_x: ", inactive_extruder_x); - DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", extruder_duplication_enabled); - DEBUG_ECHOPAIR("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); - DEBUG_ECHOPAIR("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); - DEBUG_ECHOPAIR("\ndelayed_move_time: ", delayed_move_time); - DEBUG_ECHOPAIR("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS); - DEBUG_ECHOPAIR("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS); - DEBUG_ECHOPAIR("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS); - DEBUG_ECHOPAIR("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); - DEBUG_ECHOPAIR("\toolchange_settings.z_raise=", toolchange_settings.z_raise); - DEBUG_ECHOPAIR("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET); + DEBUG_ECHOPGM("\nactive_extruder_x_pos: ", current_position.x); + DEBUG_ECHOPGM("\ninactive_extruder_x: ", inactive_extruder_x); + DEBUG_ECHOPGM("\nextruder_duplication_enabled: ", extruder_duplication_enabled); + DEBUG_ECHOPGM("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); + DEBUG_ECHOPGM("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); + DEBUG_ECHOPGM("\ndelayed_move_time: ", delayed_move_time); + DEBUG_ECHOPGM("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS); + DEBUG_ECHOPGM("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS); + DEBUG_ECHOPGM("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS); + DEBUG_ECHOPGM("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); + DEBUG_ECHOPGM("\toolchange_settings.z_raise=", toolchange_settings.z_raise); + DEBUG_ECHOPGM("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET); DEBUG_EOL(); HOTEND_LOOP() { - DEBUG_ECHOPAIR_P(SP_T_STR, e); - LOOP_LINEAR_AXES(a) DEBUG_ECHOPAIR(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); + DEBUG_ECHOPGM_P(SP_T_STR, e); + LOOP_LINEAR_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/control/M993_M994.cpp b/Marlin/src/gcode/control/M993_M994.cpp index ff9ff85bf5..252792e522 100644 --- a/Marlin/src/gcode/control/M993_M994.cpp +++ b/Marlin/src/gcode/control/M993_M994.cpp @@ -37,7 +37,7 @@ void GcodeSuite::M993() { char fname[] = "spiflash.bin"; card.openFileWrite(fname); if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open ", fname, " to write."); + SERIAL_ECHOLNPGM("Failed to open ", fname, " to write."); return; } @@ -65,7 +65,7 @@ void GcodeSuite::M994() { char fname[] = "spiflash.bin"; card.openFileRead(fname); if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open ", fname, " to read."); + SERIAL_ECHOLNPGM("Failed to open ", fname, " to read."); return; } diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 6a084d83ad..5e8f6b5436 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -49,7 +49,7 @@ void GcodeSuite::T(const int8_t tool_index) { DEBUG_SECTION(log_T, "T", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("...(", tool_index, ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("...(", tool_index, ")"); // Count this command as movement / activity reset_stepper_timeout(); diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp index cd7833c701..a06e98ad1e 100644 --- a/Marlin/src/gcode/eeprom/M500-M504.cpp +++ b/Marlin/src/gcode/eeprom/M500-M504.cpp @@ -75,14 +75,14 @@ void GcodeSuite::M502() { if (dowrite) { val = parser.byteval('V'); persistentStore.write_data(addr, &val); - SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", val); + SERIAL_ECHOLNPGM("Wrote address ", addr, " with ", val); } else { if (parser.seenval('T')) { const int endaddr = parser.value_ushort(); while (addr <= endaddr) { persistentStore.read_data(addr, &val); - SERIAL_ECHOLNPAIR("0x", hex_word(addr), ":", hex_byte(val)); + SERIAL_ECHOLNPGM("0x", hex_word(addr), ":", hex_byte(val)); addr++; safe_delay(10); } @@ -90,7 +90,7 @@ void GcodeSuite::M502() { } else { persistentStore.read_data(addr, &val); - SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", val); + SERIAL_ECHOLNPGM("Read address ", addr, " and got ", val); } } return; diff --git a/Marlin/src/gcode/feature/L6470/M122.cpp b/Marlin/src/gcode/feature/L6470/M122.cpp index cfac427642..1e5b37e4b7 100644 --- a/Marlin/src/gcode/feature/L6470/M122.cpp +++ b/Marlin/src/gcode/feature/L6470/M122.cpp @@ -68,7 +68,7 @@ inline void L6470_say_status(const L64XX_axis_t axis) { if (!(sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD)) SERIAL_ECHOPGM("IN"); SERIAL_ECHOPGM("VALID "); SERIAL_ECHOPGM_P(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? PSTR("COMPLETED ") : PSTR("Not PERFORMED")); - SERIAL_ECHOPAIR("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK "); + SERIAL_ECHOPGM("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK "); } SERIAL_ECHOPGM(" OVERCURRENT:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_OCD) == 0); if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) { diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index b1beed068a..2ab13f5b5d 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -63,7 +63,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { #if ENABLED(L6470_CHITCHAT) char tmp[10]; sprintf_P(tmp, PSTR("%4x "), status); - DEBUG_ECHOPAIR(" status: ", tmp); + DEBUG_ECHOPGM(" status: ", tmp); print_bin(status); #else UNUSED(status); @@ -104,13 +104,13 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { } SERIAL_EOL(); - SERIAL_ECHOPAIR("...MicroSteps: ", MicroSteps, + SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps, " ADC_OUT: ", L6470_ADC_out); SERIAL_ECHOPGM(" Vs_compensation: "); SERIAL_ECHOPGM_P((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? PSTR("ENABLED ") : PSTR("DISABLED")); - SERIAL_ECHOLNPAIR(" Compensation coefficient: ~", comp_coef * 0.01f); + SERIAL_ECHOLNPGM(" Compensation coefficient: ~", comp_coef * 0.01f); - SERIAL_ECHOPAIR("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD), + SERIAL_ECHOPGM("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD), " KVAL_RUN : ", motor.GetParam(L6470_KVAL_RUN), " KVAL_ACC: ", motor.GetParam(L6470_KVAL_ACC), " KVAL_DEC: ", motor.GetParam(L6470_KVAL_DEC), @@ -168,7 +168,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { SERIAL_ECHOLNPGM(" mA) Motor Status: NA"); const uint16_t MicroSteps = _BV(motor.GetParam(L6470_STEP_MODE) & 0x07); //NOMORE(MicroSteps, 16); - SERIAL_ECHOPAIR("...MicroSteps: ", MicroSteps, + SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps, " ADC_OUT: ", L6470_ADC_out); SERIAL_ECHOLNPGM(" Vs_compensation: NA\n"); @@ -185,7 +185,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { case 1: DEBUG_ECHOLNPGM("75V/uS") ; break; case 2: DEBUG_ECHOLNPGM("110V/uS") ; break; case 3: DEBUG_ECHOLNPGM("260V/uS") ; break; - default: DEBUG_ECHOLNPAIR("slew rate: ", (motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT); break; + default: DEBUG_ECHOLNPGM("slew rate: ", (motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT); break; } #endif SERIAL_EOL(); diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp index 3dd21ef985..ad0a91111d 100644 --- a/Marlin/src/gcode/feature/L6470/M916-918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp @@ -96,7 +96,7 @@ void GcodeSuite::M916() { if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold)) return; // quit if invalid user input - DEBUG_ECHOLNPAIR("feedrate = ", final_feedrate); + DEBUG_ECHOLNPGM("feedrate = ", final_feedrate); planner.synchronize(); // wait for all current movement commands to complete @@ -127,9 +127,9 @@ void GcodeSuite::M916() { do { if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) - DEBUG_ECHOLNPAIR("TVAL current (mA) = ", (M91x_counter + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); // report TVAL current for this run + DEBUG_ECHOLNPGM("TVAL current (mA) = ", (M91x_counter + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); // report TVAL current for this run else - DEBUG_ECHOLNPAIR("kval_hold = ", M91x_counter); // report KVAL_HOLD for this run + DEBUG_ECHOLNPGM("kval_hold = ", M91x_counter); // report KVAL_HOLD for this run for (j = 0; j < driver_count; j++) L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, M91x_counter); //set KVAL_HOLD or TVAL (same register address) @@ -236,7 +236,7 @@ void GcodeSuite::M917() { if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold)) return; // quit if invalid user input - DEBUG_ECHOLNPAIR("feedrate = ", final_feedrate); + DEBUG_ECHOLNPGM("feedrate = ", final_feedrate); planner.synchronize(); // wait for all current movement commands to complete @@ -252,18 +252,18 @@ void GcodeSuite::M917() { // 2 - OCD finalized - decreasing STALL - exit when STALL warning happens // 3 - OCD finalized - increasing STALL - exit when STALL warning stop // 4 - all testing completed - DEBUG_ECHOPAIR(".\n.\n.\nover_current threshold : ", (OCD_TH_val + 1) * 375); // first status display - DEBUG_ECHOPAIR(" (OCD_TH: : ", OCD_TH_val); + DEBUG_ECHOPGM(".\n.\n.\nover_current threshold : ", (OCD_TH_val + 1) * 375); // first status display + DEBUG_ECHOPGM(" (OCD_TH: : ", OCD_TH_val); if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) { - DEBUG_ECHOPAIR(") Stall threshold: ", (STALL_TH_val + 1) * 31.25); - DEBUG_ECHOPAIR(" (STALL_TH: ", STALL_TH_val); + DEBUG_ECHOPGM(") Stall threshold: ", (STALL_TH_val + 1) * 31.25); + DEBUG_ECHOPGM(" (STALL_TH: ", STALL_TH_val); } DEBUG_ECHOLNPGM(")"); do { - if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) DEBUG_ECHOPAIR("STALL threshold : ", (STALL_TH_val + 1) * 31.25); - DEBUG_ECHOLNPAIR(" OCD threshold : ", (OCD_TH_val + 1) * 375); + if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) DEBUG_ECHOPGM("STALL threshold : ", (STALL_TH_val + 1) * 31.25); + DEBUG_ECHOLNPGM(" OCD threshold : ", (OCD_TH_val + 1) * 375); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate)); gcode.process_subcommands_now_P(gcode_string); @@ -303,7 +303,7 @@ void GcodeSuite::M917() { if (!(k % 4)) { kval_hold *= 0.95; DEBUG_EOL(); - DEBUG_ECHOLNPAIR("Lowering KVAL_HOLD by about 5% to ", kval_hold); + DEBUG_ECHOLNPGM("Lowering KVAL_HOLD by about 5% to ", kval_hold); for (j = 0; j < driver_count; j++) L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold); } @@ -590,8 +590,8 @@ void GcodeSuite::M918() { } m_steps = L64xxManager.get_param(axis_index[0], L6470_STEP_MODE) & 0x07; // get microsteps - DEBUG_ECHOLNPAIR("Microsteps = ", _BV(m_steps)); - DEBUG_ECHOLNPAIR("target (maximum) feedrate = ", final_feedrate); + DEBUG_ECHOLNPGM("Microsteps = ", _BV(m_steps)); + DEBUG_ECHOLNPGM("target (maximum) feedrate = ", final_feedrate); const float feedrate_inc = final_feedrate / 10, // Start at 1/10 of max & go up by 1/10 per step fr_limit = final_feedrate * 0.99f; // Rounding-safe comparison value @@ -612,7 +612,7 @@ void GcodeSuite::M918() { do { current_feedrate += feedrate_inc; - DEBUG_ECHOLNPAIR("...feedrate = ", current_feedrate); + DEBUG_ECHOLNPGM("...feedrate = ", current_feedrate); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(current_feedrate)); gcode.process_subcommands_now_P(gcode_string); diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index e1859fb7d9..4ed601bbe8 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -115,11 +115,11 @@ void GcodeSuite::M900() { #if ENABLED(EXTRA_LIN_ADVANCE_K) #if EXTRUDERS < 2 - SERIAL_ECHOLNPAIR("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); + SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); #else LOOP_L_N(i, EXTRUDERS) { const bool slot = TEST(lin_adv_slot, i); - SERIAL_ECHOLNPAIR("Advance T", i, " S", slot, " K", planner.extruder_advance_K[i], + SERIAL_ECHOLNPGM("Advance T", i, " S", slot, " K", planner.extruder_advance_K[i], "(S", !slot, " K", other_extruder_advance_K[i], ")"); SERIAL_EOL(); } @@ -129,7 +129,7 @@ void GcodeSuite::M900() { SERIAL_ECHO_START(); #if EXTRUDERS < 2 - SERIAL_ECHOLNPAIR("Advance K=", planner.extruder_advance_K[0]); + SERIAL_ECHOLNPGM("Advance K=", planner.extruder_advance_K[0]); #else SERIAL_ECHOPGM("Advance K"); LOOP_L_N(i, EXTRUDERS) { @@ -148,11 +148,11 @@ void GcodeSuite::M900_report(const bool forReplay/*=true*/) { report_heading(forReplay, PSTR(STR_LINEAR_ADVANCE)); #if EXTRUDERS < 2 report_echo_start(forReplay); - SERIAL_ECHOLNPAIR(" M900 K", planner.extruder_advance_K[0]); + SERIAL_ECHOLNPGM(" M900 K", planner.extruder_advance_K[0]); #else LOOP_L_N(i, EXTRUDERS) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR(" M900 T", i, " K", planner.extruder_advance_K[i]); + SERIAL_ECHOLNPGM(" M900 T", i, " K", planner.extruder_advance_K[i]); } #endif } diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index 3b72ee002c..eede16b5bd 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -68,7 +68,7 @@ void GcodeSuite::M710() { void GcodeSuite::M710_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_CONTROLLER_FAN)); - SERIAL_ECHOLNPAIR(" M710" + SERIAL_ECHOLNPGM(" M710" " S", int(controllerFan.settings.active_speed), " I", int(controllerFan.settings.idle_speed), " A", int(controllerFan.settings.auto_mode), diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index cde73ff271..a0b5c48e82 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -102,7 +102,7 @@ void GcodeSuite::M907() { void GcodeSuite::M907_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_STEPPER_MOTOR_CURRENTS)); #if HAS_MOTOR_CURRENT_PWM - SERIAL_ECHOLNPAIR_P( // PWM-based has 3 values: + SERIAL_ECHOLNPGM_P( // PWM-based has 3 values: PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y , SP_Z_STR, stepper.motor_current_setting[1] // Z , SP_E_STR, stepper.motor_current_setting[2] // E diff --git a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp index a70f7a61fe..ff174ecf13 100644 --- a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp +++ b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M404() { planner.volumetric_area_nominal = CIRCLE_AREA(filwidth.nominal_mm * 0.5); } else - SERIAL_ECHOLNPAIR("Filament dia (nominal mm):", filwidth.nominal_mm); + SERIAL_ECHOLNPGM("Filament dia (nominal mm):", filwidth.nominal_mm); } /** @@ -65,7 +65,7 @@ void GcodeSuite::M406() { * M407: Get measured filament diameter on serial output */ void GcodeSuite::M407() { - SERIAL_ECHOLNPAIR("Filament dia (measured mm):", filwidth.measured_mm); + SERIAL_ECHOLNPGM("Filament dia (measured mm):", filwidth.measured_mm); } #endif // FILAMENT_WIDTH_SENSOR diff --git a/Marlin/src/gcode/feature/mixing/M166.cpp b/Marlin/src/gcode/feature/mixing/M166.cpp index 5f788344eb..f42583d052 100644 --- a/Marlin/src/gcode/feature/mixing/M166.cpp +++ b/Marlin/src/gcode/feature/mixing/M166.cpp @@ -30,12 +30,12 @@ #include "../../../feature/mixing.h" inline void echo_mix() { - SERIAL_ECHOPAIR(" (", mixer.mix[0], "%|", mixer.mix[1], "%)"); + SERIAL_ECHOPGM(" (", mixer.mix[0], "%|", mixer.mix[1], "%)"); } inline void echo_zt(const int t, const_float_t z) { mixer.update_mix_from_vtool(t); - SERIAL_ECHOPAIR_P(SP_Z_STR, z, SP_T_STR, t); + SERIAL_ECHOPGM_P(SP_Z_STR, z, SP_T_STR, t); echo_mix(); } @@ -74,7 +74,7 @@ void GcodeSuite::M166() { #if ENABLED(GRADIENT_VTOOL) if (mixer.gradient.vtool_index >= 0) { - SERIAL_ECHOPAIR(" (T", mixer.gradient.vtool_index); + SERIAL_ECHOPGM(" (T", mixer.gradient.vtool_index); SERIAL_CHAR(')'); } #endif diff --git a/Marlin/src/gcode/feature/password/M510-M512.cpp b/Marlin/src/gcode/feature/password/M510-M512.cpp index eeb9b1df22..a5f017f5f3 100644 --- a/Marlin/src/gcode/feature/password/M510-M512.cpp +++ b/Marlin/src/gcode/feature/password/M510-M512.cpp @@ -66,7 +66,7 @@ void GcodeSuite::M510() { if (password.value_entry < CAT(1e, PASSWORD_LENGTH)) { password.is_set = true; password.value = password.value_entry; - SERIAL_ECHOLNPAIR(STR_PASSWORD_SET, password.value); // TODO: Update password.string + SERIAL_ECHOLNPGM(STR_PASSWORD_SET, password.value); // TODO: Update password.string } else SERIAL_ECHOLNPGM(STR_PASSWORD_TOO_LONG); diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 79451235b1..4c7190091c 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -47,7 +47,7 @@ void GcodeSuite::G60() { SBI(saved_slots[slot >> 3], slot & 0x07); #if ENABLED(SAVED_POSITIONS_DEBUG) - DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot); + DEBUG_ECHOPGM(STR_SAVED_POS " S", slot); const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOLNPAIR_F_P( LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e, diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index a10c8217ef..f3e5a2ab38 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -69,7 +69,7 @@ void GcodeSuite::G61(void) { } else { if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { - DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); + DEBUG_ECHOPGM(STR_RESTORING_POS " S", slot); LOOP_LINEAR_AXES(i) { destination[i] = parser.seen(AXIS_CHAR(i)) ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) @@ -83,7 +83,7 @@ void GcodeSuite::G61(void) { } #if HAS_EXTRUDERS if (parser.seen_test('E')) { - DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); + DEBUG_ECHOLNPGM(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); SYNC_E(stored_position[slot].e); } #endif diff --git a/Marlin/src/gcode/feature/pause/M603.cpp b/Marlin/src/gcode/feature/pause/M603.cpp index e26ab1c7b4..ebb110d2e7 100644 --- a/Marlin/src/gcode/feature/pause/M603.cpp +++ b/Marlin/src/gcode/feature/pause/M603.cpp @@ -69,12 +69,12 @@ void GcodeSuite::M603_report(const bool forReplay/*=true*/) { #if EXTRUDERS == 1 report_echo_start(forReplay); - SERIAL_ECHOPAIR(" M603 L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length), " ;"); + SERIAL_ECHOPGM(" M603 L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length), " ;"); say_units(); #else LOOP_L_N(e, EXTRUDERS) { report_echo_start(forReplay); - SERIAL_ECHOPAIR(" M603 T", e, " L", LINEAR_UNIT(fc_settings[e].load_length), " U", LINEAR_UNIT(fc_settings[e].unload_length), " ;"); + SERIAL_ECHOPGM(" M603 T", e, " L", LINEAR_UNIT(fc_settings[e].load_length), " U", LINEAR_UNIT(fc_settings[e].unload_length), " ;"); say_units(); } #endif diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index 34430fbc38..642a75d061 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -50,7 +50,7 @@ void GcodeSuite::M430() { #endif #endif if (do_report) { - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( #if ENABLED(POWER_MONITOR_CURRENT) "Current: ", power_monitor.getAmps(), "A" #if ENABLED(POWER_MONITOR_VOLTAGE) diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index b1be80619f..7c714dad25 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -58,7 +58,7 @@ void GcodeSuite::M413() { void GcodeSuite::M413_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_POWER_LOSS_RECOVERY)); - SERIAL_ECHOPAIR(" M413 S", AS_DIGIT(recovery.enabled), " ; "); + SERIAL_ECHOPGM(" M413 S", AS_DIGIT(recovery.enabled), " ; "); serialprintln_onoff(recovery.enabled); } diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 56c7f03604..bed08294ba 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M412() { SERIAL_ECHOPGM("Filament runout "); serialprint_onoff(runout.enabled); #if HAS_FILAMENT_RUNOUT_DISTANCE - SERIAL_ECHOPAIR(" ; Distance ", runout.runout_distance(), "mm"); + SERIAL_ECHOPGM(" ; Distance ", runout.runout_distance(), "mm"); #endif #if ENABLED(HOST_ACTION_COMMANDS) SERIAL_ECHOPGM(" ; Host handling "); @@ -68,7 +68,7 @@ void GcodeSuite::M412() { void GcodeSuite::M412_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " M412 S", runout.enabled #if HAS_FILAMENT_RUNOUT_DISTANCE , " D", LINEAR_UNIT(runout.runout_distance()) diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 243cf46560..8877603c3a 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -209,13 +209,13 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) say_M906(forReplay); #if AXIS_IS_TMC(X) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.getMilliamps()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps()); #endif #if AXIS_IS_TMC(Y) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.getMilliamps()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.getMilliamps()); #endif #if AXIS_IS_TMC(Z) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.getMilliamps()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.getMilliamps()); #endif SERIAL_EOL(); #endif @@ -224,71 +224,71 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { say_M906(forReplay); SERIAL_ECHOPGM(" I1"); #if AXIS_IS_TMC(X2) - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.getMilliamps()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.getMilliamps()); #endif #if AXIS_IS_TMC(Y2) - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.getMilliamps()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.getMilliamps()); #endif #if AXIS_IS_TMC(Z2) - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.getMilliamps()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.getMilliamps()); #endif SERIAL_EOL(); #endif #if AXIS_IS_TMC(Z3) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps()); + SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.getMilliamps()); #endif #if AXIS_IS_TMC(Z4) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); + SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.getMilliamps()); #endif #if AXIS_IS_TMC(I) say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); + SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.getMilliamps()); #endif #if AXIS_IS_TMC(J) say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); + SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.getMilliamps()); #endif #if AXIS_IS_TMC(K) say_M906(forReplay); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); + SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.getMilliamps()); #endif #if AXIS_IS_TMC(E0) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); + SERIAL_ECHOLNPGM(" T0 E", stepperE0.getMilliamps()); #endif #if AXIS_IS_TMC(E1) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T1 E", stepperE1.getMilliamps()); + SERIAL_ECHOLNPGM(" T1 E", stepperE1.getMilliamps()); #endif #if AXIS_IS_TMC(E2) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T2 E", stepperE2.getMilliamps()); + SERIAL_ECHOLNPGM(" T2 E", stepperE2.getMilliamps()); #endif #if AXIS_IS_TMC(E3) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T3 E", stepperE3.getMilliamps()); + SERIAL_ECHOLNPGM(" T3 E", stepperE3.getMilliamps()); #endif #if AXIS_IS_TMC(E4) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T4 E", stepperE4.getMilliamps()); + SERIAL_ECHOLNPGM(" T4 E", stepperE4.getMilliamps()); #endif #if AXIS_IS_TMC(E5) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T5 E", stepperE5.getMilliamps()); + SERIAL_ECHOLNPGM(" T5 E", stepperE5.getMilliamps()); #endif #if AXIS_IS_TMC(E6) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T6 E", stepperE6.getMilliamps()); + SERIAL_ECHOLNPGM(" T6 E", stepperE6.getMilliamps()); #endif #if AXIS_IS_TMC(E7) say_M906(forReplay); - SERIAL_ECHOLNPAIR(" T7 E", stepperE7.getMilliamps()); + SERIAL_ECHOLNPGM(" T7 E", stepperE7.getMilliamps()); #endif SERIAL_EOL(); } diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index d711865480..58702c603f 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -321,13 +321,13 @@ #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP say_M913(forReplay); #if X_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX.get_pwm_thrs()); #endif #if Y_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.get_pwm_thrs()); #endif #if Z_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.get_pwm_thrs()); #endif SERIAL_EOL(); #endif @@ -336,71 +336,71 @@ say_M913(forReplay); SERIAL_ECHOPGM(" I1"); #if X2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.get_pwm_thrs()); #endif #if Y2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.get_pwm_thrs()); #endif #if Z2_HAS_STEALTHCHOP - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); #endif SERIAL_EOL(); #endif #if Z3_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.get_pwm_thrs()); #endif #if Z4_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.get_pwm_thrs()); #endif #if I_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); + SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.get_pwm_thrs()); #endif #if J_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); + SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.get_pwm_thrs()); #endif #if K_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); + SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.get_pwm_thrs()); #endif #if E0_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T0 E", stepperE0.get_pwm_thrs()); #endif #if E1_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T1 E", stepperE1.get_pwm_thrs()); #endif #if E2_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T2 E", stepperE2.get_pwm_thrs()); #endif #if E3_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T3 E", stepperE3.get_pwm_thrs()); #endif #if E4_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T4 E", stepperE4.get_pwm_thrs()); #endif #if E5_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T5 E", stepperE5.get_pwm_thrs()); #endif #if E6_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T6 E", stepperE6.get_pwm_thrs()); #endif #if E7_HAS_STEALTHCHOP say_M913(forReplay); - SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); + SERIAL_ECHOLNPGM(" T7 E", stepperE7.get_pwm_thrs()); #endif SERIAL_EOL(); } @@ -522,13 +522,13 @@ #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS say_M914(forReplay); #if X_SENSORLESS - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.homing_threshold()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX.homing_threshold()); #endif #if Y_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.homing_threshold()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.homing_threshold()); #endif #if Z_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.homing_threshold()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.homing_threshold()); #endif SERIAL_EOL(); #endif @@ -537,38 +537,38 @@ say_M914(forReplay); SERIAL_ECHOPGM(" I1"); #if X2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.homing_threshold()); + SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.homing_threshold()); #endif #if Y2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.homing_threshold()); + SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.homing_threshold()); #endif #if Z2_SENSORLESS - SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.homing_threshold()); + SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.homing_threshold()); #endif SERIAL_EOL(); #endif #if Z3_SENSORLESS say_M914(forReplay); - SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold()); + SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.homing_threshold()); #endif #if Z4_SENSORLESS say_M914(forReplay); - SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); + SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.homing_threshold()); #endif #if I_SENSORLESS say_M914(forReplay); - SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); + SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.homing_threshold()); #endif #if J_SENSORLESS say_M914(forReplay); - SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); + SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.homing_threshold()); #endif #if K_SENSORLESS say_M914(forReplay); - SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); + SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.homing_threshold()); #endif } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 4c03fd9f85..477d43ed63 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -130,7 +130,7 @@ int8_t GcodeSuite::get_target_extruder_from_command() { if (e < EXTRUDERS) return e; SERIAL_ECHO_START(); SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum); - SERIAL_ECHOLNPAIR(" " STR_INVALID_EXTRUDER " ", e); + SERIAL_ECHOLNPGM(" " STR_INVALID_EXTRUDER " ", e); return -1; } return active_extruder; @@ -149,7 +149,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { if (e == -1) SERIAL_ECHOLNPGM(" " STR_E_STEPPER_NOT_SPECIFIED); else - SERIAL_ECHOLNPAIR(" " STR_INVALID_E_STEPPER " ", e); + SERIAL_ECHOLNPGM(" " STR_INVALID_E_STEPPER " ", e); return -1; } @@ -1082,7 +1082,7 @@ void GcodeSuite::process_next_command() { SERIAL_ECHO_START(); SERIAL_ECHOLN(command.buffer); #if ENABLED(M100_FREE_MEMORY_DUMPER) - SERIAL_ECHOPAIR("slot:", queue.ring_buffer.index_r); + SERIAL_ECHOPGM("slot:", queue.ring_buffer.index_r); M100_dump_routine(PSTR(" Command Queue:"), (const char*)&queue.ring_buffer, sizeof(queue.ring_buffer)); #endif } diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index b317a17815..3baff46836 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -179,7 +179,7 @@ void GcodeSuite::D(const int16_t dcode) { break; case 7: // D7 dump the current serial port type (hence configuration) - SERIAL_ECHOLNPAIR("Current serial configuration RX_BS:", RX_BUFFER_SIZE, ", TX_BS:", TX_BUFFER_SIZE); + SERIAL_ECHOLNPGM("Current serial configuration RX_BS:", RX_BUFFER_SIZE, ", TX_BS:", TX_BUFFER_SIZE); SERIAL_ECHOLN(gtn(&SERIAL_IMPL)); break; @@ -202,7 +202,7 @@ void GcodeSuite::D(const int16_t dcode) { case 101: { // D101 Test SD Write card.openFileWrite("test.gco"); if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open test.gco to write."); + SERIAL_ECHOLNPGM("Failed to open test.gco to write."); return; } __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; @@ -224,7 +224,7 @@ void GcodeSuite::D(const int16_t dcode) { char testfile[] = "test.gco"; card.openFileRead(testfile); if (!card.isFileOpen()) { - SERIAL_ECHOLNPAIR("Failed to open test.gco to read."); + SERIAL_ECHOLNPGM("Failed to open test.gco to read."); return; } __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512]; diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index a5a9f70a8b..db2404a28d 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/Marlin/src/gcode/geometry/G53-G59.cpp @@ -69,7 +69,7 @@ void GcodeSuite::G53() { process_parsed_command(); // ...process the chained command select_coordinate_system(old_system); #ifdef DEBUG_M53 - SERIAL_ECHOLNPAIR("Go back to workspace ", old_system); + SERIAL_ECHOLNPGM("Go back to workspace ", old_system); report_current_position(); #endif } @@ -87,7 +87,7 @@ void GcodeSuite::G53() { void G54_59(uint8_t subcode=0) { const int8_t _space = parser.codenum - 54 + subcode; if (gcode.select_coordinate_system(_space)) { - SERIAL_ECHOLNPAIR("Select workspace ", _space); + SERIAL_ECHOLNPGM("Select workspace ", _space); report_current_position(); } } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index ce142dacdf..416b3f7634 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -54,7 +54,7 @@ void GcodeSuite::M206() { void GcodeSuite::M206_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_HOME_OFFSET)); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( #if IS_CARTESIAN LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 7d69033319..cdb9efb71b 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -218,7 +218,7 @@ void GcodeSuite::M114() { } #if HAS_EXTRUDERS if (parser.seen_test('E')) { - SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); + SERIAL_ECHOLNPGM("Count E:", stepper.position(E_AXIS)); return; } #endif diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index e4f412406f..1c106977bf 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -175,7 +175,7 @@ void GcodeSuite::M115() { apply_motion_limits(cmax); const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(), wmin = cmin.asLogical(), wmax = cmax.asLogical(); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "area:{" "full:{" "min:{x:", lmin.x, ",y:", lmin.y, ",z:", lmin.z, "}," diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 7a0b8e3ab0..cec8df7542 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -36,7 +36,7 @@ static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8 SERIAL_ECHOPGM("Config:"); if (pref) SERIAL_ECHOPGM_P(pref); if (ind >= 0) { SERIAL_ECHO(ind); SERIAL_CHAR(':'); } - SERIAL_ECHOPAIR_P(name, AS_CHAR(':')); + SERIAL_ECHOPGM_P(name, AS_CHAR(':')); } static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr, const int8_t ind=-1) { config_prefix(name, pref, ind); diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index cbd752d245..77fd425763 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -64,7 +64,7 @@ void GcodeSuite::M145_report(const bool forReplay/*=true*/) { report_heading(forReplay, PSTR(STR_MATERIAL_HEATUP)); LOOP_L_N(i, PREHEAT_COUNT) { report_echo_start(forReplay); - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR(" M145 S"), i #if HAS_HOTEND , PSTR(" H"), parser.to_temp_units(ui.material_preset[i].hotend_temp) diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index 2b7e3dc994..618e3d5d6c 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M250() { void GcodeSuite::M250_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_LCD_CONTRAST)); - SERIAL_ECHOLNPAIR(" M250 C", ui.contrast); + SERIAL_ECHOLNPGM(" M250 C", ui.contrast); } #endif // HAS_LCD_CONTRAST diff --git a/Marlin/src/gcode/lcd/M256.cpp b/Marlin/src/gcode/lcd/M256.cpp index ff7c59fc9a..ee187cc2e1 100644 --- a/Marlin/src/gcode/lcd/M256.cpp +++ b/Marlin/src/gcode/lcd/M256.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M256() { void GcodeSuite::M256_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_LCD_BRIGHTNESS)); - SERIAL_ECHOLNPAIR(" M256 B", ui.brightness); + SERIAL_ECHOLNPGM(" M256 B", ui.brightness); } #endif // HAS_LCD_BRIGHTNESS diff --git a/Marlin/src/gcode/lcd/M414.cpp b/Marlin/src/gcode/lcd/M414.cpp index 26ecea2083..0eac980e0f 100644 --- a/Marlin/src/gcode/lcd/M414.cpp +++ b/Marlin/src/gcode/lcd/M414.cpp @@ -45,7 +45,7 @@ void GcodeSuite::M414() { void GcodeSuite::M414_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_UI_LANGUAGE)); - SERIAL_ECHOLNPAIR(" M414 S", ui.language); + SERIAL_ECHOLNPGM(" M414 S", ui.language); } #endif // HAS_MULTI_LANGUAGE diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 2b57a6b99a..747ddd64de 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -91,12 +91,12 @@ void GcodeSuite::M290() { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - SERIAL_ECHOLNPAIR(STR_PROBE_OFFSET " " STR_Z, probe.offset.z); + SERIAL_ECHOLNPGM(STR_PROBE_OFFSET " " STR_Z, probe.offset.z); #endif #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) { - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( PSTR("Hotend "), active_extruder #if ENABLED(BABYSTEP_XY) , PSTR("Offset X"), hotend_offset[active_extruder].x @@ -111,12 +111,12 @@ void GcodeSuite::M290() { #endif #if ENABLED(MESH_BED_LEVELING) - SERIAL_ECHOLNPAIR("MBL Adjust Z", mbl.z_offset); + SERIAL_ECHOLNPGM("MBL Adjust Z", mbl.z_offset); #endif #if ENABLED(BABYSTEP_DISPLAY_TOTAL) { - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( #if ENABLED(BABYSTEP_XY) PSTR("Babystep X"), babystep.axis_total[X_AXIS] , SP_Y_STR, babystep.axis_total[Y_AXIS] diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index e4e2973449..4d4fdae0d6 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -333,7 +333,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(DEBUG_GCODE_PARSER) if (debug) { - SERIAL_ECHOPAIR("Got param ", AS_CHAR(param), " at index ", p - command_ptr - 1); + SERIAL_ECHOPGM("Got param ", AS_CHAR(param), " at index ", p - command_ptr - 1); if (has_val) SERIAL_ECHOPGM(" (has_val)"); } #endif @@ -341,7 +341,7 @@ void GCodeParser::parse(char *p) { if (!has_val && !string_arg) { // No value? First time, keep as string_arg string_arg = p - 1; #if ENABLED(DEBUG_GCODE_PARSER) - if (debug) SERIAL_ECHOPAIR(" string_arg: ", hex_address((void*)string_arg)); // DEBUG + if (debug) SERIAL_ECHOPGM(" string_arg: ", hex_address((void*)string_arg)); // DEBUG #endif } @@ -352,7 +352,7 @@ void GCodeParser::parse(char *p) { else if (!string_arg) { // Not A-Z? First time, keep as the string_arg string_arg = p - 1; #if ENABLED(DEBUG_GCODE_PARSER) - if (debug) SERIAL_ECHOPAIR(" string_arg: ", hex_address((void*)string_arg)); // DEBUG + if (debug) SERIAL_ECHOPGM(" string_arg: ", hex_address((void*)string_arg)); // DEBUG #endif } @@ -390,7 +390,7 @@ void GCodeParser::unknown_command_warning() { #if ENABLED(DEBUG_GCODE_PARSER) void GCodeParser::debug() { - SERIAL_ECHOPAIR("Command: ", command_ptr, " (", command_letter); + SERIAL_ECHOPGM("Command: ", command_ptr, " (", command_letter); SERIAL_ECHO(codenum); SERIAL_ECHOLNPGM(")"); #if ENABLED(FASTER_GCODE_PARSER) @@ -398,18 +398,18 @@ void GCodeParser::unknown_command_warning() { for (char c = 'A'; c <= 'Z'; ++c) if (seen(c)) SERIAL_CHAR(c, ' '); SERIAL_CHAR('}'); #else - SERIAL_ECHOPAIR(" args: { ", command_args, " }"); + SERIAL_ECHOPGM(" args: { ", command_args, " }"); #endif if (string_arg) { - SERIAL_ECHOPAIR(" string: \"", string_arg); + SERIAL_ECHOPGM(" string: \"", string_arg); SERIAL_CHAR('"'); } SERIAL_ECHOLNPGM("\n"); for (char c = 'A'; c <= 'Z'; ++c) { if (seen(c)) { - SERIAL_ECHOPAIR("Code '", c); SERIAL_ECHOPGM("':"); + SERIAL_ECHOPGM("Code '", c); SERIAL_ECHOPGM("':"); if (has_value()) { - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "\n float: ", value_float(), "\n long: ", value_long(), "\n ulong: ", value_ulong(), diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index f8fb890695..ad550765ec 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -133,9 +133,9 @@ public: param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0 #if ENABLED(DEBUG_GCODE_PARSER) if (codenum == 800) { - SERIAL_ECHOPAIR("Set bit ", ind, " of codebits (", hex_address((void*)(codebits >> 16))); + SERIAL_ECHOPGM("Set bit ", ind, " of codebits (", hex_address((void*)(codebits >> 16))); print_hex_word((uint16_t)(codebits & 0xFFFF)); - SERIAL_ECHOLNPAIR(") | param = ", param[ind]); + SERIAL_ECHOLNPGM(") | param = ", param[ind]); } #endif } diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 4347f55aa8..f4152c76e9 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -53,7 +53,7 @@ void GcodeSuite::G30() { const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; const float measured_z = probe.probe_at_point(pos, raise_after, 1); if (!isnan(measured_z)) - SERIAL_ECHOLNPAIR("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); + SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); restore_feedrate_and_scaling(); diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index e7261b5a14..5518117946 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -47,11 +47,11 @@ void GcodeSuite::M851() { if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) offs.x = x; else { - SERIAL_ECHOLNPAIR("?X out of range (-", X_BED_SIZE, " to ", X_BED_SIZE, ")"); + SERIAL_ECHOLNPGM("?X out of range (-", X_BED_SIZE, " to ", X_BED_SIZE, ")"); ok = false; } #else - if (x) SERIAL_ECHOLNPAIR("?X must be 0 (NOZZLE_AS_PROBE)."); // ...but let 'ok' stay true + if (x) SERIAL_ECHOLNPGM("?X must be 0 (NOZZLE_AS_PROBE)."); // ...but let 'ok' stay true #endif } @@ -61,11 +61,11 @@ void GcodeSuite::M851() { if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) offs.y = y; else { - SERIAL_ECHOLNPAIR("?Y out of range (-", Y_BED_SIZE, " to ", Y_BED_SIZE, ")"); + SERIAL_ECHOLNPGM("?Y out of range (-", Y_BED_SIZE, " to ", Y_BED_SIZE, ")"); ok = false; } #else - if (y) SERIAL_ECHOLNPAIR("?Y must be 0 (NOZZLE_AS_PROBE)."); // ...but let 'ok' stay true + if (y) SERIAL_ECHOLNPGM("?Y must be 0 (NOZZLE_AS_PROBE)."); // ...but let 'ok' stay true #endif } @@ -74,7 +74,7 @@ void GcodeSuite::M851() { if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) offs.z = z; else { - SERIAL_ECHOLNPAIR("?Z out of range (", Z_PROBE_OFFSET_RANGE_MIN, " to ", Z_PROBE_OFFSET_RANGE_MAX, ")"); + SERIAL_ECHOLNPGM("?Z out of range (", Z_PROBE_OFFSET_RANGE_MIN, " to ", Z_PROBE_OFFSET_RANGE_MAX, ")"); ok = false; } } @@ -85,7 +85,7 @@ void GcodeSuite::M851() { void GcodeSuite::M851_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_Z_PROBE_OFFSET)); - SERIAL_ECHOPAIR_P( + SERIAL_ECHOPGM_P( #if HAS_PROBE_XY_OFFSET PSTR(" M851 X"), LINEAR_UNIT(probe.offset_xy.x), SP_Y_STR, LINEAR_UNIT(probe.offset_xy.y), diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index f461fc2b07..c6a9cfbe20 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -32,13 +32,13 @@ mpe_settings_t mpe_settings; inline void mpe_settings_report() { SERIAL_ECHO_MSG("Magnetic Parking Extruder"); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("L: Left parking :", mpe_settings.parking_xpos[0]); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("R: Right parking :", mpe_settings.parking_xpos[1]); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("I: Grab Offset :", mpe_settings.grab_distance); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("J: Normal speed :", long(MMS_TO_MMM(mpe_settings.slow_feedrate))); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("H: High speed :", long(MMS_TO_MMM(mpe_settings.fast_feedrate))); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("D: Distance trav.:", mpe_settings.travel_distance); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("C: Compenstion :", mpe_settings.compensation_factor); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("L: Left parking :", mpe_settings.parking_xpos[0]); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("R: Right parking :", mpe_settings.parking_xpos[1]); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("I: Grab Offset :", mpe_settings.grab_distance); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("J: Normal speed :", long(MMS_TO_MMM(mpe_settings.slow_feedrate))); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("H: High speed :", long(MMS_TO_MMM(mpe_settings.fast_feedrate))); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("D: Distance trav.:", mpe_settings.travel_distance); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("C: Compenstion :", mpe_settings.compensation_factor); } void mpe_settings_init() { diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 37acc8d58c..07d7c536a6 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -127,7 +127,7 @@ bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ * Return true if the command was consumed */ bool GCodeQueue::enqueue_one(const char *cmd) { - //SERIAL_ECHOLNPAIR("enqueue_one(\"", cmd, "\")"); + //SERIAL_ECHOLNPGM("enqueue_one(\"", cmd, "\")"); if (*cmd == 0 || ISEOL(*cmd)) return true; @@ -260,7 +260,7 @@ void GCodeQueue::RingBuffer::ok_to_send() { while (NUMERIC_SIGNED(*p)) SERIAL_CHAR(*p++); } - SERIAL_ECHOPAIR_P(SP_P_STR, planner.moves_free(), + SERIAL_ECHOPGM_P(SP_P_STR, planner.moves_free(), SP_B_STR, BUFSIZE - length); #endif SERIAL_EOL(); @@ -276,7 +276,7 @@ void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) { PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command #endif SERIAL_FLUSH(); - SERIAL_ECHOLNPAIR(STR_RESEND, serial_state[serial_ind.index].last_N + 1); + SERIAL_ECHOLNPGM(STR_RESEND, serial_state[serial_ind.index].last_N + 1); SERIAL_ECHOLNPGM(STR_OK); } @@ -306,7 +306,7 @@ inline int read_serial(const serial_index_t index) { return SERIAL_IMPL.read(ind void GCodeQueue::gcode_line_error(PGM_P const err, const serial_index_t serial_ind) { PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command SERIAL_ERROR_START(); - SERIAL_ECHOLNPAIR_P(err, serial_state[serial_ind.index].last_N); + SERIAL_ECHOLNPGM_P(err, serial_state[serial_ind.index].last_N); while (read_serial(serial_ind) != -1) { /* nada */ } // Clear out the RX buffer. Why don't use flush here ? flush_and_request_resend(serial_ind); serial_state[serial_ind.index].count = 0; @@ -659,10 +659,10 @@ void GCodeQueue::advance() { #if !defined(__AVR__) || !defined(USBCON) #if ENABLED(SERIAL_STATS_DROPPED_RX) - SERIAL_ECHOLNPAIR("Dropped bytes: ", MYSERIAL1.dropped()); + SERIAL_ECHOLNPGM("Dropped bytes: ", MYSERIAL1.dropped()); #endif #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - SERIAL_ECHOLNPAIR("Max RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); + SERIAL_ECHOLNPGM("Max RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif #endif @@ -693,7 +693,7 @@ void GCodeQueue::advance() { #if ENABLED(BUFFER_MONITORING) void GCodeQueue::report_buffer_statistics() { - SERIAL_ECHOLNPAIR("D576" + SERIAL_ECHOLNPGM("D576" " P:", planner.moves_free(), " ", -queue.planner_buffer_underruns, " (", queue.max_planner_buffer_empty_duration, ")" " B:", BUFSIZE - ring_buffer.length, " ", -queue.command_buffer_underruns, " (", queue.max_command_buffer_empty_duration, ")" ); diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index eeca59088f..20b3781ead 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M149() { void GcodeSuite::M149_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_TEMPERATURE_UNITS)); - SERIAL_ECHOPAIR(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); + SERIAL_ECHOPGM(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); SERIAL_ECHOLNPGM_P(parser.temp_units_name()); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index d14d6f10dd..76d77e4cab 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1923,7 +1923,7 @@ void HMI_SDCardUpdate() { if (HMI_flag.home_flag) return; if (DWIN_lcd_sd_status != card.isMounted()) { DWIN_lcd_sd_status = card.isMounted(); - //SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); + //SERIAL_ECHOLNPGM("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); if (DWIN_lcd_sd_status) { if (checkkey == SelectFile) Redraw_SD_List(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index e446733d9b..edcf199182 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -969,7 +969,7 @@ void HMI_SDCardUpdate() { if (HMI_flag.home_flag) return; if (DWIN_lcd_sd_status != card.isMounted()) { DWIN_lcd_sd_status = card.isMounted(); - //SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); + //SERIAL_ECHOLNPGM("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); if (DWIN_lcd_sd_status) { if (checkkey == SelectFile) Redraw_SD_List(); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp index 58adf9761f..1339c39f3f 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -86,7 +86,7 @@ void FileNavigator::refresh() { filelist.refresh(); } void FileNavigator::changeDIR(const char *folder) { if (currentfolderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth - DEBUG_ECHOLNPAIR("FD:" , folderdepth, " FP:",currentindex, " currentfolder:", currentfoldername, " enter:", folder); + DEBUG_ECHOLNPGM("FD:" , folderdepth, " FP:",currentindex, " currentfolder:", currentfoldername, " enter:", folder); currentfolderindex[currentfolderdepth] = currentindex; strcat(currentfoldername, folder); strcat(currentfoldername, "/"); @@ -96,7 +96,7 @@ void FileNavigator::changeDIR(const char *folder) { } void FileNavigator::upDIR() { - DEBUG_ECHOLNPAIR("upDIR() from D:", currentfolderdepth, " N:", currentfoldername); + DEBUG_ECHOLNPGM("upDIR() from D:", currentfolderdepth, " N:", currentfoldername); if (!filelist.isAtRootDir()) { filelist.upDir(); currentfolderdepth--; @@ -117,7 +117,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { if (skip == 0) return; while (skip > 0) { if (filelist.seek(currentindex)) { - DEBUG_ECHOLNPAIR("CI:", currentindex, " FD:", currentfolderdepth, " N:", skip, " ", filelist.longFilename()); + DEBUG_ECHOLNPGM("CI:", currentindex, " FD:", currentfolderdepth, " N:", skip, " ", filelist.longFilename()); if (!filelist.isDir()) { skip--; currentindex++; @@ -151,7 +151,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { } lastpanelindex = index; - DEBUG_ECHOLNPAIR("index=", index, " currentindex=", currentindex); + DEBUG_ECHOLNPGM("index=", index, " currentindex=", currentindex); if (currentindex == 0 && currentfolderdepth > 0) { // Add a link to go up a folder // The new panel ignores entries that don't end in .GCO or .gcode so add and pad them. @@ -169,7 +169,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { for (uint16_t seek = currentindex; seek < currentindex + filesneeded; seek++) { if (filelist.seek(seek)) { sendFile(paneltype); - DEBUG_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'"); + DEBUG_ECHOLNPGM("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'"); } } } @@ -212,7 +212,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { #else // Flat file list void FileNavigator::getFiles(uint16_t index, panel_type_t paneltype, uint8_t filesneeded) { - DEBUG_ECHOLNPAIR("getFiles() I:", index," L:", lastpanelindex); + DEBUG_ECHOLNPGM("getFiles() I:", index," L:", lastpanelindex); // if we're searching backwards, jump back to start and search forward if (index < lastpanelindex) { reset(); @@ -248,7 +248,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { TFTSer.println(filelist.shortFilename()); if (currentfolderdepth > 0) TFTSer.print(currentfoldername); TFTSer.println(filelist.longFilename()); - DEBUG_ECHOLNPAIR("/", currentfoldername, "", filelist.shortFilename(), " ", filelist.longFilename()); + DEBUG_ECHOLNPGM("/", currentfoldername, "", filelist.shortFilename(), " ", filelist.longFilename()); } #endif // Flat file list diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 0f6f8abe38..5cd0922800 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -107,12 +107,12 @@ namespace ExtUI { void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated - //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); + //SERIAL_ECHOLNPGM("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); } void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { // Called to indicate a special condition - //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " state:", state); + //SERIAL_ECHOLNPGM("onMeshUpdate() x:", xpos, " y:", ypos, " state:", state); } #endif diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 0ecb138bd5..42364f2890 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -104,7 +104,7 @@ void ChironTFT::Startup() { PlayTune(BEEPER_PIN, TERN(AC_DEFAULT_STARTUP_TUNE, Anycubic_PowerOn, GB_PowerOn), 1); #if ACDEBUGLEVEL - SERIAL_ECHOLNPAIR("AC Debug Level ", ACDEBUGLEVEL); + SERIAL_ECHOLNPGM("AC Debug Level ", ACDEBUGLEVEL); #endif SendtoTFTLN(AC_msg_ready); } @@ -128,13 +128,13 @@ void ChironTFT::IdleLoop() { void ChironTFT::PrinterKilled(PGM_P error,PGM_P component) { SendtoTFTLN(AC_msg_kill_lcd); #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); + SERIAL_ECHOLNPGM("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); #endif } void ChironTFT::MediaEvent(media_event_t event) { #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("ProcessMediaStatus() ", event); + SERIAL_ECHOLNPGM("ProcessMediaStatus() ", event); #endif switch (event) { case AC_media_inserted: @@ -154,8 +154,8 @@ void ChironTFT::MediaEvent(media_event_t event) { void ChironTFT::TimerEvent(timer_event_t event) { #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("TimerEvent() ", event); - SERIAL_ECHOLNPAIR("Printer State: ", printer_state); + SERIAL_ECHOLNPGM("TimerEvent() ", event); + SERIAL_ECHOLNPGM("Printer State: ", printer_state); #endif switch (event) { @@ -184,7 +184,7 @@ void ChironTFT::TimerEvent(timer_event_t event) { void ChironTFT::FilamentRunout() { #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("FilamentRunout() printer_state ", printer_state); + SERIAL_ECHOLNPGM("FilamentRunout() printer_state ", printer_state); #endif // 1 Signal filament out last_error = AC_error_filament_runout; @@ -195,7 +195,7 @@ void ChironTFT::FilamentRunout() { void ChironTFT::ConfirmationRequest(const char * const msg) { // M108 continue #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); + SERIAL_ECHOLNPGM("ConfirmationRequest() ", msg, " printer_state:", printer_state); #endif switch (printer_state) { case AC_printer_pausing: { @@ -232,8 +232,8 @@ void ChironTFT::ConfirmationRequest(const char * const msg) { void ChironTFT::StatusChange(const char * const msg) { #if ACDEBUG(AC_MARLIN) - SERIAL_ECHOLNPAIR("StatusChange() ", msg); - SERIAL_ECHOLNPAIR("printer_state:", printer_state); + SERIAL_ECHOLNPGM("StatusChange() ", msg); + SERIAL_ECHOLNPGM("printer_state:", printer_state); #endif bool msg_matched = false; // The only way to get printer status is to parse messages @@ -348,7 +348,7 @@ bool ChironTFT::ReadTFTCommand() { if (command_ready || command_len == MAX_CMND_LEN) { panel_command[command_len] = '\0'; #if ACDEBUG(AC_ALL) - SERIAL_ECHOLNPAIR("len(",command_len,") < ", panel_command); + SERIAL_ECHOLNPGM("len(",command_len,") < ", panel_command); #endif command_ready = true; } @@ -360,13 +360,13 @@ int8_t ChironTFT::FindToken(char c) { do { if (panel_command[pos] == c) { #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Tpos:", pos, " ", c); + SERIAL_ECHOLNPGM("Tpos:", pos, " ", c); #endif return pos; } } while(++pos < command_len); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Not found: ", c); + SERIAL_ECHOLNPGM("Not found: ", c); #endif return -1; } @@ -381,7 +381,7 @@ void ChironTFT::CheckHeaters() { if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { SendtoTFTLN(AC_msg_nozzle_temp_abnormal); last_error = AC_error_abnormal_temp_t0; - SERIAL_ECHOLNPAIR("Extruder temp abnormal! : ", temp); + SERIAL_ECHOLNPGM("Extruder temp abnormal! : ", temp); break; } delay_ms(500); @@ -396,7 +396,7 @@ void ChironTFT::CheckHeaters() { if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { SendtoTFTLN(AC_msg_nozzle_temp_abnormal); last_error = AC_error_abnormal_temp_bed; - SERIAL_ECHOLNPAIR("Bed temp abnormal! : ", temp); + SERIAL_ECHOLNPGM("Bed temp abnormal! : ", temp); break; } delay_ms(500); @@ -423,7 +423,7 @@ void ChironTFT::CheckHeaters() { void ChironTFT::SendFileList(int8_t startindex) { // Respond to panel request for 4 files starting at index #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("## SendFileList ## ", startindex); + SERIAL_ECHOLNPGM("## SendFileList ## ", startindex); #endif SendtoTFTLN(PSTR("FN ")); filenavigator.getFiles(startindex, panel_type, 4); @@ -440,7 +440,7 @@ void ChironTFT::SelectFile() { selectedfile[command_len - 5] = '\0'; } #if ACDEBUG(AC_FILE) - SERIAL_ECHOLNPAIR(" Selected File: ",selectedfile); + SERIAL_ECHOLNPGM(" Selected File: ",selectedfile); #endif switch (selectedfile[0]) { case '/': // Valid file selected @@ -561,7 +561,7 @@ void ChironTFT::PanelInfo(uint8_t req) { TFTSer.print(ui8tostr2(time % 60)); SendtoTFT(PSTR(" M")); #if ACDEBUG(AC_ALL) - SERIAL_ECHOLNPAIR("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); + SERIAL_ECHOLNPGM("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); #endif } break; @@ -702,7 +702,7 @@ void ChironTFT::PanelAction(uint8_t req) { char MoveCmnd[30]; sprintf_P(MoveCmnd, PSTR("G91\nG0%s\nG90"), panel_command + 3); #if ACDEBUG(AC_ACTION) - SERIAL_ECHOLNPAIR("Move: ", MoveCmnd); + SERIAL_ECHOLNPGM("Move: ", MoveCmnd); #endif setSoftEndstopState(true); // enable endstops injectCommands(MoveCmnd); @@ -781,7 +781,7 @@ void ChironTFT::PanelProcess(uint8_t req) { if (isPositionKnown()) { #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Moving to mesh point at x: ", pos.x, " y: ", pos.y, " z: ", pos_z); + SERIAL_ECHOLNPGM("Moving to mesh point at x: ", pos.x, " y: ", pos.y, " z: ", pos_z); #endif // Go up before moving setAxisPosition_mm(3.0,Z); @@ -790,7 +790,7 @@ void ChironTFT::PanelProcess(uint8_t req) { setAxisPosition_mm(20 + (93 * pos.y), Y); setAxisPosition_mm(0.0, Z); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Current Z: ", getAxisPosition_mm(Z)); + SERIAL_ECHOLNPGM("Current Z: ", getAxisPosition_mm(Z)); #endif } } @@ -858,17 +858,17 @@ void ChironTFT::PanelProcess(uint8_t req) { // From the leveling panel use the all points UI to adjust the print pos. if (isPrinting()) { #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change Zoffset from:", live_Zoffset, " to ", live_Zoffset + Zshift); + SERIAL_ECHOLNPGM("Change Zoffset from:", live_Zoffset, " to ", live_Zoffset + Zshift); #endif if (isAxisPositionKnown(Z)) { #if ACDEBUG(AC_INFO) const float currZpos = getAxisPosition_mm(Z); - SERIAL_ECHOLNPAIR("Nudge Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + SERIAL_ECHOLNPGM("Nudge Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); #endif // Use babystepping to adjust the head position int16_t steps = mmToWholeSteps(constrain(Zshift,-0.05,0.05), Z); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Steps to move Z: ", steps); + SERIAL_ECHOLNPGM("Steps to move Z: ", steps); #endif babystepAxis_steps(steps, Z); live_Zoffset += Zshift; @@ -882,12 +882,12 @@ void ChironTFT::PanelProcess(uint8_t req) { const float currval = getMeshPoint(pos); setMeshPoint(pos, constrain(currval + Zshift, AC_LOWEST_MESHPOINT_VAL, 2)); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change mesh point X", x," Y",y ," from ", currval, " to ", getMeshPoint(pos) ); + SERIAL_ECHOLNPGM("Change mesh point X", x," Y",y ," from ", currval, " to ", getMeshPoint(pos) ); #endif } const float currZOffset = getZOffset_mm(); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change probe offset from ", currZOffset, " to ", currZOffset + Zshift); + SERIAL_ECHOLNPGM("Change probe offset from ", currZOffset, " to ", currZOffset + Zshift); #endif setZOffset_mm(currZOffset + Zshift); @@ -898,7 +898,7 @@ void ChironTFT::PanelProcess(uint8_t req) { // Move Z axis const float currZpos = getAxisPosition_mm(Z); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + SERIAL_ECHOLNPGM("Move Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); #endif setAxisPosition_mm(currZpos+constrain(Zshift,-0.05,0.05),Z); } @@ -930,8 +930,8 @@ void ChironTFT::PanelProcess(uint8_t req) { float currmesh = getMeshPoint(pos); float newval = atof(&panel_command[11])/100; #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Change mesh point x:", pos.x, " y:", pos.y); - SERIAL_ECHOLNPAIR("from ", currmesh, " to ", newval); + SERIAL_ECHOLNPGM("Change mesh point x:", pos.x, " y:", pos.y); + SERIAL_ECHOLNPGM("from ", currmesh, " to ", newval); #endif // Update Meshpoint setMeshPoint(pos,newval); @@ -942,7 +942,7 @@ void ChironTFT::PanelProcess(uint8_t req) { setSoftEndstopState(false); float currZpos = getAxisPosition_mm(Z); #if ACDEBUG(AC_INFO) - SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(newval - currmesh, -0.05, 0.05)); + SERIAL_ECHOLNPGM("Move Z pos from ", currZpos, " to ", currZpos + constrain(newval - currmesh, -0.05, 0.05)); #endif setAxisPosition_mm(currZpos + constrain(newval - currmesh, -0.05, 0.05), Z); } diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 3277ad4fb4..b739e83dc1 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -143,7 +143,7 @@ void AnycubicTFTClass::OnKillTFT() { void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) { #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPAIR("TFT Serial Debug: OnSDCardStateChange event triggered...", isInserted); + SERIAL_ECHOLNPGM("TFT Serial Debug: OnSDCardStateChange event triggered...", isInserted); #endif DoSDCardStateCheck(); } @@ -164,7 +164,7 @@ void AnycubicTFTClass::OnFilamentRunout() { void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) { #if ENABLED(ANYCUBIC_LCD_DEBUG) - SERIAL_ECHOLNPAIR("TFT Serial Debug: OnUserConfirmRequired triggered... ", msg); + SERIAL_ECHOLNPGM("TFT Serial Debug: OnUserConfirmRequired triggered... ", msg); #endif #if ENABLED(SDSUPPORT) @@ -557,7 +557,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { #if ENABLED(ANYCUBIC_LCD_DEBUG) if ((a_command > 7) && (a_command != 20)) // No debugging of status polls, please! - SERIAL_ECHOLNPAIR("TFT Serial Command: ", TFTcmdbuffer[TFTbufindw]); + SERIAL_ECHOLNPGM("TFT Serial Command: ", TFTcmdbuffer[TFTbufindw]); #endif switch (a_command) { diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 535bc96591..262dcea364 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -154,19 +154,19 @@ void DGUSDisplay::ProcessRx() { case DGUS_IDLE: // Waiting for the first header byte receivedbyte = LCD_SERIAL.read(); - //DEBUG_ECHOPAIR("< ",x); + //DEBUG_ECHOPGM("< ",x); if (DGUS_HEADER1 == receivedbyte) rx_datagram_state = DGUS_HEADER1_SEEN; break; case DGUS_HEADER1_SEEN: // Waiting for the second header byte receivedbyte = LCD_SERIAL.read(); - //DEBUG_ECHOPAIR(" ",x); + //DEBUG_ECHOPGM(" ",x); rx_datagram_state = (DGUS_HEADER2 == receivedbyte) ? DGUS_HEADER2_SEEN : DGUS_IDLE; break; case DGUS_HEADER2_SEEN: // Waiting for the length byte rx_datagram_len = LCD_SERIAL.read(); - DEBUG_ECHOPAIR(" (", rx_datagram_len, ") "); + DEBUG_ECHOPGM(" (", rx_datagram_len, ") "); // Telegram min len is 3 (command and one word of payload) rx_datagram_state = WITHIN(rx_datagram_len, 3, DGUS_RX_BUFFER_SIZE) ? DGUS_WAIT_TELEGRAM : DGUS_IDLE; @@ -178,14 +178,14 @@ void DGUSDisplay::ProcessRx() { Initialized = true; // We've talked to it, so we defined it as initialized. uint8_t command = LCD_SERIAL.read(); - DEBUG_ECHOPAIR("# ", command); + DEBUG_ECHOPGM("# ", command); uint8_t readlen = rx_datagram_len - 1; // command is part of len. unsigned char tmp[rx_datagram_len - 1]; unsigned char *ptmp = tmp; while (readlen--) { receivedbyte = LCD_SERIAL.read(); - DEBUG_ECHOPAIR(" ", receivedbyte); + DEBUG_ECHOPGM(" ", receivedbyte); *ptmp++ = receivedbyte; } DEBUG_ECHOPGM(" # "); @@ -206,7 +206,7 @@ void DGUSDisplay::ProcessRx() { if (command == DGUS_CMD_READVAR) { const uint16_t vp = tmp[0] << 8 | tmp[1]; //const uint8_t dlen = tmp[2] << 1; // Convert to Bytes. (Display works with words) - //DEBUG_ECHOPAIR(" vp=", vp, " dlen=", dlen); + //DEBUG_ECHOPGM(" vp=", vp, " dlen=", dlen); DGUS_VP_Variable ramcopy; if (populate_VPVar(vp, &ramcopy)) { if (ramcopy.set_by_display_handler) @@ -215,7 +215,7 @@ void DGUSDisplay::ProcessRx() { DEBUG_ECHOLNPGM(" VPVar found, no handler."); } else - DEBUG_ECHOLNPAIR(" VPVar not found:", vp); + DEBUG_ECHOLNPGM(" VPVar not found:", vp); rx_datagram_state = DGUS_IDLE; break; @@ -260,9 +260,9 @@ bool DGUSDisplay::no_reentrance = false; #define sw_barrier() asm volatile("": : :"memory"); bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy) { - // DEBUG_ECHOPAIR("populate_VPVar ", VP); + // DEBUG_ECHOPGM("populate_VPVar ", VP); const DGUS_VP_Variable *pvp = DGUSLCD_FindVPVar(VP); - // DEBUG_ECHOLNPAIR(" pvp ", (uint16_t )pvp); + // DEBUG_ECHOLNPGM(" pvp ", (uint16_t )pvp); if (!pvp) return false; memcpy_P(ramcopy, pvp, sizeof(DGUS_VP_Variable)); return true; diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 9e44cf1331..16576f7039 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -110,8 +110,8 @@ void DGUSScreenHandler::setstatusmessagePGM(PGM_P const msg) { // Send an 8 bit or 16 bit value to the display. void DGUSScreenHandler::DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { - //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + //DEBUG_ECHOPGM(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPGM(" data ", *(uint16_t *)var.memadr); if (var.size > 1) dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); else @@ -122,8 +122,8 @@ void DGUSScreenHandler::DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var) { // Send an uint8_t between 0 and 255 to the display, but scale to a percentage (0..100) void DGUSScreenHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { - //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + //DEBUG_ECHOPGM(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPGM(" data ", *(uint16_t *)var.memadr); uint16_t tmp = *(uint8_t *) var.memadr + 1; // +1 -> avoid rounding issues for the display. tmp = map(tmp, 0, 255, 0, 100); dgusdisplay.WriteVariable(var.VP, tmp); @@ -132,9 +132,9 @@ void DGUSScreenHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var) { // Send the current print progress to the display. void DGUSScreenHandler::DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var) { - //DEBUG_ECHOPAIR(" DGUSLCD_SendPrintProgressToDisplay ", var.VP); + //DEBUG_ECHOPGM(" DGUSLCD_SendPrintProgressToDisplay ", var.VP); uint16_t tmp = ExtUI::getProgress_percent(); - //DEBUG_ECHOLNPAIR(" data ", tmp); + //DEBUG_ECHOLNPGM(" data ", tmp); dgusdisplay.WriteVariable(var.VP, tmp); } @@ -151,9 +151,9 @@ void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { void DGUSScreenHandler::DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr) { if (var.memadr) { uint16_t value = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("FAN value get:", value); + DEBUG_ECHOLNPGM("FAN value get:", value); *(uint8_t*)var.memadr = map(constrain(value, 0, 100), 0, 100, 0, 255); - DEBUG_ECHOLNPAIR("FAN value change:", *(uint8_t*)var.memadr); + DEBUG_ECHOLNPGM("FAN value change:", *(uint8_t*)var.memadr); } } @@ -234,8 +234,8 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { void DGUSScreenHandler::DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { - DEBUG_ECHOPAIR(" DGUSLCD_SendFanStatusToDisplay ", var.VP); - DEBUG_ECHOLNPAIR(" data ", *(uint8_t *)var.memadr); + DEBUG_ECHOPGM(" DGUSLCD_SendFanStatusToDisplay ", var.VP); + DEBUG_ECHOLNPGM(" data ", *(uint8_t *)var.memadr); uint16_t data_to_send = 0; if (*(uint8_t *) var.memadr) data_to_send = 1; dgusdisplay.WriteVariable(var.VP, data_to_send); @@ -247,8 +247,8 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { // Send heater status value to the display. void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { - DEBUG_ECHOPAIR(" DGUSLCD_SendHeaterStatusToDisplay ", var.VP); - DEBUG_ECHOLNPAIR(" data ", *(int16_t *)var.memadr); + DEBUG_ECHOPGM(" DGUSLCD_SendHeaterStatusToDisplay ", var.VP); + DEBUG_ECHOLNPGM(" data ", *(int16_t *)var.memadr); uint16_t data_to_send = 0; if (*(int16_t *) var.memadr) data_to_send = 1; dgusdisplay.WriteVariable(var.VP, data_to_send); @@ -261,11 +261,11 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) // In FYSETC UI design there are 10 statuses to loop static uint16_t period = 0; static uint16_t index = 0; - //DEBUG_ECHOPAIR(" DGUSLCD_SendWaitingStatusToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", swap16(index)); + //DEBUG_ECHOPGM(" DGUSLCD_SendWaitingStatusToDisplay ", var.VP); + //DEBUG_ECHOLNPGM(" data ", swap16(index)); if (period++ > DGUS_UI_WAITING_STATUS_PERIOD) { dgusdisplay.WriteVariable(var.VP, index); - //DEBUG_ECHOLNPAIR(" data ", swap16(index)); + //DEBUG_ECHOLNPGM(" data ", swap16(index)); if (++index >= DGUS_UI_WAITING_STATUS) index = 0; period = 0; } @@ -307,7 +307,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) const int16_t scroll = (int16_t)swap16(*(uint16_t*)val_ptr); if (scroll) { top_file += scroll; - DEBUG_ECHOPAIR("new topfile calculated:", top_file); + DEBUG_ECHOPGM("new topfile calculated:", top_file); if (top_file < 0) { top_file = 0; DEBUG_ECHOLNPGM("Top of filelist reached"); @@ -317,7 +317,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) NOLESS(max_top, 0); NOMORE(top_file, max_top); } - DEBUG_ECHOPAIR("new topfile adjusted:", top_file); + DEBUG_ECHOPGM("new topfile adjusted:", top_file); } else if (!filelist.isAtRootDir()) { IF_DISABLED(DGUS_LCD_UI_MKS, filelist.upDir()); @@ -371,7 +371,7 @@ const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp) { ++ret; } while (1); - DEBUG_ECHOLNPAIR("FindVPVar NOT FOUND ", vp); + DEBUG_ECHOLNPGM("FindVPVar NOT FOUND ", vp); return nullptr; } @@ -476,7 +476,7 @@ void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_p const int16_t lock = swap16(*(uint16_t*)val_ptr); strcpy_P(buf, lock ? PSTR("M18") : PSTR("M17")); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); } @@ -499,7 +499,7 @@ void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ DEBUG_ECHOLNPGM("HandleStepPerMMChanged"); uint16_t value_raw = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); float value = (float)value_raw / 10; ExtUI::axis_t axis; switch (var.VP) { @@ -519,7 +519,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo DEBUG_ECHOLNPGM("HandleStepPerMMExtruderChanged"); uint16_t value_raw = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); float value = (float)value_raw / 10; ExtUI::extruder_t extruder; switch (var.VP) { @@ -696,7 +696,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr #endif void DGUSScreenHandler::UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup) { - DEBUG_ECHOLNPAIR("SetNewScreen: ", newscreen); + DEBUG_ECHOLNPGM("SetNewScreen: ", newscreen); if (!popup) { memmove(&past_screens[1], &past_screens[0], sizeof(past_screens) - 1); past_screens[0] = current_screen; @@ -707,18 +707,18 @@ void DGUSScreenHandler::UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup) { } void DGUSScreenHandler::PopToOldScreen() { - DEBUG_ECHOLNPAIR("PopToOldScreen s=", past_screens[0]); + DEBUG_ECHOLNPGM("PopToOldScreen s=", past_screens[0]); GotoScreen(past_screens[0], true); memmove(&past_screens[0], &past_screens[1], sizeof(past_screens) - 1); past_screens[sizeof(past_screens) - 1] = DGUSLCD_SCREEN_MAIN; } void DGUSScreenHandler::UpdateScreenVPData() { - DEBUG_ECHOPAIR(" UpdateScreenVPData Screen: ", current_screen); + DEBUG_ECHOPGM(" UpdateScreenVPData Screen: ", current_screen); const uint16_t *VPList = DGUSLCD_FindScreenVPMapList(current_screen); if (!VPList) { - DEBUG_ECHOLNPAIR(" NO SCREEN FOR: ", current_screen); + DEBUG_ECHOLNPGM(" NO SCREEN FOR: ", current_screen); ScreenComplete = true; return; // nothing to do, likely a bug or boring screen. } @@ -729,7 +729,7 @@ void DGUSScreenHandler::UpdateScreenVPData() { bool sent_one = false; do { uint16_t VP = pgm_read_word(VPList); - DEBUG_ECHOPAIR(" VP: ", VP); + DEBUG_ECHOPGM(" VP: ", VP); if (!VP) { update_ptr = 0; DEBUG_ECHOLNPGM(" UpdateScreenVPData done"); @@ -745,14 +745,14 @@ void DGUSScreenHandler::UpdateScreenVPData() { // Send the VP to the display, but try to avoid overrunning the Tx Buffer. // But send at least one VP, to avoid getting stalled. if (rcpy.send_to_display_handler && (!sent_one || expected_tx <= dgusdisplay.GetFreeTxBuffer())) { - //DEBUG_ECHOPAIR(" calling handler for ", rcpy.VP); + //DEBUG_ECHOPGM(" calling handler for ", rcpy.VP); sent_one = true; rcpy.send_to_display_handler(rcpy); } else { // auto x=dgusdisplay.GetFreeTxBuffer(); - //DEBUG_ECHOLNPAIR(" tx almost full: ", x); - //DEBUG_ECHOPAIR(" update_ptr ", update_ptr); + //DEBUG_ECHOLNPGM(" tx almost full: ", x); + //DEBUG_ECHOPGM(" update_ptr ", update_ptr); ScreenComplete = false; return; // please call again! } @@ -767,7 +767,7 @@ void DGUSScreenHandler::GotoScreen(DGUSLCD_Screens screen, bool ispopup) { } void DGUSDisplay::RequestScreen(DGUSLCD_Screens screen) { - DEBUG_ECHOLNPAIR("GotoScreen ", screen); + DEBUG_ECHOLNPGM("GotoScreen ", screen); const unsigned char gotoscreen[] = { 0x5A, 0x01, (unsigned char) (screen >> 8U), (unsigned char) (screen & 0xFFU) }; WriteVariable(0x84, gotoscreen, sizeof(gotoscreen)); } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index ae6a31fb05..60a0f6c5bb 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -134,7 +134,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // meaning "return to previous screen" DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; - DEBUG_ECHOLNPAIR("\n DEBUG target", target); + DEBUG_ECHOLNPGM("\n DEBUG target", target); if (target == DGUSLCD_SCREEN_POPUP) { // Special handling for popup is to return to previous menu @@ -146,7 +146,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { UpdateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } @@ -190,10 +190,10 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓"); ForceCompleteUpdate(); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -215,13 +215,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (movevalue < 0) { value = -value; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓ "); if (backup_speed != speed) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); } // while (!enqueue_and_echo_command(buf)) idle(); //DEBUG_ECHOLNPGM(" ✓ "); @@ -237,16 +237,16 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); return; } #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("V1:", rawvalue); + DEBUG_ECHOLNPGM("V1:", rawvalue); float value = (float)rawvalue / 10; - DEBUG_ECHOLNPAIR("V2:", value); + DEBUG_ECHOLNPGM("V2:", value); float newvalue = 0; switch (var.VP) { diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index c67ec73f61..83f7a39c28 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -134,7 +134,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // meaning "return to previous screen" DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; - DEBUG_ECHOLNPAIR("\n DEBUG target", target); + DEBUG_ECHOLNPGM("\n DEBUG target", target); if (target == DGUSLCD_SCREEN_POPUP) { // Special handling for popup is to return to previous menu @@ -146,7 +146,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { UpdateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } @@ -190,10 +190,10 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓"); ForceCompleteUpdate(); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -215,13 +215,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (movevalue < 0) { value = -value; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓ "); if (backup_speed != speed) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); } // while (!enqueue_and_echo_command(buf)) idle(); //DEBUG_ECHOLNPGM(" ✓ "); @@ -237,16 +237,16 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); return; } #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("V1:", rawvalue); + DEBUG_ECHOLNPGM("V1:", rawvalue); float value = (float)rawvalue / 10; - DEBUG_ECHOLNPAIR("V2:", value); + DEBUG_ECHOLNPGM("V2:", value); float newvalue = 0; switch (var.VP) { diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index c80191c8e5..60c3790882 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -83,8 +83,8 @@ void DGUSScreenHandler::sendinfoscreen_mks(const void *line1, const void *line2, void DGUSScreenHandler::DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { - //DEBUG_ECHOPAIR(" DGUS_LCD_SendWordValueToDisplay ", var.VP); - //DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + //DEBUG_ECHOPGM(" DGUS_LCD_SendWordValueToDisplay ", var.VP); + //DEBUG_ECHOLNPGM(" data ", *(uint16_t *)var.memadr); uint16_t tmp = *(uint8_t *) var.memadr; // +1 -> avoid rounding issues for the display. // tmp = map(tmp, 0, 255, 0, 100); dgusdisplay.WriteVariable(var.VP, tmp); @@ -109,14 +109,14 @@ void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay_MKS(DGUS_VP_Variable &var void DGUSScreenHandler::DGUSLCD_SetUint8(DGUS_VP_Variable &var, void *val_ptr) { if (var.memadr) { const uint16_t value = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("FAN value get:", value); + DEBUG_ECHOLNPGM("FAN value get:", value); *(uint8_t*)var.memadr = map(constrain(value, 0, 255), 0, 255, 0, 255); - DEBUG_ECHOLNPAIR("FAN value change:", *(uint8_t*)var.memadr); + DEBUG_ECHOLNPGM("FAN value change:", *(uint8_t*)var.memadr); } } void DGUSScreenHandler::DGUSLCD_SendGbkToDisplay(DGUS_VP_Variable &var) { - DEBUG_ECHOLNPAIR(" data ", *(uint16_t *)var.memadr); + DEBUG_ECHOLNPGM(" data ", *(uint16_t *)var.memadr); uint16_t *tmp = (uint16_t*) var.memadr; dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); } @@ -282,7 +282,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // meaning "return to previous screen" DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; - DEBUG_ECHOLNPAIR("\n DEBUG target", target); + DEBUG_ECHOLNPGM("\n DEBUG target", target); // when the dgus had reboot, it will enter the DGUSLCD_SCREEN_MAIN page, // so user can change any page to use this function, an it will check @@ -311,13 +311,13 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { UpdateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } void DGUSScreenHandler::ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t target = swap16(*(uint16_t *)val_ptr); - DEBUG_ECHOLNPAIR(" back = 0x%x", target); + DEBUG_ECHOLNPGM(" back = 0x%x", target); switch (target) { } } @@ -756,7 +756,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { else if (manualMoveStep == 0x02) manualMoveStep = 100; else if (manualMoveStep == 0x03) manualMoveStep = 1000; - DEBUG_ECHOLNPAIR("QUEUE LEN:", queue.length); + DEBUG_ECHOLNPGM("QUEUE LEN:", queue.length); if (!print_job_timer.isPaused() && !queue.ring_buffer.empty()) return; @@ -818,7 +818,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { break; } - DEBUG_ECHOPAIR("movevalue = ", movevalue); + DEBUG_ECHOPGM("movevalue = ", movevalue); if (movevalue != 0 && movevalue != 5) { // get move distance switch (movevalue) { case 0x0001: movevalue = manualMoveStep; break; @@ -829,20 +829,20 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); // char buf[6] = "G28 X"; // buf[4] = axiscode; char buf[6]; sprintf(buf, "G28 %c", axiscode); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓"); ForceCompleteUpdate(); return; } else if (movevalue == 5) { - DEBUG_ECHOPAIR("send M84"); + DEBUG_ECHOPGM("send M84"); char buf[6]; snprintf_P(buf,6,PSTR("M84 %c"), axiscode); queue.enqueue_one_now(buf); @@ -851,7 +851,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { @@ -871,7 +871,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { //if (backup_speed != speed) { // snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); // queue.enqueue_one_now(buf); - // //DEBUG_ECHOPAIR(" ", buf); + // //DEBUG_ECHOPGM(" ", buf); //} //while (!enqueue_and_echo_command(buf)) idle(); @@ -889,7 +889,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); return; } @@ -923,7 +923,7 @@ void DGUSScreenHandler::HandleStepPerMMChanged_MKS(DGUS_VP_Variable &var, void * const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); const float value = (float)value_raw; - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); DEBUG_ECHOLNPAIR_F("value:", value); ExtUI::axis_t axis; @@ -945,7 +945,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged_MKS(DGUS_VP_Variable &var const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); const float value = (float)value_raw; - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); DEBUG_ECHOLNPAIR_F("value:", value); ExtUI::extruder_t extruder; @@ -970,7 +970,7 @@ void DGUSScreenHandler::HandleMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *va const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); const float value = (float)value_raw; - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); DEBUG_ECHOLNPAIR_F("value:", value); ExtUI::axis_t axis; @@ -992,7 +992,7 @@ void DGUSScreenHandler::HandleExtruderMaxSpeedChange_MKS(DGUS_VP_Variable &var, const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); const float value = (float)value_raw; - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); DEBUG_ECHOLNPAIR_F("value:", value); ExtUI::extruder_t extruder; @@ -1017,7 +1017,7 @@ void DGUSScreenHandler::HandleMaxAccChange_MKS(DGUS_VP_Variable &var, void *val_ const uint16_t value_raw = swap16(*(uint16_t*)val_ptr); const float value = (float)value_raw; - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); DEBUG_ECHOLNPAIR_F("value:", value); ExtUI::axis_t axis; @@ -1037,7 +1037,7 @@ void DGUSScreenHandler::HandleExtruderAccChange_MKS(DGUS_VP_Variable &var, void DEBUG_ECHOLNPGM("HandleExtruderAccChange_MKS"); uint16_t value_raw = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); float value = (float)value_raw; ExtUI::extruder_t extruder; switch (var.VP) { @@ -1091,9 +1091,9 @@ void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("V1:", rawvalue); + DEBUG_ECHOLNPGM("V1:", rawvalue); const float value = 1.0f * rawvalue; - DEBUG_ECHOLNPAIR("V2:", value); + DEBUG_ECHOLNPGM("V2:", value); float newvalue = 0; switch (var.VP) { diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index b0759c63af..db467d7b34 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -134,7 +134,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // meaning "return to previous screen" DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; - DEBUG_ECHOLNPAIR("\n DEBUG target", target); + DEBUG_ECHOLNPGM("\n DEBUG target", target); if (target == DGUSLCD_SCREEN_POPUP) { // Special handling for popup is to return to previous menu @@ -146,7 +146,7 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { UpdateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPAIR("WARNING: No screen Mapping found for ", target); + if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } @@ -190,10 +190,10 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPAIR(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓"); ForceCompleteUpdate(); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPAIR(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -215,13 +215,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (movevalue < 0) { value = -value; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); queue.enqueue_one_now(buf); //DEBUG_ECHOLNPGM(" ✓ "); if (backup_speed != speed) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); - //DEBUG_ECHOPAIR(" ", buf); + //DEBUG_ECHOPGM(" ", buf); } // while (!enqueue_and_echo_command(buf)) idle(); //DEBUG_ECHOLNPGM(" ✓ "); @@ -237,16 +237,16 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPAIR(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); return; } #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR("V1:", rawvalue); + DEBUG_ECHOLNPGM("V1:", rawvalue); float value = (float)rawvalue / 10; - DEBUG_ECHOLNPAIR("V2:", value); + DEBUG_ECHOLNPGM("V2:", value); float newvalue = 0; switch (var.VP) { diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp index e82f63bce1..4fce364f81 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp @@ -159,7 +159,7 @@ void DGUSDisplay::WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t si } void DGUSDisplay::SwitchScreen(DGUS_Screen screen) { - DEBUG_ECHOLNPAIR("SwitchScreen ", (uint8_t)screen); + DEBUG_ECHOLNPGM("SwitchScreen ", (uint8_t)screen); const uint8_t command[] = { 0x5A, 0x01, 0x00, (uint8_t)screen }; Write(0x84, command, sizeof(command)); } @@ -167,13 +167,13 @@ void DGUSDisplay::SwitchScreen(DGUS_Screen screen) { void DGUSDisplay::PlaySound(uint8_t start, uint8_t len, uint8_t volume) { if (volume == 0) volume = DGUSDisplay::volume; if (volume == 0) return; - DEBUG_ECHOLNPAIR("PlaySound ", start, ":", len, "\nVolume ", volume); + DEBUG_ECHOLNPGM("PlaySound ", start, ":", len, "\nVolume ", volume); const uint8_t command[] = { start, len, volume, 0x00 }; Write(0xA0, command, sizeof(command)); } void DGUSDisplay::EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { - DEBUG_ECHOLNPAIR("EnableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); + DEBUG_ECHOLNPGM("EnableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x01 }; Write(0xB0, command, sizeof(command)); @@ -183,7 +183,7 @@ void DGUSDisplay::EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_ } void DGUSDisplay::DisableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { - DEBUG_ECHOLNPAIR("DisableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); + DEBUG_ECHOLNPGM("DisableControl ", (uint8_t)control, "\nScreen ", (uint8_t)screen, "\nType ", (uint8_t)type); const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x00 }; Write(0xB0, command, sizeof(command)); @@ -203,14 +203,14 @@ uint8_t DGUSDisplay::GetVolume() { void DGUSDisplay::SetBrightness(uint8_t new_brightness) { brightness = constrain(new_brightness, 0, 100); new_brightness = map_precise(brightness, 0, 100, 5, 100); - DEBUG_ECHOLNPAIR("SetBrightness ", new_brightness); + DEBUG_ECHOLNPGM("SetBrightness ", new_brightness); const uint8_t command[] = { new_brightness, new_brightness }; Write(0x82, command, sizeof(command)); } void DGUSDisplay::SetVolume(uint8_t new_volume) { volume = map_precise(constrain(new_volume, 0, 100), 0, 100, 0, 255); - DEBUG_ECHOLNPAIR("SetVolume ", volume); + DEBUG_ECHOLNPGM("SetVolume ", volume); const uint8_t command[] = { volume, 0x00 }; Write(0xA1, command, sizeof(command)); } @@ -234,19 +234,19 @@ void DGUSDisplay::ProcessRx() { case DGUS_IDLE: // Waiting for the first header byte receivedbyte = LCD_SERIAL.read(); - DEBUG_ECHOPAIR("< ", receivedbyte); + DEBUG_ECHOPGM("< ", receivedbyte); if (DGUS_HEADER1 == receivedbyte) rx_datagram_state = DGUS_HEADER1_SEEN; break; case DGUS_HEADER1_SEEN: // Waiting for the second header byte receivedbyte = LCD_SERIAL.read(); - DEBUG_ECHOPAIR(" ", receivedbyte); + DEBUG_ECHOPGM(" ", receivedbyte); rx_datagram_state = (DGUS_HEADER2 == receivedbyte) ? DGUS_HEADER2_SEEN : DGUS_IDLE; break; case DGUS_HEADER2_SEEN: // Waiting for the length byte rx_datagram_len = LCD_SERIAL.read(); - DEBUG_ECHOPAIR(" (", rx_datagram_len, ") "); + DEBUG_ECHOPGM(" (", rx_datagram_len, ") "); // Telegram min len is 3 (command and one word of payload) rx_datagram_state = WITHIN(rx_datagram_len, 3, DGUS_RX_BUFFER_SIZE) ? DGUS_WAIT_TELEGRAM : DGUS_IDLE; @@ -258,7 +258,7 @@ void DGUSDisplay::ProcessRx() { initialized = true; // We've talked to it, so we defined it as initialized. uint8_t command = LCD_SERIAL.read(); - DEBUG_ECHOPAIR("# ", command); + DEBUG_ECHOPGM("# ", command); uint8_t readlen = rx_datagram_len - 1; // command is part of len. unsigned char tmp[rx_datagram_len - 1]; @@ -266,7 +266,7 @@ void DGUSDisplay::ProcessRx() { while (readlen--) { receivedbyte = LCD_SERIAL.read(); - DEBUG_ECHOPAIR(" ", receivedbyte); + DEBUG_ECHOPGM(" ", receivedbyte); *ptmp++ = receivedbyte; } DEBUG_ECHOPGM(" # "); @@ -287,7 +287,7 @@ void DGUSDisplay::ProcessRx() { if (command == DGUS_READVAR) { const uint16_t addr = tmp[0] << 8 | tmp[1]; const uint8_t dlen = tmp[2] << 1; // Convert to Bytes. (Display works with words) - DEBUG_ECHOPAIR("addr=", addr, " dlen=", dlen, "> "); + DEBUG_ECHOPGM("addr=", addr, " dlen=", dlen, "> "); if (addr == DGUS_VERSION && dlen == 2) { DEBUG_ECHOLNPGM("VERSIONS"); @@ -400,7 +400,7 @@ bool DGUS_PopulateVP(const DGUS_Addr addr, DGUS_VP * const buffer) { return true; } } while (++ret); - DEBUG_ECHOLNPAIR("VP not found: ", (uint16_t)addr); + DEBUG_ECHOLNPGM("VP not found: ", (uint16_t)addr); return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index a28318335c..ebe99a37d2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -178,9 +178,9 @@ bool UIFlashStorage::is_present = false; if (!is_known) { SERIAL_ECHO_MSG("Unable to locate supported SPI Flash Memory."); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(" Manufacturer ID, got: ", manufacturer_id); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(" Device Type , got: ", device_type); - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(" Capacity , got: ", capacity); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Manufacturer ID, got: ", manufacturer_id); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Device Type , got: ", device_type); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(" Capacity , got: ", capacity); } return is_known; @@ -247,7 +247,7 @@ bool UIFlashStorage::is_present = false; case 0xFFFFFFFFul: return read_offset; case delimiter: read_offset = offset; break; default: - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("Invalid delimiter in Flash: ", delim); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Invalid delimiter in Flash: ", delim); return -1; } } @@ -325,7 +325,7 @@ bool UIFlashStorage::is_present = false; } SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Writing UI settings to SPI Flash (offset ", write_addr); + SERIAL_ECHOPGM("Writing UI settings to SPI Flash (offset ", write_addr); SERIAL_ECHOPGM(")..."); const uint32_t delim = delimiter; @@ -509,7 +509,7 @@ bool UIFlashStorage::is_present = false; bytes_remaining = get_media_file_size(slot); if (bytes_remaining != 0xFFFFFFFFUL) { - SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("Boot media file size:", bytes_remaining); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Boot media file size:", bytes_remaining); addr = get_media_file_start(slot); return true; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index a696ca3413..c8e5721006 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -131,7 +131,7 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + //SERIAL_ECHOLNPGM("OnPidTuning:", rst); switch (rst) { case PID_STARTED: StatusScreen::setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index a10fdc3ede..40cddce7fd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1025,8 +1025,8 @@ template bool CLCD::CommandFifo::write(T data, uint16_t len) { if (Command_Space < (len + padding)) { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Waiting for ", len + padding); - SERIAL_ECHOLNPAIR(" bytes in command queue, now free: ", Command_Space); + SERIAL_ECHOPGM("Waiting for ", len + padding); + SERIAL_ECHOLNPGM(" bytes in command queue, now free: ", Command_Space); #endif do { Command_Space = mem_read_32(REG::CMDB_SPACE) & 0x0FFF; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index b4438a92b9..2b7eca0cce 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -199,7 +199,7 @@ #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) - // SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything + // SERIAL_ECHOPGM / SERIAL_ECHOPGM_P is used to output a key value pair. The key must be a string and the value can be anything // Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). #define __SEP_N(N,V...) _SEP_##N(V) #define _SEP_N(N,V...) __SEP_N(N,V) @@ -218,9 +218,9 @@ #define SERIAL_ECHO_START() #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(V...) SERIAL_ECHOLNPAIR(V) - #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) - #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) + #define SERIAL_ECHO_MSG(V...) SERIAL_ECHOLNPGM(V) + #define SERIAL_ECHOLNPGM(V...) _SELP_N(NUM_ARGS(V),V) + #define SERIAL_ECHOPGM(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp index a13c36265e..1ee73c140e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp @@ -132,8 +132,8 @@ bool DLCache::store(uint32_t min_bytes /* = 0*/) { // Not enough memory to cache the display list. #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Not enough space in GRAM to cache display list, free space: ", dl_slot_size); - SERIAL_ECHOLNPAIR(" Required: ", dl_size); + SERIAL_ECHOPGM ("Not enough space in GRAM to cache display list, free space: ", dl_slot_size); + SERIAL_ECHOLNPGM(" Required: ", dl_size); #endif dl_slot_used = 0; save_slot(); @@ -142,8 +142,8 @@ bool DLCache::store(uint32_t min_bytes /* = 0*/) { else { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Saving DL to RAMG cache, bytes: ", dl_slot_used); - SERIAL_ECHOLNPAIR(" Free space: ", dl_slot_size); + SERIAL_ECHOPGM ("Saving DL to RAMG cache, bytes: ", dl_slot_used); + SERIAL_ECHOLNPGM(" Free space: ", dl_slot_size); #endif dl_slot_used = dl_size; save_slot(); @@ -172,8 +172,8 @@ void DLCache::append() { cmd.execute(); wait_until_idle(); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Appending to DL from RAMG cache, bytes: ", dl_slot_used); - SERIAL_ECHOLNPAIR(" REG_CMD_DL: ", CLCD::mem_read_32(REG::CMD_DL)); + SERIAL_ECHOPGM ("Appending to DL from RAMG cache, bytes: ", dl_slot_used); + SERIAL_ECHOLNPGM(" REG_CMD_DL: ", CLCD::mem_read_32(REG::CMD_DL)); #endif } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp index 4e318cef17..44836cec48 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp @@ -33,7 +33,7 @@ uint8_t ScreenRef::lookupScreen(onRedraw_func_t onRedraw_ptr) { } #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Screen not found: ", (uintptr_t) onRedraw_ptr); + SERIAL_ECHOPGM("Screen not found: ", (uintptr_t) onRedraw_ptr); #endif return 0xFF; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h index 486c4fe562..a13ab8e9aa 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h @@ -237,7 +237,7 @@ class CachedScreen { cmd.cmd(CMD_SWAP); cmd.execute(); #if ENABLED(TOUCH_UI_DEBUG) - SERIAL_ECHOLNPAIR("Time to draw screen (ms): ", millis() - start_time); + SERIAL_ECHOLNPGM("Time to draw screen (ms): ", millis() - start_time); #endif } }; diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index 12cdcdf004..8c9bfc32e5 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -122,7 +122,7 @@ void set_lcd_error_P(PGM_P const error, PGM_P const component/*=nullptr*/) { void process_lcd_c_command(const char *command) { const int target_val = command[1] ? atoi(command + 1) : -1; if (target_val < 0) { - DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); + DEBUG_ECHOLNPGM("UNKNOWN C COMMAND ", command); return; } switch (command[0]) { @@ -143,7 +143,7 @@ void process_lcd_c_command(const char *command) { case 'P': ExtUI::setTargetTemp_celsius(target_val, ExtUI::heater_t::BED); break; #endif - default: DEBUG_ECHOLNPAIR("UNKNOWN C COMMAND ", command); + default: DEBUG_ECHOLNPGM("UNKNOWN C COMMAND ", command); } } @@ -185,7 +185,7 @@ void process_lcd_eb_command(const char *command) { write_to_lcd(message_buffer); } break; - default: DEBUG_ECHOLNPAIR("UNKNOWN E/B COMMAND ", command); + default: DEBUG_ECHOLNPGM("UNKNOWN E/B COMMAND ", command); } } @@ -212,7 +212,7 @@ void process_lcd_j_command(const char *command) { case 'Y': j_move_axis(command, ExtUI::axis_t::Y); break; case 'Z': j_move_axis(command, ExtUI::axis_t::Z); break; case 'X': j_move_axis(command, ExtUI::axis_t::X); break; - default: DEBUG_ECHOLNPAIR("UNKNOWN J COMMAND ", command); + default: DEBUG_ECHOLNPGM("UNKNOWN J COMMAND ", command); } } @@ -336,7 +336,7 @@ void process_lcd_s_command(const char *command) { #endif } break; - default: DEBUG_ECHOLNPAIR("UNKNOWN S COMMAND ", command); + default: DEBUG_ECHOLNPGM("UNKNOWN S COMMAND ", command); } } @@ -360,11 +360,11 @@ void process_lcd_command(const char *command) { case 'C': process_lcd_c_command(current); break; case 'B': case 'E': process_lcd_eb_command(current); break; - default: DEBUG_ECHOLNPAIR("UNKNOWN COMMAND ", command); + default: DEBUG_ECHOLNPGM("UNKNOWN COMMAND ", command); } } else - DEBUG_ECHOLNPAIR("UNKNOWN COMMAND FORMAT ", command); + DEBUG_ECHOLNPGM("UNKNOWN COMMAND FORMAT ", command); } // diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index 8a23799988..cae534de3b 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -106,7 +106,7 @@ namespace ExtUI { void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - //SERIAL_ECHOLNPAIR("OnPidTuning:", rst); + //SERIAL_ECHOLNPGM("OnPidTuning:", rst); switch (rst) { case PID_STARTED: set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE)); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 0a5f5cd550..624626a322 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -233,7 +233,7 @@ uint32_t lv_get_pic_addr(uint8_t *Pname) { currentFlashPage = 0; #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPAIR("Getting picture SPI Flash Address: ", (const char*)Pname); + SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname); #endif W25QXX.init(SPI_QUARTER_SPEED); @@ -408,7 +408,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { createFilename(dosFilename, entry); if (!file.open(&dir, dosFilename, O_READ)) { #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPAIR("Error opening Asset: ", fn); + SERIAL_ECHOLNPGM("Error opening Asset: ", fn); #endif return; } @@ -463,7 +463,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { } while (pbr >= BMP_WRITE_BUF_LEN); #endif #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPAIR("Space used: ", fn, " - ", (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize / 1024, "KB"); + SERIAL_ECHOLNPGM("Space used: ", fn, " - ", (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize / 1024, "KB"); totalCompressed += (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize; #endif SPIFlash.endWrite(); @@ -481,7 +481,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { file.close(); #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPAIR("Asset added: ", fn); + SERIAL_ECHOLNPGM("Asset added: ", fn); #endif } @@ -537,8 +537,8 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { #if ENABLED(MARLIN_DEV_MODE) uint8_t pic_counter = 0; W25QXX.SPI_FLASH_BufferRead(&pic_counter, PIC_COUNTER_ADDR, 1); - SERIAL_ECHOLNPAIR("Total assets loaded: ", pic_counter); - SERIAL_ECHOLNPAIR("Total Uncompressed: ", totalSizes, ", Compressed: ", totalCompressed); + SERIAL_ECHOLNPGM("Total assets loaded: ", pic_counter); + SERIAL_ECHOLNPGM("Total Uncompressed: ", totalSizes, ", Compressed: ", totalCompressed); #endif } diff --git a/Marlin/src/lcd/extui/nextion/FileNavigator.cpp b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp index 650bbd6645..07f1256ded 100644 --- a/Marlin/src/lcd/extui/nextion/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp @@ -79,7 +79,7 @@ void FileNavigator::getFiles(uint16_t index) { lastindex = index; #if NEXDEBUG(AC_FILE) - DEBUG_ECHOLNPAIR("index=", index, " currentindex=", currentindex); + DEBUG_ECHOLNPGM("index=", index, " currentindex=", currentindex); #endif if (currentindex == 0 && folderdepth > 0) { // Add a link to go up a folder @@ -127,7 +127,7 @@ void FileNavigator::getFiles(uint16_t index) { fcnt++; fseek = seek; #if NEXDEBUG(AC_FILE) - DEBUG_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'\n"); + DEBUG_ECHOLNPGM("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'\n"); #endif } } @@ -137,7 +137,7 @@ void FileNavigator::getFiles(uint16_t index) { void FileNavigator::changeDIR(char *folder) { #if NEXDEBUG(AC_FILE) - DEBUG_ECHOLNPAIR("currentfolder: ", currentfoldername, " New: ", folder); + DEBUG_ECHOLNPGM("currentfolder: ", currentfoldername, " New: ", folder); #endif if (folderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth strcat(currentfoldername, folder); @@ -165,7 +165,7 @@ void FileNavigator::upDIR() { pos[1] = '\0'; } #if NEXDEBUG(AC_FILE) - DEBUG_ECHOLNPAIR("depth: ", folderdepth, " currentfoldername: ", currentfoldername); + DEBUG_ECHOLNPGM("depth: ", folderdepth, " currentfoldername: ", currentfoldername); #endif } diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 9035442681..50423db4fd 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -72,7 +72,7 @@ void NextionTFT::Startup() { SEND_VALasTXT("tmppage.bedy", Y_BED_SIZE); SEND_VALasTXT("tmppage.bedz", Z_MAX_POS); - DEBUG_ECHOLNPAIR("Nextion Debug Level ", NEXDEBUGLEVEL); + DEBUG_ECHOLNPGM("Nextion Debug Level ", NEXDEBUGLEVEL); } void NextionTFT::IdleLoop() { @@ -98,13 +98,13 @@ void NextionTFT::PrintFinished() { void NextionTFT::ConfirmationRequest(const char * const msg) { SEND_VALasTXT("tmppage.M117", msg); #if NEXDEBUG(N_MARLIN) - DEBUG_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); + DEBUG_ECHOLNPGM("ConfirmationRequest() ", msg, " printer_state:", printer_state); #endif } void NextionTFT::StatusChange(const char * const msg) { #if NEXDEBUG(N_MARLIN) - DEBUG_ECHOLNPAIR("StatusChange() ", msg, "\nprinter_state:", printer_state); + DEBUG_ECHOLNPGM("StatusChange() ", msg, "\nprinter_state:", printer_state); #endif SEND_VALasTXT("tmppage.M117", msg); } @@ -133,12 +133,12 @@ bool NextionTFT::ReadTFTCommand() { if (nextion_command[0] == 'G' || nextion_command[0] == 'M' || nextion_command[0] == 'T') injectCommands(nextion_command); #if NEXDEBUG(N_ALL) - DEBUG_ECHOLNPAIR("< ", nextion_command); + DEBUG_ECHOLNPGM("< ", nextion_command); #endif #if NEXDEBUG(N_SOME) uint8_t req = atoi(&nextion_command[1]); if (req > 7 && req != 20) - DEBUG_ECHOLNPAIR( "> ", AS_CHAR(nextion_command[0]), + DEBUG_ECHOLNPGM( "> ", AS_CHAR(nextion_command[0]), "\n> ", AS_CHAR(nextion_command[1]), "\n> ", AS_CHAR(nextion_command[2]), "\n> ", AS_CHAR(nextion_command[3]), @@ -151,7 +151,7 @@ bool NextionTFT::ReadTFTCommand() { void NextionTFT::SendFileList(int8_t startindex) { // respond to panel request for 7 files starting at index #if NEXDEBUG(N_INFO) - DEBUG_ECHOLNPAIR("## SendFileList ## ", startindex); + DEBUG_ECHOLNPGM("## SendFileList ## ", startindex); #endif filenavigator.getFiles(startindex); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 8c59500574..67ad99ba2b 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -778,7 +778,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder ); - //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); + //SERIAL_ECHOLNPGM("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); axis = NO_AXIS_ENUM; @@ -795,7 +795,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves axis = move_axis; - //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); + //SERIAL_ECHOLNPGM("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); } #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -981,10 +981,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; //#define ENCODER_RATE_MULTIPLIER_DEBUG #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); - SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); - SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); - SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); + SERIAL_ECHOPGM("Enc Step Rate: ", encoderStepRate); + SERIAL_ECHOPGM(" Multiplier: ", encoderMultiplier); + SERIAL_ECHOPGM(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); + SERIAL_ECHOPGM(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); SERIAL_EOL(); #endif } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 7ea355b795..2c33e890bf 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -217,7 +217,7 @@ void menu_advanced_settings(); #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) void bltouch_report() { - SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode); + SERIAL_ECHOLNPGM("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode); SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); char mess[21]; strcpy_P(mess, PSTR("BLTouch Mode - ")); diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index c3090bcc5b..9bc799129e 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -56,12 +56,12 @@ static bool probe_single_point() { if (reference_index < 0) reference_index = tram_index; move_to_tramming_wait_pos(); - DEBUG_ECHOLNPAIR("probe_single_point(", tram_index, ") = ", z_probed_height, "mm"); + DEBUG_ECHOLNPGM("probe_single_point(", tram_index, ") = ", z_probed_height, "mm"); return (z_isvalid[tram_index] = !isnan(z_probed_height)); } static void _menu_single_probe() { - DEBUG_ECHOLNPAIR("Screen: single probe screen Arg:", tram_index); + DEBUG_ECHOLNPGM("Screen: single probe screen Arg:", tram_index); START_MENU(); STATIC_ITEM(MSG_BED_TRAMMING, SS_LEFT); STATIC_ITEM(MSG_LAST_VALUE_SP, SS_LEFT, z_isvalid[tram_index] ? ftostr42_52(z_measured[reference_index] - z_measured[tram_index]) : "---"); @@ -87,7 +87,7 @@ static void tramming_wizard_menu() { // Init the wizard and enter the submenu void goto_tramming_wizard() { - DEBUG_ECHOLNPAIR("Screen: goto_tramming_wizard", 1); + DEBUG_ECHOLNPGM("Screen: goto_tramming_wizard", 1); ui.defer_status_screen(); // Initialize measured point flags diff --git a/Marlin/src/lcd/tft/tft_string.cpp b/Marlin/src/lcd/tft/tft_string.cpp index c2a571e826..6f2d8690b2 100644 --- a/Marlin/src/lcd/tft/tft_string.cpp +++ b/Marlin/src/lcd/tft/tft_string.cpp @@ -45,21 +45,21 @@ void TFT_String::set_font(const uint8_t *font) { for (glyph = 0; glyph < 256; glyph++) glyphs[glyph] = nullptr; - DEBUG_ECHOLNPAIR("Format: ", font_header->Format); - DEBUG_ECHOLNPAIR("BBXWidth: ", font_header->BBXWidth); - DEBUG_ECHOLNPAIR("BBXHeight: ", font_header->BBXHeight); - DEBUG_ECHOLNPAIR("BBXOffsetX: ", font_header->BBXOffsetX); - DEBUG_ECHOLNPAIR("BBXOffsetY: ", font_header->BBXOffsetY); - DEBUG_ECHOLNPAIR("CapitalAHeight: ", font_header->CapitalAHeight); - DEBUG_ECHOLNPAIR("Encoding65Pos: ", font_header->Encoding65Pos); - DEBUG_ECHOLNPAIR("Encoding97Pos: ", font_header->Encoding97Pos); - DEBUG_ECHOLNPAIR("FontStartEncoding: ", font_header->FontStartEncoding); - DEBUG_ECHOLNPAIR("FontEndEncoding: ", font_header->FontEndEncoding); - DEBUG_ECHOLNPAIR("LowerGDescent: ", font_header->LowerGDescent); - DEBUG_ECHOLNPAIR("FontAscent: ", font_header->FontAscent); - DEBUG_ECHOLNPAIR("FontDescent: ", font_header->FontDescent); - DEBUG_ECHOLNPAIR("FontXAscent: ", font_header->FontXAscent); - DEBUG_ECHOLNPAIR("FontXDescent: ", font_header->FontXDescent); + DEBUG_ECHOLNPGM("Format: ", font_header->Format); + DEBUG_ECHOLNPGM("BBXWidth: ", font_header->BBXWidth); + DEBUG_ECHOLNPGM("BBXHeight: ", font_header->BBXHeight); + DEBUG_ECHOLNPGM("BBXOffsetX: ", font_header->BBXOffsetX); + DEBUG_ECHOLNPGM("BBXOffsetY: ", font_header->BBXOffsetY); + DEBUG_ECHOLNPGM("CapitalAHeight: ", font_header->CapitalAHeight); + DEBUG_ECHOLNPGM("Encoding65Pos: ", font_header->Encoding65Pos); + DEBUG_ECHOLNPGM("Encoding97Pos: ", font_header->Encoding97Pos); + DEBUG_ECHOLNPGM("FontStartEncoding: ", font_header->FontStartEncoding); + DEBUG_ECHOLNPGM("FontEndEncoding: ", font_header->FontEndEncoding); + DEBUG_ECHOLNPGM("LowerGDescent: ", font_header->LowerGDescent); + DEBUG_ECHOLNPGM("FontAscent: ", font_header->FontAscent); + DEBUG_ECHOLNPGM("FontDescent: ", font_header->FontDescent); + DEBUG_ECHOLNPGM("FontXAscent: ", font_header->FontXAscent); + DEBUG_ECHOLNPGM("FontXDescent: ", font_header->FontXDescent); add_glyphs(font); } diff --git a/Marlin/src/lcd/tft_io/touch_calibration.cpp b/Marlin/src/lcd/tft_io/touch_calibration.cpp index 2a54d2af40..1c3b8b35fc 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.cpp +++ b/Marlin/src/lcd/tft_io/touch_calibration.cpp @@ -77,10 +77,10 @@ void TouchCalibration::validate_calibration() { if (calibration_state == CALIBRATION_SUCCESS) { SERIAL_ECHOLNPGM("Touch screen calibration completed"); - SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_X ", calibration.x); - SERIAL_ECHOLNPAIR("TOUCH_CALIBRATION_Y ", calibration.y); - SERIAL_ECHOLNPAIR("TOUCH_OFFSET_X ", calibration.offset_x); - SERIAL_ECHOLNPAIR("TOUCH_OFFSET_Y ", calibration.offset_y); + SERIAL_ECHOLNPGM("TOUCH_CALIBRATION_X ", calibration.x); + SERIAL_ECHOLNPGM("TOUCH_CALIBRATION_Y ", calibration.y); + SERIAL_ECHOLNPGM("TOUCH_OFFSET_X ", calibration.offset_x); + SERIAL_ECHOLNPGM("TOUCH_OFFSET_Y ", calibration.offset_y); SERIAL_ECHO_TERNARY(calibration.orientation == TOUCH_LANDSCAPE, "TOUCH_ORIENTATION ", "TOUCH_LANDSCAPE", "TOUCH_PORTRAIT", "\n"); TERN_(TOUCH_CALIBRATION_AUTO_SAVE, settings.save()); } @@ -95,7 +95,7 @@ bool TouchCalibration::handleTouch(uint16_t x, uint16_t y) { if (calibration_state < CALIBRATION_SUCCESS) { calibration_points[calibration_state].raw_x = x; calibration_points[calibration_state].raw_y = y; - DEBUG_ECHOLNPAIR("TouchCalibration - State: ", calibration_state, ", x: ", calibration_points[calibration_state].x, ", raw_x: ", x, ", y: ", calibration_points[calibration_state].y, ", raw_y: ", y); + DEBUG_ECHOLNPGM("TouchCalibration - State: ", calibration_state, ", x: ", calibration_points[calibration_state].x, ", raw_x: ", x, ", y: ", calibration_points[calibration_state].y, ", raw_y: ", y); } switch (calibration_state) { diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 876405a40c..6f80652ce5 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -388,10 +388,10 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const inline void echo_min_max(const char a, const_float_t min, const_float_t max) { DEBUG_CHAR(' '); DEBUG_CHAR(a); - DEBUG_ECHOLNPAIR(" min = ", min, " max = ", max); + DEBUG_ECHOLNPGM(" min = ", min, " max = ", max); } inline void echo_oct_used(const_float_t oct, const uint8_t stall) { - DEBUG_ECHOPAIR("over_current_threshold used : ", oct); + DEBUG_ECHOPGM("over_current_threshold used : ", oct); DEBUG_ECHOPGM_P(stall ? PSTR(" (Stall") : PSTR(" (OCD")); DEBUG_ECHOLNPGM(" threshold)"); } @@ -568,7 +568,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } DEBUG_ECHOPGM("Monitoring:"); - for (j = 0; j < driver_count; j++) DEBUG_ECHOPAIR(" ", axis_mon[j]); + for (j = 0; j < driver_count; j++) DEBUG_ECHOPGM(" ", axis_mon[j]); DEBUG_EOL(); // now have a list of driver(s) to monitor @@ -589,19 +589,19 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } // only print the tval from one of the drivers kval_hold = get_param(axis_index[0], L6474_TVAL); - DEBUG_ECHOLNPAIR("TVAL current (mA) = ", (kval_hold + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); + DEBUG_ECHOLNPGM("TVAL current (mA) = ", (kval_hold + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); } else { kval_hold = parser.byteval('K'); if (kval_hold) { - DEBUG_ECHOLNPAIR("kval_hold = ", kval_hold); + DEBUG_ECHOLNPGM("kval_hold = ", kval_hold); for (j = 0; j < driver_count; j++) set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold); } else { // only print the KVAL_HOLD from one of the drivers kval_hold = get_param(axis_index[0], L6470_KVAL_HOLD); - DEBUG_ECHOLNPAIR("KVAL_HOLD = ", kval_hold); + DEBUG_ECHOLNPGM("KVAL_HOLD = ", kval_hold); } } @@ -629,7 +629,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in OCD_TH_actual = (OCD_TH_val_local + 1) * 375; } - DEBUG_ECHOLNPAIR("over_current_threshold specified: ", over_current_threshold); + DEBUG_ECHOLNPGM("over_current_threshold specified: ", over_current_threshold); if (!(sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)) echo_oct_used((STALL_TH_val_local + 1) * 31.25, true); echo_oct_used((OCD_TH_val_local + 1) * 375, false); diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 1264c6fbe8..df0702b9fb 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -177,14 +177,14 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { #ifdef MAX31865_DEBUG_SPI #ifndef LARGE_PINMAP - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "Regular begin call with _cs: ", _cs, " _miso: ", _miso, " _sclk: ", _sclk, " _mosi: ", _mosi ); #else - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "LARGE_PINMAP begin call with _cs: ", _cs, " _miso: ", _miso, " _sclk: ", _sclk, @@ -192,7 +192,7 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { ); #endif // LARGE_PINMAP - SERIAL_ECHOLNPAIR("config: ", readRegister8(MAX31856_CONFIG_REG)); + SERIAL_ECHOLNPGM("config: ", readRegister8(MAX31856_CONFIG_REG)); SERIAL_EOL(); #endif // MAX31865_DEBUG_SPI } @@ -290,7 +290,7 @@ uint16_t MAX31865::readRaw() { uint16_t rtd = readRegister16(MAX31856_RTDMSB_REG); #ifdef MAX31865_DEBUG - SERIAL_ECHOLNPAIR("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); + SERIAL_ECHOLNPGM("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); #endif // Disable the bias to lower power dissipation between reads. @@ -437,7 +437,7 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { while (n--) { buffer[0] = spixfer(0xFF); #ifdef MAX31865_DEBUG_SPI - SERIAL_ECHOLNPAIR("buffer read ", n, " data: ", buffer[0]); + SERIAL_ECHOLNPGM("buffer read ", n, " data: ", buffer[0]); #endif buffer++; } diff --git a/Marlin/src/libs/bresenham.h b/Marlin/src/libs/bresenham.h index 6e4162fd13..865c43c29e 100644 --- a/Marlin/src/libs/bresenham.h +++ b/Marlin/src/libs/bresenham.h @@ -120,11 +120,11 @@ public: static void report(const uint8_t index) { if (index < Cfg::SIZE) { - SERIAL_ECHOPAIR("bresenham ", index, " : (", dividend[index], "/", divisor, ") "); + SERIAL_ECHOPGM("bresenham ", index, " : (", dividend[index], "/", divisor, ") "); if (counter[index] >= 0) SERIAL_CHAR(' '); if (labs(counter[index]) < 100) { SERIAL_CHAR(' '); if (labs(counter[index]) < 10) SERIAL_CHAR(' '); } SERIAL_ECHO(counter[index]); - SERIAL_ECHOLNPAIR(" ... ", value[index]); + SERIAL_ECHOLNPGM(" ... ", value[index]); } } diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 992c3a09b4..899848d7f2 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -121,8 +121,8 @@ void recalc_delta_settings() { */ #define DELTA_DEBUG(VAR) do { \ - SERIAL_ECHOLNPAIR_P(PSTR("Cartesian X"), VAR.x, SP_Y_STR, VAR.y, SP_Z_STR, VAR.z); \ - SERIAL_ECHOLNPAIR_P(PSTR("Delta A"), delta.a, SP_B_STR, delta.b, SP_C_STR, delta.c); \ + SERIAL_ECHOLNPGM_P(PSTR("Cartesian X"), VAR.x, SP_Y_STR, VAR.y, SP_Z_STR, VAR.z); \ + SERIAL_ECHOLNPGM_P(PSTR("Delta A"), delta.a, SP_B_STR, delta.b, SP_C_STR, delta.c); \ }while(0) void inverse_kinematics(const xyz_pos_t &raw) { diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 8ca19e4361..b5315f2f01 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -429,7 +429,7 @@ void Endstops::event_handler() { #endif #define _ENDSTOP_HIT_ECHO(A,C) do{ \ - SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); _SET_STOP_CHAR(A,C); }while(0) + SERIAL_ECHOPGM(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); _SET_STOP_CHAR(A,C); }while(0) #define _ENDSTOP_HIT_TEST(A,C) \ if (TERN0(HAS_##A##_MIN, TEST(hit_state, A##_MIN)) || TERN0(HAS_##A##_MAX, TEST(hit_state, A##_MAX))) \ @@ -1271,7 +1271,7 @@ void Endstops::update() { #endif uint16_t endstop_change = live_state_local ^ old_live_state_local; - #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S)) + #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPGM(" " STRINGIFY(S) ":", TEST(live_state_local, S)) if (endstop_change) { #if HAS_X_MIN diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index eb6dc6597c..cdd425c472 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -195,7 +195,7 @@ inline void report_more_positions() { // 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( + SERIAL_ECHOPGM_P( LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, @@ -257,7 +257,7 @@ void report_current_position_projected() { /** * Output the current grbl compatible state to serial while moving */ - void report_current_grblstate_moving() { SERIAL_ECHOLNPAIR("S_XYZ:", int(M_State_grbl)); } + void report_current_grblstate_moving() { SERIAL_ECHOLNPGM("S_XYZ:", int(M_State_grbl)); } /** * Output the current position (processed) to serial while moving @@ -266,7 +266,7 @@ void report_current_position_projected() { get_cartesian_from_steppers(); const xyz_pos_t lpos = cartes.asLogical(); - SERIAL_ECHOPAIR( + SERIAL_ECHOPGM( "X:", lpos.x #if HAS_Y_AXIS , " Y:", lpos.y @@ -774,7 +774,7 @@ void restore_feedrate_and_scaling() { #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); + SERIAL_ECHOLNPGM("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -969,10 +969,10 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { #endif /* - SERIAL_ECHOPAIR("mm=", cartesian_mm); - SERIAL_ECHOPAIR(" seconds=", seconds); - SERIAL_ECHOPAIR(" segments=", segments); - SERIAL_ECHOPAIR(" segment_mm=", cartesian_segment_mm); + SERIAL_ECHOPGM("mm=", cartesian_mm); + SERIAL_ECHOPGM(" seconds=", seconds); + SERIAL_ECHOPGM(" segments=", segments); + SERIAL_ECHOPGM(" segment_mm=", cartesian_segment_mm); SERIAL_EOL(); //*/ @@ -1035,9 +1035,9 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { const float inv_duration = scaled_fr_mm_s / cartesian_segment_mm; #endif - // SERIAL_ECHOPAIR("mm=", cartesian_mm); - // SERIAL_ECHOLNPAIR(" segments=", segments); - // SERIAL_ECHOLNPAIR(" segment_mm=", cartesian_segment_mm); + //SERIAL_ECHOPGM("mm=", cartesian_mm); + //SERIAL_ECHOLNPGM(" segments=", segments); + //SERIAL_ECHOLNPGM(" segment_mm=", cartesian_segment_mm); // Get the raw current position as starting point xyze_pos_t raw = current_position; @@ -1204,7 +1204,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { new_pos.x += duplicate_extruder_x_offset; // Move duplicate extruder into the correct position - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break; planner.synchronize(); @@ -1515,11 +1515,11 @@ void prepare_line_to_destination() { const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); + DEBUG_ECHOPGM("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else - DEBUG_ECHOPAIR("[", home_fr_mm_s, "]"); + DEBUG_ECHOPGM("[", home_fr_mm_s, "]"); DEBUG_ECHOLNPGM(")"); } @@ -1595,12 +1595,12 @@ void prepare_line_to_destination() { * "trusted" position). */ void set_axis_never_homed(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_untrusted(axis); set_axis_unhomed(axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); } @@ -1683,7 +1683,7 @@ void prepare_line_to_destination() { // Check if home distance within endstop assumed repeatability noise of .05mm and warn. if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) - SERIAL_ECHOLNPAIR("Selected home phase ", home_phase[axis], + SERIAL_ECHOLNPGM("Selected home phase ", home_phase[axis], " too close to endstop trigger phase ", phaseCurrent, ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); @@ -1695,7 +1695,7 @@ void prepare_line_to_destination() { // Optional debug messages if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR( + DEBUG_ECHOLNPGM( "Endstop ", AS_CHAR(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, " Delta:", phaseDelta, " Distance:", mmDelta ); @@ -1741,7 +1741,7 @@ void prepare_line_to_destination() { ) return; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); @@ -1780,7 +1780,7 @@ void prepare_line_to_destination() { const xyz_float_t backoff = SENSORLESS_BACKOFF_MM; if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS) || TERN0(Z_SENSORLESS, axis == Z_AXIS) || TERN0(I_SENSORLESS, axis == I_AXIS) || TERN0(J_SENSORLESS, axis == J_AXIS) || TERN0(K_SENSORLESS, axis == K_AXIS)) && backoff[axis]) { const float backoff_length = -ABS(backoff[axis]) * axis_home_dir; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Sensorless backoff: ", backoff_length, "mm"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Sensorless backoff: ", backoff_length, "mm"); do_homing_move(axis, backoff_length, homing_feedrate(axis)); } #endif @@ -1796,7 +1796,7 @@ void prepare_line_to_destination() { // Fast move towards endstop until triggered // const float move_length = 1.5f * max_length(TERN(DELTA, Z_AXIS, axis)) * axis_home_dir; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Home Fast: ", move_length, "mm"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home Fast: ", move_length, "mm"); do_homing_move(axis, move_length, 0.0, !use_probe_bump); #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) @@ -1806,7 +1806,7 @@ void prepare_line_to_destination() { // If a second homing move is configured... if (bump) { // Move away from the endstop by the axis HOMING_BUMP_MM - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Move Away: ", -bump, "mm"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move Away: ", -bump, "mm"); do_homing_move(axis, -bump, TERN(HOMING_Z_WITH_PROBE, (axis == Z_AXIS ? z_probe_fast_mm_s : 0), 0), false); #if ENABLED(DETECT_BROKEN_ENDSTOP) @@ -1839,7 +1839,7 @@ void prepare_line_to_destination() { // Slow move towards endstop until triggered const float rebump = bump * 2; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Re-bump: ", rebump, "mm"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Re-bump: ", rebump, "mm"); do_homing_move(axis, rebump, get_homing_bump_feedrate(axis), true); #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) @@ -2003,7 +2003,7 @@ void prepare_line_to_destination() { // Retrace by the amount specified in delta_endstop_adj if more than min steps. if (adjDistance * (Z_HOME_DIR) < 0 && ABS(adjDistance) > minDistance) { // away from endstop, more than min distance - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("adjDistance:", adjDistance); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("adjDistance:", adjDistance); do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); } @@ -2050,7 +2050,7 @@ void prepare_line_to_destination() { if (axis == Z_AXIS) fwretract.current_hop = 0.0; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); } // homeaxis() @@ -2075,7 +2075,7 @@ void prepare_line_to_destination() { * Callers must sync the planner position after calling this! */ void set_axis_is_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_trusted(axis); set_axis_homed(axis); @@ -2104,7 +2104,7 @@ void set_axis_is_at_home(const AxisEnum axis) { current_position.z -= probe.offset.z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe.offset.z = ", probe.offset.z); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe.offset.z = ", probe.offset.z); #else @@ -2125,17 +2125,17 @@ void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { #if HAS_HOME_OFFSET - DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); + DEBUG_ECHOLNPGM("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); #endif DEBUG_POS("", current_position); - DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); + DEBUG_ECHOLNPGM("<<< set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); } } #if HAS_WORKSPACE_OFFSET void update_workspace_offset(const AxisEnum axis) { workspace_offset[axis] = home_offset[axis] + position_shift[axis]; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); } #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 04d32f9c18..3e030c84d2 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1858,7 +1858,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ); /* <-- add a slash to enable - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " _populate_block FR:", fr_mm_s, " A:", target.a, " (", da, " steps)" " B:", target.b, " (", db, " steps)" @@ -2331,10 +2331,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (max_vfr > 0 && cs > max_vfr) { NOMORE(speed_factor, max_vfr / cs); // respect volumetric extruder limit (if any) /* <-- add a slash to enable - SERIAL_ECHOPAIR("volumetric extruder limit enforced: ", (cs * CIRCLE_AREA(filament_size[extruder] * 0.5f))); - SERIAL_ECHOPAIR(" mm^3/s (", cs); - SERIAL_ECHOPAIR(" mm/s) limited to ", (max_vfr * CIRCLE_AREA(filament_size[extruder] * 0.5f))); - SERIAL_ECHOPAIR(" mm^3/s (", max_vfr); + SERIAL_ECHOPGM("volumetric extruder limit enforced: ", (cs * CIRCLE_AREA(filament_size[extruder] * 0.5f))); + SERIAL_ECHOPGM(" mm^3/s (", cs); + SERIAL_ECHOPGM(" mm/s) limited to ", (max_vfr * CIRCLE_AREA(filament_size[extruder] * 0.5f))); + SERIAL_ECHOPGM(" mm^3/s (", max_vfr); SERIAL_ECHOLNPGM(" mm/s)"); //*/ } @@ -2921,44 +2921,44 @@ bool Planner::buffer_segment(const abce_pos_t &abce #endif /* <-- add a slash to enable - SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); + SERIAL_ECHOPGM(" buffer_segment FR:", fr_mm_s); #if IS_KINEMATIC - SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b); + SERIAL_ECHOPGM(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b); #else - SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a); - SERIAL_ECHOPAIR(" (", position.x, "->", target.x); + SERIAL_ECHOPGM_P(SP_X_LBL, abce.a); + SERIAL_ECHOPGM(" (", position.x, "->", target.x); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b); + SERIAL_ECHOPGM_P(SP_Y_LBL, abce.b); #endif - SERIAL_ECHOPAIR(" (", position.y, "->", target.y); + SERIAL_ECHOPGM(" (", position.y, "->", target.y); #if LINEAR_AXES >= ABC #if ENABLED(DELTA) - SERIAL_ECHOPAIR(") C:", abce.c); + SERIAL_ECHOPGM(") C:", abce.c); #else SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c); + SERIAL_ECHOPGM_P(SP_Z_LBL, abce.c); #endif - SERIAL_ECHOPAIR(" (", position.z, "->", target.z); + SERIAL_ECHOPGM(" (", position.z, "->", target.z); SERIAL_CHAR(')'); #endif #if LINEAR_AXES >= 4 - SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i); - SERIAL_ECHOPAIR(" (", position.i, "->", target.i); + SERIAL_ECHOPGM_P(SP_I_LBL, abce.i); + SERIAL_ECHOPGM(" (", position.i, "->", target.i); SERIAL_CHAR(')'); #endif #if LINEAR_AXES >= 5 - SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j); - SERIAL_ECHOPAIR(" (", position.j, "->", target.j); + SERIAL_ECHOPGM_P(SP_J_LBL, abce.j); + SERIAL_ECHOPGM(" (", position.j, "->", target.j); SERIAL_CHAR(')'); #endif #if LINEAR_AXES >= 6 - SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k); - SERIAL_ECHOPAIR(" (", position.k, "->", target.k); + SERIAL_ECHOPGM_P(SP_K_LBL, abce.k); + SERIAL_ECHOPGM(" (", position.k, "->", target.k); SERIAL_CHAR(')'); #endif #if HAS_EXTRUDERS - SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e); - SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")"); + SERIAL_ECHOPGM_P(SP_E_LBL, abce.e); + SERIAL_ECHOLNPGM(" (", position.e, "->", target.e, ")"); #else SERIAL_EOL(); #endif @@ -3186,7 +3186,7 @@ inline void limit_and_warn(float &val, const uint8_t axis, PGM_P const setting_n SERIAL_CHAR(AXIS_CHAR(lim_axis)); SERIAL_ECHOPGM(" Max "); SERIAL_ECHOPGM_P(setting_name); - SERIAL_ECHOLNPAIR(" limited to ", val); + SERIAL_ECHOLNPGM(" limited to ", val); } } diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 4c5f1fc782..27dee76715 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -179,7 +179,7 @@ void PrintCounter::saveStats() { inline void _service_when(char buffer[], const char * const msg, const uint32_t when) { SERIAL_ECHOPGM(STR_STATS); SERIAL_ECHOPGM_P(msg); - SERIAL_ECHOLNPAIR(" in ", duration_t(when).toString(buffer)); + SERIAL_ECHOLNPGM(" in ", duration_t(when).toString(buffer)); } #endif @@ -187,7 +187,7 @@ void PrintCounter::showStats() { char buffer[22]; SERIAL_ECHOPGM(STR_STATS); - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( "Prints: ", data.totalPrints, ", Finished: ", data.finishedPrints, ", Failed: ", data.totalPrints - data.finishedPrints @@ -197,21 +197,21 @@ void PrintCounter::showStats() { SERIAL_ECHOPGM(STR_STATS); duration_t elapsed = data.printTime; elapsed.toString(buffer); - SERIAL_ECHOPAIR("Total time: ", buffer); + SERIAL_ECHOPGM("Total time: ", buffer); #if ENABLED(DEBUG_PRINTCOUNTER) - SERIAL_ECHOPAIR(" (", data.printTime); + SERIAL_ECHOPGM(" (", data.printTime); SERIAL_CHAR(')'); #endif elapsed = data.longestPrint; elapsed.toString(buffer); - SERIAL_ECHOPAIR(", Longest job: ", buffer); + SERIAL_ECHOPGM(", Longest job: ", buffer); #if ENABLED(DEBUG_PRINTCOUNTER) - SERIAL_ECHOPAIR(" (", data.longestPrint); + SERIAL_ECHOPGM(" (", data.longestPrint); SERIAL_CHAR(')'); #endif - SERIAL_ECHOPAIR("\n" STR_STATS "Filament used: ", data.filamentUsed / 1000); + SERIAL_ECHOPGM("\n" STR_STATS "Filament used: ", data.filamentUsed / 1000); SERIAL_CHAR('m'); SERIAL_EOL(); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index a4469bb209..16ff166493 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -111,7 +111,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() * If true, move to MAX_X and release the solenoid */ static void dock_sled(const bool stow) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("dock_sled(", stow, ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("dock_sled(", stow, ")"); // Dock sled a bit closer to ensure proper capturing do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET - ((stow) ? 1 : 0)); @@ -274,7 +274,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() * Raise Z to a minimum height to make room for a probe to move */ void Probe::do_z_raise(const float z_raise) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Probe::do_z_raise(", z_raise, ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Probe::do_z_raise(", z_raise, ")"); float z_dest = z_raise; if (offset.z < 0) z_dest -= offset.z; do_z_clearance(z_dest); @@ -367,7 +367,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #if ENABLED(WAIT_FOR_NOZZLE_HEAT) const celsius_t hotendPreheat = hotend_temp > thermalManager.degTargetHotend(0) ? hotend_temp : 0; if (hotendPreheat) { - DEBUG_ECHOPAIR("hotend (", hotendPreheat, ")"); + DEBUG_ECHOPGM("hotend (", hotendPreheat, ")"); thermalManager.setTargetHotend(hotendPreheat, 0); } #elif ENABLED(WAIT_FOR_BED_HEAT) @@ -378,7 +378,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { const celsius_t bedPreheat = bed_temp > thermalManager.degTargetBed() ? bed_temp : 0; if (bedPreheat) { if (hotendPreheat) DEBUG_ECHOPGM(" and "); - DEBUG_ECHOPAIR("bed (", bedPreheat, ")"); + DEBUG_ECHOPGM("bed (", bedPreheat, ")"); thermalManager.setTargetBed(bedPreheat); } #endif @@ -400,7 +400,7 @@ bool Probe::set_deployed(const bool deploy) { if (DEBUGGING(LEVELING)) { DEBUG_POS("Probe::set_deployed", current_position); - DEBUG_ECHOLNPAIR("deploy: ", deploy); + DEBUG_ECHOLNPGM("deploy: ", deploy); } if (endstops.z_probe_enabled == deploy) return false; @@ -629,7 +629,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { const float first_probe_z = current_position.z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("1st Probe Z:", first_probe_z); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("1st Probe Z:", first_probe_z); // Raise to give the probe clearance do_blocking_move_to_z(current_position.z + Z_CLEARANCE_MULTI_PROBE, z_probe_fast_mm_s); @@ -723,7 +723,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { const float z2 = current_position.z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2); // Return a weighted average of the fast and slow probes const float measured_z = (z2 * 3.0 + first_probe_z * 2.0) * 0.2; @@ -751,7 +751,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai DEBUG_SECTION(log_probe, "Probe::probe_at_point", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPAIR( + DEBUG_ECHOLNPGM( "...(", LOGICAL_X_POSITION(rx), ", ", LOGICAL_Y_POSITION(ry), ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_LAST_STOW ? "stow (last)" : raise_after == PROBE_PT_STOW ? "stow" : "none", ", ", verbose_level, @@ -788,7 +788,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai if (stow()) measured_z = NAN; // Error on stow? if (verbose_level > 2) - SERIAL_ECHOLNPAIR("Bed X: ", LOGICAL_X_POSITION(rx), " Y: ", LOGICAL_Y_POSITION(ry), " Z: ", measured_z); + SERIAL_ECHOLNPGM("Bed X: ", LOGICAL_X_POSITION(rx), " Y: ", LOGICAL_Y_POSITION(ry), " Z: ", measured_z); } if (isnan(measured_z)) { @@ -864,7 +864,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif #if ((ENABLED(DELTA) && (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y))) || HAS_CURRENT_HOME(Z)) auto debug_current_on = [](PGM_P const s, const int16_t a, const int16_t b) { - if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); } + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); } }; #endif if (onoff) { diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index 07f714a997..2527292e16 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -58,7 +58,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE cartes.y = a_sin + b_sin + scara_offset.y; // phi /* - DEBUG_ECHOLNPAIR( + DEBUG_ECHOLNPGM( "SCARA FK Angle a=", a, " b=", b, " a_sin=", a_sin, @@ -66,7 +66,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE " b_sin=", b_sin, " b_cos=", b_cos ); - DEBUG_ECHOLNPAIR(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")"); + DEBUG_ECHOLNPGM(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")"); //*/ } @@ -80,13 +80,13 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE else { // MORGAN_SCARA uses a Cartesian XY home position xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; - //DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y); + //DEBUG_ECHOLNPGM_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y); delta = homeposition; forward_kinematics(delta.a, delta.b); current_position[axis] = cartes[axis]; - //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + //DEBUG_ECHOLNPGM_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); update_software_endstops(axis); } } @@ -132,7 +132,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE /* DEBUG_POS("SCARA IK", raw); DEBUG_POS("SCARA IK", delta); - DEBUG_ECHOLNPAIR(" SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Psi=", PSI); + DEBUG_ECHOLNPGM(" SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Psi=", PSI); //*/ } @@ -150,13 +150,13 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE #define SCARA_OFFSET_THETA2 131 // degrees #endif ab_float_t homeposition = { SCARA_OFFSET_THETA1, SCARA_OFFSET_THETA2 }; - //DEBUG_ECHOLNPAIR("homeposition A:", homeposition.a, " B:", homeposition.b); + //DEBUG_ECHOLNPGM("homeposition A:", homeposition.a, " B:", homeposition.b); inverse_kinematics(homeposition); forward_kinematics(delta.a, delta.b); current_position[axis] = cartes[axis]; - //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + //DEBUG_ECHOLNPGM_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); update_software_endstops(axis); } } @@ -172,7 +172,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE /* DEBUG_POS("SCARA IK", raw); DEBUG_POS("SCARA IK", delta); - SERIAL_ECHOLNPAIR(" SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2); + SERIAL_ECHOLNPGM(" SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2); //*/ } @@ -185,13 +185,13 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE current_position.z = Z_HOME_POS; else { xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; - //DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y, SP_Z_LBL, homeposition.z); + //DEBUG_ECHOLNPGM_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y, SP_Z_LBL, homeposition.z); inverse_kinematics(homeposition); forward_kinematics(delta.a, delta.b, delta.c); current_position[axis] = cartes[axis]; - //DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); + //DEBUG_ECHOLNPGM_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); update_software_endstops(axis); } } @@ -289,13 +289,13 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE delta.set(DEGREES(THETA), DEGREES(PHI), DEGREES(PSI)); - //SERIAL_ECHOLNPAIR(" SCARA (x,y,z) ", spos.x , ",", spos.y, ",", spos.z, " Rho=", RHO, " Rho2=", RHO2, " Theta=", THETA, " Phi=", PHI, " Psi=", PSI, " Gamma=", GAMMA); + //SERIAL_ECHOLNPGM(" SCARA (x,y,z) ", spos.x , ",", spos.y, ",", spos.z, " Rho=", RHO, " Rho2=", RHO2, " Theta=", THETA, " Phi=", PHI, " Psi=", PSI, " Gamma=", GAMMA); } #endif void scara_report_positions() { - SERIAL_ECHOLNPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS) + SERIAL_ECHOLNPGM("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS) #if ENABLED(AXEL_TPARA) , " Phi:", planner.get_axis_position_degrees(B_AXIS) , " Psi:", planner.get_axis_position_degrees(C_AXIS) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 017b96cc20..8e4c758854 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2353,7 +2353,7 @@ void MarlinSettings::postprocess() { else if (!validating) { DEBUG_ECHO_START(); DEBUG_ECHO(version); - DEBUG_ECHOLNPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET), " bytes; crc ", (uint32_t)working_crc, ")"); + DEBUG_ECHOLNPGM(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET), " bytes; crc ", (uint32_t)working_crc, ")"); } if (!validating && !eeprom_error) postprocess(); @@ -2380,7 +2380,7 @@ void MarlinSettings::postprocess() { if (ubl.storage_slot >= 0) { load_mesh(ubl.storage_slot); - DEBUG_ECHOLNPAIR("Mesh ", ubl.storage_slot, " loaded from storage."); + DEBUG_ECHOLNPGM("Mesh ", ubl.storage_slot, " loaded from storage."); } else { ubl.reset(); @@ -2436,7 +2436,7 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) inline void ubl_invalid_slot(const int s) { - DEBUG_ECHOLNPAIR("?Invalid slot.\n", s, " mesh slots available."); + DEBUG_ECHOLNPGM("?Invalid slot.\n", s, " mesh slots available."); UNUSED(s); } @@ -2467,7 +2467,7 @@ void MarlinSettings::postprocess() { const int16_t a = calc_num_meshes(); if (!WITHIN(slot, 0, a - 1)) { ubl_invalid_slot(a); - DEBUG_ECHOLNPAIR("E2END=", persistentStore.capacity() - 1, " meshes_end=", meshes_end, " slot=", slot); + DEBUG_ECHOLNPGM("E2END=", persistentStore.capacity() - 1, " meshes_end=", meshes_end, " slot=", slot); DEBUG_EOL(); return; } @@ -2489,7 +2489,7 @@ void MarlinSettings::postprocess() { persistentStore.access_finish(); if (status) SERIAL_ECHOLNPGM("?Unable to save mesh data."); - else DEBUG_ECHOLNPAIR("Mesh saved in slot ", slot); + else DEBUG_ECHOLNPGM("Mesh saved in slot ", slot); #else @@ -2533,7 +2533,7 @@ void MarlinSettings::postprocess() { #endif if (status) SERIAL_ECHOLNPGM("?Unable to load mesh data."); - else DEBUG_ECHOLNPAIR("Mesh loaded from slot ", slot); + else DEBUG_ECHOLNPGM("Mesh loaded from slot ", slot); EEPROM_FINISH(); @@ -3010,8 +3010,8 @@ void MarlinSettings::reset() { #if DISABLED(DISABLE_M503) #define CONFIG_ECHO_START() gcode.report_echo_start(forReplay) - #define CONFIG_ECHO_MSG(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0) - #define CONFIG_ECHO_MSG_P(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P(V); }while(0) + #define CONFIG_ECHO_MSG(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) + #define CONFIG_ECHO_MSG_P(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM_P(V); }while(0) #define CONFIG_ECHO_HEADING(STR) gcode.report_heading(forReplay, PSTR(STR)) void M92_report(const bool echo=true, const int8_t e=-1); @@ -3027,7 +3027,7 @@ void MarlinSettings::reset() { // CONFIG_ECHO_HEADING("Linear Units"); #if ENABLED(INCH_MODE_SUPPORT) - SERIAL_ECHOPAIR(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); + SERIAL_ECHOPGM(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); #else SERIAL_ECHOPGM(" G21 ;"); #endif @@ -3096,7 +3096,7 @@ void MarlinSettings::reset() { LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" G29 S3 I", px, " J", py); + SERIAL_ECHOPGM(" G29 S3 I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(mbl.z_values[px][py]), 5); } } @@ -3121,7 +3121,7 @@ void MarlinSettings::reset() { LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(px, GRID_MAX_POINTS_X) { CONFIG_ECHO_START(); - SERIAL_ECHOPAIR(" G29 W I", px, " J", py); + SERIAL_ECHOPGM(" G29 W I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(z_values[px][py]), 5); } } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index f9245336f3..aea5f88c06 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2845,7 +2845,7 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { #endif void Stepper::report_a_position(const xyz_long_t &pos) { - SERIAL_ECHOLNPAIR_P( + SERIAL_ECHOLNPGM_P( LIST_N(DOUBLE(LINEAR_AXES), TERN(SAYS_A, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, TERN(SAYS_B, PSTR("B:"), SP_Y_LBL), pos.y, @@ -3167,7 +3167,7 @@ void Stepper::report_positions() { #if HAS_MOTOR_CURRENT_SPI - //SERIAL_ECHOLNPAIR("Digipotss current ", current); + //SERIAL_ECHOLNPGM("Digipotss current ", current); const uint8_t digipot_ch[] = DIGIPOT_CHANNELS; set_digipot_value_spi(digipot_ch[driver], current); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 934f734e9c..6be98e90d4 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -394,7 +394,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, void Temperature::report_fan_speed(const uint8_t fan) { if (fan >= FAN_COUNT) return; PORT_REDIRECT(SerialMask::All); - SERIAL_ECHOLNPAIR("M106 P", fan, " S", fan_speed[fan]); + SERIAL_ECHOLNPGM("M106 P", fan, " S", fan_speed[fan]); } #endif @@ -676,7 +676,7 @@ volatile bool Temperature::raw_temps_ready = false; LIMIT(bias, 20, max_pow - 20); d = (bias > max_pow >> 1) ? max_pow - 1 - bias : bias; - SERIAL_ECHOPAIR(STR_BIAS, bias, STR_D_COLON, d, STR_T_MIN, minT, STR_T_MAX, maxT); + SERIAL_ECHOPGM(STR_BIAS, bias, STR_D_COLON, d, STR_T_MIN, minT, STR_T_MAX, maxT); if (cycles > 2) { const float Ku = (4.0f * d) / (float(M_PI) * (maxT - minT) * 0.5f), Tu = float(t_low + t_high) * 0.001f, @@ -687,12 +687,12 @@ volatile bool Temperature::raw_temps_ready = false; tune_pid.Ki = tune_pid.Kp * 2.0f / Tu; tune_pid.Kd = tune_pid.Kp * Tu * df; - SERIAL_ECHOLNPAIR(STR_KU, Ku, STR_TU, Tu); + SERIAL_ECHOLNPGM(STR_KU, Ku, STR_TU, Tu); if (ischamber || isbed) SERIAL_ECHOLNPGM(" No overshoot"); else SERIAL_ECHOLNPGM(STR_CLASSIC_PID); - SERIAL_ECHOLNPAIR(STR_KP, tune_pid.Kp, STR_KI, tune_pid.Ki, STR_KD, tune_pid.Kd); + SERIAL_ECHOLNPGM(STR_KP, tune_pid.Kp, STR_KI, tune_pid.Ki, STR_KD, tune_pid.Kd); } } SHV((bias + d) >> 1); @@ -756,13 +756,13 @@ volatile bool Temperature::raw_temps_ready = false; #if EITHER(PIDTEMPBED, PIDTEMPCHAMBER) PGM_P const estring = GHV(PSTR("chamber"), PSTR("bed"), NUL_STR); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Kp ", tune_pid.Kp); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Ki ", tune_pid.Ki); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPAIR("Kd ", tune_pid.Kd); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Kp ", tune_pid.Kp); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Ki ", tune_pid.Ki); + say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Kd ", tune_pid.Kd); #else - say_default_(); SERIAL_ECHOLNPAIR("Kp ", tune_pid.Kp); - say_default_(); SERIAL_ECHOLNPAIR("Ki ", tune_pid.Ki); - say_default_(); SERIAL_ECHOLNPAIR("Kd ", tune_pid.Kd); + say_default_(); SERIAL_ECHOLNPGM("Kp ", tune_pid.Kp); + say_default_(); SERIAL_ECHOLNPGM("Ki ", tune_pid.Ki); + say_default_(); SERIAL_ECHOLNPGM("Kd ", tune_pid.Kd); #endif auto _set_hotend_pid = [](const uint8_t e, const PID_t &in_pid) { @@ -996,7 +996,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms OPTCODE(HAS_TEMP_BED, case H_BED: SERIAL_ECHOPGM(STR_HEATER_BED); break) default: if (real_heater_id >= 0) - SERIAL_ECHOLNPAIR("E", real_heater_id); + SERIAL_ECHOLNPGM("E", real_heater_id); } SERIAL_EOL(); } @@ -1728,7 +1728,7 @@ void Temperature::manage_heater() { void Temperature::M305_report(const uint8_t t_index, const bool forReplay/*=true*/) { gcode.report_heading_etc(forReplay, PSTR(STR_USER_THERMISTORS)); - SERIAL_ECHOPAIR(" M305 P", AS_DIGIT(t_index)); + SERIAL_ECHOPGM(" M305 P", AS_DIGIT(t_index)); const user_thermistor_t &t = user_thermistor[t_index]; @@ -2535,7 +2535,7 @@ void Temperature::init() { case H_CHAMBER: SERIAL_ECHOPGM("chamber"); break; default: SERIAL_ECHO(heater_id); } - SERIAL_ECHOLNPAIR( + SERIAL_ECHOLNPGM( " ; sizeof(running_temp):", sizeof(running_temp), " ; State:", state, " ; Timer:", timer, " ; Temperature:", current, " ; Target Temp:", target #if HEATER_IDLE_HANDLER @@ -2813,7 +2813,7 @@ void Temperature::disable_all_heaters() { SERIAL_ERROR_START(); SERIAL_ECHOPGM("Temp measurement error! "); #if HAS_MAX31855 - SERIAL_ECHOPAIR("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); + SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); else if (max_tc_temp & 0x2) @@ -2825,7 +2825,7 @@ void Temperature::disable_all_heaters() { max865ref.clearFault(); if (fault_31865) { SERIAL_EOL(); - SERIAL_ECHOLNPAIR("\nMAX31865 Fault: (", fault_31865, ") >>"); + SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); if (fault_31865 & MAX31865_FAULT_LOWTHRESH) @@ -3543,7 +3543,7 @@ void Temperature::isr() { SERIAL_PRINT(t, SFP); #if ENABLED(SHOW_TEMP_ADC_VALUES) // Temperature MAX SPI boards do not have an OVERSAMPLENR defined - SERIAL_ECHOPAIR(" (", TERN(HAS_MAXTC_LIBRARIES, k == 'T', false) ? r : r * RECIPROCAL(OVERSAMPLENR)); + SERIAL_ECHOPGM(" (", TERN(HAS_MAXTC_LIBRARIES, k == 'T', false) ? r : r * RECIPROCAL(OVERSAMPLENR)); SERIAL_CHAR(')'); #endif delay(2); @@ -3576,19 +3576,19 @@ void Temperature::isr() { #if HAS_MULTI_HOTEND HOTEND_LOOP() print_heater_state((heater_id_t)e, degHotend(e), degTargetHotend(e) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(e))); #endif - SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); + SERIAL_ECHOPGM(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED - SERIAL_ECHOPAIR(" B@:", getHeaterPower(H_BED)); + SERIAL_ECHOPGM(" B@:", getHeaterPower(H_BED)); #endif #if HAS_HEATED_CHAMBER - SERIAL_ECHOPAIR(" C@:", getHeaterPower(H_CHAMBER)); + SERIAL_ECHOPGM(" C@:", getHeaterPower(H_CHAMBER)); #endif #if HAS_COOLER - SERIAL_ECHOPAIR(" C@:", getHeaterPower(H_COOLER)); + SERIAL_ECHOPGM(" C@:", getHeaterPower(H_COOLER)); #endif #if HAS_MULTI_HOTEND HOTEND_LOOP() { - SERIAL_ECHOPAIR(" @", e); + SERIAL_ECHOPGM(" @", e); SERIAL_CHAR(':'); SERIAL_ECHO(getHeaterPower((heater_id_t)e)); } @@ -3896,7 +3896,7 @@ void Temperature::isr() { const bool wants_to_cool = isProbeAboveTemp(target_temp), will_wait = !(wants_to_cool && no_wait_for_cooling); if (will_wait) - SERIAL_ECHOLNPAIR("Waiting for probe to ", (wants_to_cool ? PSTR("cool down") : PSTR("heat up")), " to ", target_temp, " degrees."); + SERIAL_ECHOLNPGM("Waiting for probe to ", (wants_to_cool ? PSTR("cool down") : PSTR("heat up")), " to ", target_temp, " degrees."); #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) KEEPALIVE_STATE(NOT_BUSY); diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 8fffb2e640..cb551647d7 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -189,7 +189,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; - DEBUG_ECHOPAIR("(1) Move extruder ", new_tool); + DEBUG_ECHOPGM("(1) Move extruder ", new_tool); DEBUG_POS(" to new extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -199,7 +199,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = grabpos + offsetcompensation; - DEBUG_ECHOPAIR("(2) Couple extruder ", new_tool); + DEBUG_ECHOPGM("(2) Couple extruder ", new_tool); DEBUG_POS(" to new extruder GrabPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -212,7 +212,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; - DEBUG_ECHOPAIR("(3) Move extruder ", new_tool); + DEBUG_ECHOPGM("(3) Move extruder ", new_tool); DEBUG_POS(" back to new extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -222,7 +222,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation; - DEBUG_ECHOPAIR("(4) Move extruder ", new_tool); + DEBUG_ECHOPGM("(4) Move extruder ", new_tool); DEBUG_POS(" close to old extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -232,7 +232,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = mpe_settings.parking_xpos[active_extruder] + offsetcompensation; - DEBUG_ECHOPAIR("(5) Park extruder ", new_tool); + DEBUG_ECHOPGM("(5) Park extruder ", new_tool); DEBUG_POS(" at old extruder ParkPos", current_position); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); @@ -242,7 +242,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = oldx; - DEBUG_ECHOPAIR("(6) Move extruder ", new_tool); + DEBUG_ECHOPGM("(6) Move extruder ", new_tool); DEBUG_POS(" to starting position", current_position); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); @@ -277,9 +277,9 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. if (homed_towards_final_tool) { pe_solenoid_magnet_off(1 - final_tool); - DEBUG_ECHOLNPAIR("Disengage magnet", 1 - final_tool); + DEBUG_ECHOLNPGM("Disengage magnet", 1 - final_tool); pe_solenoid_magnet_on(final_tool); - DEBUG_ECHOLNPAIR("Engage magnet", final_tool); + DEBUG_ECHOLNPGM("Engage magnet", final_tool); parking_extruder_set_parked(false); return false; } @@ -318,7 +318,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. if (!extruder_parked) { current_position.x = parkingposx[active_extruder] + x_offset; - DEBUG_ECHOLNPAIR("(1) Park extruder ", active_extruder); + DEBUG_ECHOLNPGM("(1) Park extruder ", active_extruder); DEBUG_POS("Moving ParkPos", current_position); fast_line_to_current(X_AXIS); @@ -521,7 +521,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = placexpos; - DEBUG_ECHOLNPAIR("(1) Place old tool ", active_extruder); + DEBUG_ECHOLNPGM("(1) Place old tool ", active_extruder); DEBUG_POS("Move X SwitchPos", current_position); fast_line_to_current(X_AXIS); @@ -627,7 +627,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; - SERIAL_ECHOLNPAIR("(1) Place old tool ", active_extruder); + SERIAL_ECHOLNPGM("(1) Place old tool ", active_extruder); DEBUG_POS("Move Y SwitchPos + Security", current_position); fast_line_to_current(Y_AXIS); @@ -759,7 +759,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. // 2. Move to position near active extruder parking DEBUG_SYNCHRONIZE(); - DEBUG_ECHOLNPAIR("(2) Move near active extruder parking", active_extruder); + DEBUG_ECHOLNPGM("(2) Move near active extruder parking", active_extruder); DEBUG_POS("Moving ParkPos", current_position); current_position.set(hoffs.x + placexpos, @@ -769,7 +769,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. // 3. Move gently to park position of active extruder DEBUG_SYNCHRONIZE(); - SERIAL_ECHOLNPAIR("(3) Move gently to park position of active extruder", active_extruder); + SERIAL_ECHOLNPGM("(3) Move gently to park position of active extruder", active_extruder); DEBUG_POS("Moving ParkPos", current_position); current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; @@ -858,7 +858,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. && IsRunning() && !no_move // ...and movement is permitted && (delayed_move_time || current_position.x != xhome) // ...and delayed_move_time is set OR not "already parked"... ) { - DEBUG_ECHOLNPAIR("MoveX to ", xhome); + DEBUG_ECHOLNPGM("MoveX to ", xhome); current_position.x = xhome; line_to_current_position(planner.settings.max_feedrate_mm_s[X_AXIS]); // Park the current head planner.synchronize(); @@ -878,7 +878,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. current_position.x = inactive_extruder_x; // Save the inactive extruder's position (from the old current_position) inactive_extruder_x = destination.x; - DEBUG_ECHOLNPAIR("DXC Full Control curr.x=", current_position.x, " dest.x=", destination.x); + DEBUG_ECHOLNPGM("DXC Full Control curr.x=", current_position.x, " dest.x=", destination.x); break; case DXC_AUTO_PARK_MODE: idex_set_parked(); @@ -890,7 +890,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. // Ensure X axis DIR pertains to the correct carriage stepper.set_directions(); - DEBUG_ECHOLNPAIR("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); + DEBUG_ECHOLNPGM("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); DEBUG_POS("New extruder (parked)", current_position); } @@ -1170,7 +1170,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { (void)check_tool_sensor_stats(active_extruder, true); // The newly-selected extruder XYZ is actually at... - DEBUG_ECHOLNPAIR("Offset Tool XYZ by { ", diff.x, ", ", diff.y, ", ", diff.z, " }"); + DEBUG_ECHOLNPGM("Offset Tool XYZ by { ", diff.x, ", ", diff.y, ", ", diff.z, " }"); current_position += diff; // Tell the planner the new "current position" diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 832cfa405f..9f8aac634b 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -379,7 +379,7 @@ void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=fa // Go to the next segment while (path[++i]) { } - //SERIAL_ECHOLNPAIR("Looking for segment: ", segment); + //SERIAL_ECHOLNPGM("Looking for segment: ", segment); // Find the item, setting the long filename diveDir.rewind(); @@ -399,7 +399,7 @@ void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=fa if (!dir.open(&diveDir, segment, O_READ)) { SERIAL_EOL(); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(STR_SD_CANT_OPEN_SUBDIR, segment); + SERIAL_ECHOPGM(STR_SD_CANT_OPEN_SUBDIR, segment); break; } @@ -475,7 +475,7 @@ void CardReader::manage_media() { uint8_t stat = uint8_t(IS_SD_INSERTED()); if (stat == prev_stat) return; - DEBUG_ECHOLNPAIR("SD: Status changed from ", prev_stat, " to ", stat); + DEBUG_ECHOLNPGM("SD: Status changed from ", prev_stat, " to ", stat); flag.workDirIsRoot = true; // Return to root on mount/release @@ -606,7 +606,7 @@ void CardReader::getAbsFilenameInCWD(char *dst) { } void openFailed(const char * const fname) { - SERIAL_ECHOLNPAIR(STR_SD_OPEN_FILE_FAIL, fname, "."); + SERIAL_ECHOLNPGM(STR_SD_OPEN_FILE_FAIL, fname, "."); } void announceOpen(const uint8_t doing, const char * const path) { @@ -615,7 +615,7 @@ void announceOpen(const uint8_t doing, const char * const path) { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Now "); SERIAL_ECHOPGM_P(doing == 1 ? PSTR("doing") : PSTR("fresh")); - SERIAL_ECHOLNPAIR(" file: ", path); + SERIAL_ECHOLNPGM(" file: ", path); } } @@ -678,7 +678,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ { // Don't remove this block, as the PORT_REDIRECT is a RAII PORT_REDIRECT(SerialMask::All); - SERIAL_ECHOLNPAIR(STR_SD_FILE_OPENED, fname, STR_SD_SIZE, filesize); + SERIAL_ECHOLNPGM(STR_SD_FILE_OPENED, fname, STR_SD_SIZE, filesize); SERIAL_ECHOLNPGM(STR_SD_FILE_SELECTED); } @@ -690,7 +690,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ } inline void echo_write_to_file(const char * const fname) { - SERIAL_ECHOLNPAIR(STR_SD_WRITE_TO_FILE, fname); + SERIAL_ECHOLNPGM(STR_SD_WRITE_TO_FILE, fname); } // @@ -730,7 +730,7 @@ void CardReader::openFileWrite(const char * const path) { bool CardReader::fileExists(const char * const path) { if (!isMounted()) return false; - DEBUG_ECHOLNPAIR("fileExists: ", path); + DEBUG_ECHOLNPGM("fileExists: ", path); // Dive to the file's directory and get the base name SdFile *diveDir = nullptr; @@ -762,21 +762,21 @@ void CardReader::removeFile(const char * const name) { if (!fname) return; #if ENABLED(SDCARD_READONLY) - SERIAL_ECHOLNPAIR("Deletion failed (read-only), File: ", fname, "."); + SERIAL_ECHOLNPGM("Deletion failed (read-only), File: ", fname, "."); #else if (file.remove(itsDirPtr, fname)) { - SERIAL_ECHOLNPAIR("File deleted:", fname); + SERIAL_ECHOLNPGM("File deleted:", fname); sdpos = 0; TERN_(SDCARD_SORT_ALPHA, presort()); } else - SERIAL_ECHOLNPAIR("Deletion failed, File: ", fname, "."); + SERIAL_ECHOLNPGM("Deletion failed, File: ", fname, "."); #endif } void CardReader::report_status() { if (isPrinting()) { - SERIAL_ECHOPAIR(STR_SD_PRINTING_BYTE, sdpos); + SERIAL_ECHOPGM(STR_SD_PRINTING_BYTE, sdpos); SERIAL_CHAR('/'); SERIAL_ECHOLN(filesize); } @@ -924,12 +924,12 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con // Parsing the path string const char *atom_ptr = path; - DEBUG_ECHOLNPAIR(" path = '", path, "'"); + DEBUG_ECHOLNPGM(" path = '", path, "'"); if (path[0] == '/') { // Starting at the root directory? inDirPtr = &root; atom_ptr++; - DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)inDirPtr)); + DEBUG_ECHOLNPGM(" CWD to root: ", hex_address((void*)inDirPtr)); if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else @@ -937,7 +937,7 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con startDirPtr = inDirPtr; - DEBUG_ECHOLNPAIR(" startDirPtr = ", hex_address((void*)startDirPtr)); + DEBUG_ECHOLNPGM(" startDirPtr = ", hex_address((void*)startDirPtr)); while (atom_ptr) { // Find next subdirectory delimiter @@ -954,7 +954,7 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con if (echo) SERIAL_ECHOLN(dosSubdirname); - DEBUG_ECHOLNPAIR(" sub = ", hex_address((void*)sub)); + DEBUG_ECHOLNPGM(" sub = ", hex_address((void*)sub)); // Open inDirPtr (closing first) sub->close(); @@ -966,24 +966,24 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con // Close inDirPtr if not at starting-point if (inDirPtr != startDirPtr) { - DEBUG_ECHOLNPAIR(" closing inDirPtr: ", hex_address((void*)inDirPtr)); + DEBUG_ECHOLNPGM(" closing inDirPtr: ", hex_address((void*)inDirPtr)); inDirPtr->close(); } // inDirPtr now subDir inDirPtr = sub; - DEBUG_ECHOLNPAIR(" inDirPtr = sub: ", hex_address((void*)inDirPtr)); + DEBUG_ECHOLNPGM(" inDirPtr = sub: ", hex_address((void*)inDirPtr)); // Update workDirParents and workDirDepth if (update_cwd) { - DEBUG_ECHOLNPAIR(" update_cwd"); + DEBUG_ECHOLNPGM(" update_cwd"); if (workDirDepth < MAX_DIR_DEPTH) workDirParents[workDirDepth++] = *inDirPtr; } // Point sub at the other scratch object sub = (inDirPtr != &newDir1) ? &newDir1 : &newDir2; - DEBUG_ECHOLNPAIR(" swapping sub = ", hex_address((void*)sub)); + DEBUG_ECHOLNPGM(" swapping sub = ", hex_address((void*)sub)); // Next path atom address atom_ptr = name_end + 1; @@ -991,12 +991,12 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, con if (update_cwd) { workDir = *inDirPtr; - DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)inDirPtr)); + DEBUG_ECHOLNPGM(" final workDir = ", hex_address((void*)inDirPtr)); flag.workDirIsRoot = (workDirDepth == 0); TERN_(SDCARD_SORT_ALPHA, presort()); } - DEBUG_ECHOLNPAIR(" returning string ", atom_ptr ?: "nullptr"); + DEBUG_ECHOLNPGM(" returning string ", atom_ptr ?: "nullptr"); return atom_ptr; } @@ -1138,9 +1138,9 @@ void CardReader::cdroot() { selectFileByIndex(i); SET_SORTNAME(i); SET_SORTSHORT(i); - // char out[30]; - // sprintf_P(out, PSTR("---- %i %s %s"), i, flag.filenameIsDir ? "D" : " ", sortnames[i]); - // SERIAL_ECHOLN(out); + //char out[30]; + //sprintf_P(out, PSTR("---- %i %s %s"), i, flag.filenameIsDir ? "D" : " ", sortnames[i]); + //SERIAL_ECHOLN(out); #if HAS_FOLDER_SORTING const uint16_t bit = i & 0x07, ind = i >> 3; if (bit == 0) isDir[ind] = 0x00; diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index 1975418415..5991a9fb83 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -34,9 +34,9 @@ #define USB_STARTUP_DELAY 0 // uncomment to get 'printf' console debugging. NOT FOR UNO! -//#define HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPAIR("UHS:",s);} -//#define BS_HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPAIR("UHS:",s);} -//#define MAX_HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPAIR("UHS:",s);} +//#define HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPGM("UHS:",s);} +//#define BS_HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPGM("UHS:",s);} +//#define MAX_HOST_DEBUG(...) {char s[255]; sprintf(s,__VA_ARGS__); SERIAL_ECHOLNPGM("UHS:",s);} #if ENABLED(USB_FLASH_DRIVE_SUPPORT) @@ -170,7 +170,7 @@ void DiskIODriver_USBFlash::idle() { UHS_USB_DEBUG(CONFIGURING_DONE); UHS_USB_DEBUG(RUNNING); default: - SERIAL_ECHOLNPAIR("UHS_USB_HOST_STATE: ", task_state); + SERIAL_ECHOLNPGM("UHS_USB_HOST_STATE: ", task_state); break; } } @@ -273,14 +273,14 @@ bool DiskIODriver_USBFlash::init(const uint8_t, const pin_t) { #if USB_DEBUG >= 1 const uint32_t sectorSize = bulk.GetSectorSize(0); if (sectorSize != 512) { - SERIAL_ECHOLNPAIR("Expecting sector size of 512. Got: ", sectorSize); + SERIAL_ECHOLNPGM("Expecting sector size of 512. Got: ", sectorSize); return false; } #endif #if USB_DEBUG >= 3 lun0_capacity = bulk.GetCapacity(0); - SERIAL_ECHOLNPAIR("LUN Capacity (in blocks): ", lun0_capacity); + SERIAL_ECHOLNPGM("LUN Capacity (in blocks): ", lun0_capacity); #endif return true; } @@ -299,11 +299,11 @@ bool DiskIODriver_USBFlash::readBlock(uint32_t block, uint8_t *dst) { if (!isInserted()) return false; #if USB_DEBUG >= 3 if (block >= lun0_capacity) { - SERIAL_ECHOLNPAIR("Attempt to read past end of LUN: ", block); + SERIAL_ECHOLNPGM("Attempt to read past end of LUN: ", block); return false; } #if USB_DEBUG >= 4 - SERIAL_ECHOLNPAIR("Read block ", block); + SERIAL_ECHOLNPGM("Read block ", block); #endif #endif return bulk.Read(0, block, 512, 1, dst) == 0; @@ -313,11 +313,11 @@ bool DiskIODriver_USBFlash::writeBlock(uint32_t block, const uint8_t *src) { if (!isInserted()) return false; #if USB_DEBUG >= 3 if (block >= lun0_capacity) { - SERIAL_ECHOLNPAIR("Attempt to write past end of LUN: ", block); + SERIAL_ECHOLNPGM("Attempt to write past end of LUN: ", block); return false; } #if USB_DEBUG >= 4 - SERIAL_ECHOLNPAIR("Write block ", block); + SERIAL_ECHOLNPGM("Write block ", block); #endif #endif return bulk.Write(0, block, 512, 1, src) == 0; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 4ee206bc32..a1a3b7d50e 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -121,7 +121,7 @@ bool MAX3421e::start() { const uint8_t revision = regRd(rREVISION); if (revision == 0x00 || revision == 0xFF) { - SERIAL_ECHOLNPAIR("Revision register appears incorrect on MAX3421e initialization. Got ", revision); + SERIAL_ECHOLNPGM("Revision register appears incorrect on MAX3421e initialization. Got ", revision); return false; } diff --git a/docs/Serial.md b/docs/Serial.md index f51b902723..ff8f84ef99 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -58,10 +58,10 @@ The following macros are defined (in `serial.h`) to output data to the serial po | `SERIAL_ECHO` | Any basic type is supported (`char`, `uint8_t`, `int16_t`, `int32_t`, `float`, `long`, `const char*`, ...). | For a numeric type it prints the number in decimal. A string is output as a string. | `uint8_t a = 123; SERIAL_ECHO(a); SERIAL_CHAR(' '); SERIAL_ECHO(' '); ` | `123 32` | | `SERIAL_ECHOLN` | Same as `SERIAL_ECHO` | Do `SERIAL_ECHO`, adding a newline | `int a = 456; SERIAL_ECHOLN(a);` | `456\n` | | `SERIAL_ECHO_F` | `float` or `double` | Print a decimal value with a given precision (default 2) | `float a = 3.1415; SERIAL_ECHO_F(a); SERIAL_CHAR(' '); SERIAL_ECHO_F(a, 4);` | `3.14 3.1415`| -| `SERIAL_ECHOPAIR` | String / Value pairs | Print a series of string literals and values alternately | `SERIAL_ECHOPAIR("Bob", 34);` | `Bob34` | -| `SERIAL_ECHOLNPAIR` | Same as `SERIAL_ECHOPAIR` | Do `SERIAL_ECHOPAIR`, adding a newline | `SERIAL_ECHOPAIR("Alice", 56);` | `alice56` | -| `SERIAL_ECHOPAIR_P` | Like `SERIAL_ECHOPAIR` but takes PGM strings | Print a series of PGM strings and values alternately | `SERIAL_ECHOPAIR_P(GET_TEXT(MSG_HELLO), 123);` | `Hello123` | -| `SERIAL_ECHOLNPAIR_P` | Same as `SERIAL_ECHOPAIR_P` | Do `SERIAL_ECHOPAIR_P`, adding a newline | `SERIAL_ECHOLNPAIR_P(PSTR("Alice"), 78);` | `alice78\n` | +| `SERIAL_ECHOPGM` | String / Value pairs | Print a series of string literals and values alternately | `SERIAL_ECHOPGM("Bob", 34);` | `Bob34` | +| `SERIAL_ECHOLNPGM` | Same as `SERIAL_ECHOPGM` | Do `SERIAL_ECHOPGM`, adding a newline | `SERIAL_ECHOPGM("Alice", 56);` | `alice56` | +| `SERIAL_ECHOPGM_P` | Like `SERIAL_ECHOPGM` but takes PGM strings | Print a series of PGM strings and values alternately | `SERIAL_ECHOPGM_P(GET_TEXT(MSG_HELLO), 123);` | `Hello123` | +| `SERIAL_ECHOLNPGM_P` | Same as `SERIAL_ECHOPGM_P` | Do `SERIAL_ECHOPGM_P`, adding a newline | `SERIAL_ECHOLNPGM_P(PSTR("Alice"), 78);` | `alice78\n` | | `SERIAL_ECHOLIST` | String literal, values | Print a string literal and a list of values | `SERIAL_ECHOLIST("Key ", 1, 2, 3);` | `Key 1, 2, 3` | | `SERIAL_ECHO_START` | None | Prefix an echo line | `SERIAL_ECHO_START();` | `echo:` | | `SERIAL_ECHO_MSG` | Same as `SERIAL_ECHOLN_PAIR` | Print a full echo line | `SERIAL_ECHO_MSG("Count is ", count);` | `echo:Count is 3` | From 392a4a6f85bea8470ee291eedcf85d16ce071e52 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Thu, 9 Sep 2021 16:40:10 -0500 Subject: [PATCH 0651/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix,=20improve=20E3V2?= =?UTF-8?q?=20Enhanced=20UI=20(#22733)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 158 ++++++++++++---------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 7 +- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp | 12 +- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 9 +- Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 6 +- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 35 ++--- 7 files changed, 126 insertions(+), 103 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index c45995aba5..61a9ea2c9a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -421,7 +421,7 @@ #endif #endif -#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) +#if EITHER(DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) #define HAS_LCD_BRIGHTNESS 1 #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index edcf199182..9e43e4198e 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -163,10 +163,10 @@ static bool sdprint = false; #if ENABLED(PAUSE_HEAT) #if HAS_HOTEND - uint16_t resume_hotend_temp = 0; + celsius_t resume_hotend_temp = 0; #endif #if HAS_HEATED_BED - uint16_t resume_bed_temp = 0; + celsius_t resume_bed_temp = 0; #endif #if HAS_FAN uint16_t resume_fan = 0; @@ -708,7 +708,7 @@ void _update_axis_value(const AxisEnum axis, const uint16_t x, const uint16_t y, else if (blink && draw_empty) DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" ")); else - DWINUI::Draw_Signed_Float(HMI_data.Coordinate_Color, HMI_data.Background_Color, 3, 1, x, y, p * 10); + DWINUI::Draw_Signed_Float(HMI_data.Coordinate_Color, HMI_data.Background_Color, 3, 1, x, y, p); } } @@ -805,7 +805,7 @@ void update_variable() { static float _offset = 0; if (BABY_Z_VAR != _offset) { _offset = BABY_Z_VAR; - DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, _offset * 100); + DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, _offset); } _draw_xyz_position(false); @@ -1030,14 +1030,7 @@ void Draw_Status_Area(const bool with_update) { DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); #endif - if (BABY_Z_VAR < 0) { - DWINUI::Draw_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 207, 417, -BABY_Z_VAR * 100); - DWINUI::Draw_String(HMI_data.Indicator_Color, 205, 419, F("-")); - } - else { - DWINUI::Draw_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 207, 417, BABY_Z_VAR * 100); - DWINUI::Draw_String(HMI_data.Indicator_Color, 205, 419, F(" ")); - } + DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, BABY_Z_VAR); DWIN_Draw_Rectangle(1, HMI_data.SplitLine_Color, 0, 449, DWIN_WIDTH, 451); @@ -1690,7 +1683,7 @@ void DWIN_CompletedLeveling() { HMI_ReturnScreen(); } void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { char msg[33] = ""; char str_1[6] = ""; - sprintf_P(msg, PSTR(S_FMT " %i/%i Z=%s"), GET_TEXT(MSG_PROBING_MESH), xpos, ypos, + sprintf_P(msg, PSTR(S_FMT " %i/%i Z=%s"), GET_TEXT(MSG_PROBING_POINT), xpos, ypos, dtostrf(zval, 1, 2, str_1)); ui.set_status(msg); } @@ -1791,6 +1784,7 @@ void DWIN_Print_Started(const bool sd) { sdprint = card.isPrinting() || sd; _percent_done = 0; _remain_time = 0; + HMI_flag.print_finish = false; Goto_PrintProcess(); } @@ -1846,18 +1840,20 @@ void DWIN_SetDataDefaults() { TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); + TERN_(PREVENT_COLD_EXTRUSION, HMI_data.ExtMinT = EXTRUDE_MINTEMP); } void DWIN_StoreSettings(char *buff) { - memcpy(buff, &HMI_data, min(sizeof(HMI_data), eeprom_data_size)); + memcpy(buff, &HMI_data, _MIN(sizeof(HMI_data), eeprom_data_size)); } void DWIN_LoadSettings(const char *buff) { - memcpy(&HMI_data, buff, min(sizeof(HMI_data), eeprom_data_size)); + memcpy(&HMI_data, buff, _MIN(sizeof(HMI_data), eeprom_data_size)); dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); if (HMI_data.Text_Color == HMI_data.Background_Color) DWIN_SetColorDefaults(); DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); + feedrate_percentage = 100; } void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { @@ -1970,11 +1966,11 @@ void DWIN_LockScreen(const bool flag) { // lo: low limit // hi: high limit // dp: decimal places, 0 for integers -// val: value +// val: value / scaled value // LiveUpdate: live update function when the encoder changes // Apply: update function when the encoder is pressed void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - last_checkkey = checkkey; + last_checkkey = Menu; checkkey = process; HMI_value.MinValue = lo; HMI_value.MaxValue = hi; @@ -1985,18 +1981,29 @@ void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, EncoderRate.enabled = true; } -// Generic onclick event for set values (dp = 0: integer, dp > 0: float) +// Generic onclick event for integer values // process: process id HMI destiny // lo: scaled low limit // hi: scaled high limit -// dp: decimal places, 0 for integers -// val: scaled value +// val: value // LiveUpdate: live update function when the encoder changes // Apply: update function when the encoder is pressed -void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetOnClick(process, lo, hi, dp, val, Apply, LiveUpdate); - dp ? DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value) - : Draw_Menu_IntValue(HMI_data.Selected_Color, CurrentMenu->line(), 4, HMI_value.Value); +void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetOnClick(process, lo, hi, 0, val, Apply, LiveUpdate); + Draw_Menu_IntValue(HMI_data.Selected_Color, CurrentMenu->line(), 4, HMI_value.Value); +} + +// Generic onclick event for float values +// process: process id HMI destiny +// lo: scaled low limit +// hi: scaled high limit +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + const int32_t value = round(val * POW(10, dp)); + SetOnClick(process, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), val); } // Generic onclick event for integer values @@ -2005,8 +2012,8 @@ void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_ // val: value // LiveUpdate: live update function when the encoder changes // Apply: update function when the encoder is pressed -void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetValueOnClick(SetInt, lo, hi, 0, val, Apply, LiveUpdate); +inline void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetValueOnClick(SetInt, lo, hi, val, Apply, LiveUpdate); } // Generic onclick event for set pointer to 16 bit uinteger values @@ -2017,7 +2024,7 @@ void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void ( void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; const int32_t value = *HMI_value.P_Int; - SetValueOnClick(SetPInt, lo, hi, 0, value, Apply, LiveUpdate); + SetValueOnClick(SetPInt, lo, hi, value, Apply, LiveUpdate); } // Generic onclick event for float values @@ -2026,8 +2033,8 @@ void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() = nullpt // hi: high limit // dp: decimal places // val: value -void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetValueOnClick(SetFloat, lo * POW(10, dp), hi * POW(10, dp), dp, val * POW(10, dp), Apply, LiveUpdate); +inline void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { + SetValueOnClick(SetFloat, lo, hi, dp, val, Apply, LiveUpdate); } // Generic onclick event for set pointer to float values @@ -2037,8 +2044,7 @@ void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val // Apply: update function when the encoder is pressed void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; - const int32_t value = *HMI_value.P_Float * POW(10, dp); - SetValueOnClick(SetPFloat, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); + SetValueOnClick(SetPFloat, lo, hi, dp, *HMI_value.P_Float, Apply, LiveUpdate); } #if ENABLED(EEPROM_SETTINGS) @@ -2148,7 +2154,7 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS #if HAS_HOTEND void SetMoveE() { - #ifdef PREVENT_COLD_EXTRUSION + #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(0)) { Popup_Window_ETempTooLow(); return; @@ -2162,8 +2168,14 @@ void SetMoveZto0() { char cmd[48] = ""; char str_1[5] = "", str_2[5] = ""; sprintf_P(cmd, PSTR("G28OXY\nG28Z\nG0X%sY%sF5000\nG0Z0F300"), - dtostrf(X_CENTER, 1, 1, str_1), - dtostrf(Y_CENTER, 1, 1, str_2)); + #if ENABLED(MESH_BED_LEVELING) + dtostrf(0, 1, 1, str_1), + dtostrf(0, 1, 1, str_2) + #else + dtostrf(X_CENTER, 1, 1, str_1), + dtostrf(Y_CENTER, 1, 1, str_2) + #endif + ); gcode.process_subcommands_now_P(cmd); planner.synchronize(); ui.set_status_P(PSTR("Now adjust Z Offset")); @@ -2175,7 +2187,8 @@ void SetPID(celsius_t t, heater_id_t h) { char str_1[5] = "", str_2[5] = ""; sprintf_P(cmd, PSTR("G28OXY\nG0Z5F300\nG0X%sY%sF5000\nM84"), dtostrf(X_CENTER, 1, 1, str_1), - dtostrf(Y_CENTER, 1, 1, str_2)); + dtostrf(Y_CENTER, 1, 1, str_2) + ); gcode.process_subcommands_now_P(cmd); planner.synchronize(); thermalManager.PID_autotune(t, h, HMI_data.PidCycles, true); @@ -2217,6 +2230,7 @@ void Goto_LockScreen() { #if HAS_BED_PROBE void SetProbeOffsetX() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } void SetProbeOffsetY() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } + void SetProbeOffsetZ() { SetPFloatOnClick(-10, 10, 2); } void ProbeTest() { ui.set_status_P(GET_TEXT(MSG_M48_TEST)); queue.inject_P(PSTR("G28O\nM48 P10")); @@ -2250,24 +2264,24 @@ void RestoreDefaultsColors() { void SelColor() { HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; - HMI_value.Color[2] = GetRColor(*HMI_value.P_Int); // Red + HMI_value.Color[0] = GetRColor(*HMI_value.P_Int); // Red HMI_value.Color[1] = GetGColor(*HMI_value.P_Int); // Green - HMI_value.Color[0] = GetBColor(*HMI_value.P_Int); // Blue + HMI_value.Color[2] = GetBColor(*HMI_value.P_Int); // Blue Draw_GetColor_Menu(); } void LiveRGBColor() { HMI_value.Color[CurrentMenu->line() - 2] = HMI_value.Value; - uint16_t color = RGB(HMI_value.Color[2], HMI_value.Color[1], HMI_value.Color[0]); + uint16_t color = RGB(HMI_value.Color[0], HMI_value.Color[1], HMI_value.Color[2]); DWIN_Draw_Rectangle(1, color, 20, 315, DWIN_WIDTH - 20, 335); } void SetRGBColor() { - const uint8_t line = CurrentMenu->line() - 2; - SetIntOnClick(0, (line == 1) ? 63 : 31, HMI_value.Color[CurrentMenu->SelectedItem()->icon], nullptr, LiveRGBColor); + const uint8_t color = CurrentMenu->SelectedItem()->icon; + SetIntOnClick(0, (color == 1) ? 63 : 31, HMI_value.Color[color], nullptr, LiveRGBColor); } void DWIN_ApplyColor() { - *HMI_value.P_Int = RGB(HMI_value.Color[2], HMI_value.Color[1], HMI_value.Color[0]); + *HMI_value.P_Int = RGB(HMI_value.Color[0], HMI_value.Color[1], HMI_value.Color[2]); DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); Draw_Status_Area(false); Draw_SelectColors_Menu(); @@ -2278,7 +2292,7 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } #if HAS_HOTEND void ApplyHotendTemp() { thermalManager.setTargetHotend(HMI_value.Value, 0); } - void SetHotendTemp() { SetIntOnClick(HEATER_0_MINTEMP, HEATER_0_MAXTEMP, thermalManager.degTargetHotend(0), ApplyHotendTemp); } + void SetHotendTemp() { SetIntOnClick(MIN_ETEMP, MAX_ETEMP, thermalManager.degTargetHotend(0), ApplyHotendTemp); } #endif #if HAS_HEATED_BED @@ -2384,11 +2398,19 @@ void LevBedC () { LevBed(4); } gcode.process_subcommands_now_P(PSTR("G28 XYO\nG28 Z\nM211 S0\nG29S1")); planner.synchronize(); #ifdef MANUAL_PROBE_START_Z - MMeshMoveZItem->Draw(CurrentMenu->line(MMeshMoveZItem->pos)); + const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, 2, VALX - 2 * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); #endif } - void SetMMeshMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMove);} + void LiveMeshMoveZ() { + *HMI_value.P_Float = HMI_value.Value / POW(10, 2); + if (!planner.is_full()) { + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS)); + } + } + void SetMMeshMoveZ() { SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMeshMoveZ);} void ManualMeshContinue(){ gcode.process_subcommands_now_P(PSTR("G29S2")); @@ -2496,7 +2518,7 @@ void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line) { void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value) { onDrawMenuItem(menuitem, line); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), value * POW(10, dp)); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), value); } void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { @@ -2507,8 +2529,7 @@ void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line) { const float value = *(float*)static_cast(menuitem)->value; - const int8_t dp = 2; - onDrawFloatMenu(menuitem, line, dp, value); + onDrawFloatMenu(menuitem, line, 2, value); } void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked) { @@ -2643,9 +2664,9 @@ void onDrawGetColorItem(MenuItemClass* menuitem, int8_t line) { const uint8_t i = menuitem->icon; uint16_t color; switch (i) { - case 0: color = RGB(0, 0, 31); break; - case 1: color = RGB(0, 63, 0); break; - case 2: color = RGB(31, 0, 0); break; + case 0: color = RGB(31, 0, 0); break; // Red + case 1: color = RGB(0, 63, 0); break; // Green + case 2: color = RGB(0, 0, 31); break; // Blue default: color = 0; break; } DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); @@ -3002,12 +3023,12 @@ int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); checkkey = last_checkkey; return 2; } LIMIT(HMI_value.Value, lo, hi); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); return 1; } return 0; @@ -3182,10 +3203,11 @@ void Draw_Move_Menu() { if (CurrentMenu != ProbeSetMenu) { CurrentMenu = ProbeSetMenu; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG - DWINUI::MenuItemsPrepare(4); + DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); + ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); ADDMENUITEM(ICON_ProbeTest, GET_TEXT(MSG_M48_TEST), onDrawMenuItem, ProbeTest); } CurrentMenu->Draw(); @@ -3203,7 +3225,7 @@ void Draw_Move_Menu() { ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); TERN_(HAS_FILAMENT_SENSOR, ADDMENUITEM(ICON_Runout, GET_TEXT(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable)); TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance())); - TERN_(PREVENT_COLD_EXTRUSION, ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &thermalManager.extrude_min_temp)); + TERN_(PREVENT_COLD_EXTRUSION, ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT)); TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilLoad, GET_TEXT(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length)); TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length)); } @@ -3250,9 +3272,9 @@ void Draw_GetColor_Menu() { DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); ADDMENUITEM(ICON_Cancel, GET_TEXT(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); - ADDMENUITEM(0, "Blue", onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(0, "Red", onDrawGetColorItem, SetRGBColor); ADDMENUITEM(1, "Green", onDrawGetColorItem, SetRGBColor); - ADDMENUITEM(2, "Red", onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(2, "Blue", onDrawGetColorItem, SetRGBColor); } CurrentMenu->Draw(); DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); @@ -3270,16 +3292,12 @@ void Draw_Tune_Menu() { TERN_(HAS_HOTEND, HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target)); TERN_(HAS_HEATED_BED, BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target)); TERN_(HAS_FAN, FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0])); - #if HAS_ZOFFSET_ITEM - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); - #else - ADDMENUITEM(ICON_SetHome, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); - #endif + #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament)); - ADDMENUITEM(ICON_Lock, PSTR("Lock Screen"), onDrawMenuItem, Goto_LockScreen); + ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); TERN_(HAS_LCD_BRIGHTNESS, ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness)); } CurrentMenu->Draw(); @@ -3300,7 +3318,6 @@ void Draw_Motion_Menu() { ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } CurrentMenu->Draw(); - DWIN_StatusChanged(nullptr); } #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -3476,9 +3493,9 @@ void Draw_Steps_Menu() { DWINUI::MenuItemsPrepare(8); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); @@ -3497,9 +3514,9 @@ void Draw_Steps_Menu() { DWINUI::MenuItemsPrepare(8); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); - ADDMENUITEM_P(ICON_PIDValue, F(STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); + ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); @@ -3522,6 +3539,7 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } CurrentMenu->Draw(); + if (!axis_is_trusted(Z_AXIS)) ui.set_status_P(PSTR("WARNING: Z position is unknow, move Z to home")); } #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 365ac9ed4b..ee83f9ad7c 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -20,11 +20,6 @@ */ #pragma once -/** - * DWIN by Creality3D - * Enhanced implementation by Miguel A. Risco-Castillo - */ - #include "../../../inc/MarlinConfigPre.h" #include "dwinui.h" #include "rotary_encoder.h" @@ -130,7 +125,7 @@ typedef struct { #ifdef PREHEAT_1_TEMP_BED int16_t BedPidT = PREHEAT_1_TEMP_BED; #endif - TERN_(PREVENT_COLD_EXTRUSION, uint16_t ExtMinT = EXTRUDE_MINTEMP); + TERN_(PREVENT_COLD_EXTRUSION, int16_t ExtMinT = EXTRUDE_MINTEMP); } HMI_data_t; typedef struct { diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp index 99ee74732e..b9246523ce 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp @@ -22,8 +22,8 @@ /******************************************************************************** * @file lcd/e3v2/enhanced/dwin_lcd.cpp * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo - * @date 2021/08/29 - * @version 2.1.1 + * @date 2021/09/08 + * @version 2.2.1 * @brief DWIN screen control functions ********************************************************************************/ @@ -260,7 +260,7 @@ void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color // x/y: Upper-left coordinate // value: Integer value void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { size_t i = 0; DWIN_Byte(i, 0x14); // Bit 7: bshow @@ -319,6 +319,12 @@ void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_ DWIN_Long(i, value); DWIN_Send(i); } +// value: positive float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + const long val = round(value * POW(10, fNum)); + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); +} /*---------------------------------------- Picture related functions ----------------------------------------*/ diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h index 71e66301b4..c66416a7ed 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -22,8 +22,8 @@ /******************************************************************************** * @file lcd/e3v2/enhanced/dwin_lcd.h * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo - * @date 2021/08/29 - * @version 2.1.1 + * @date 2021/08/09 + * @version 2.2.1 * @brief DWIN screen control functions ********************************************************************************/ @@ -157,7 +157,7 @@ inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t // x/y: Upper-left coordinate // value: Integer value void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value); // Draw a positive floating point number // bShow: true=display background color; false=don't display background color @@ -172,6 +172,9 @@ void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t // value: Scaled positive float value void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); +// value: positive float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); /*---------------------------------------- Picture related functions ----------------------------------------*/ diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index db08242183..85353bed28 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -1,8 +1,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Version: 3.6.3 + * Date: 2021/08/09 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as @@ -185,7 +185,7 @@ void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rli // fNum: Number of decimal digits // x/y: Upper-left point // value: Float value -void DWINUI::Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { +void DWINUI::Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { if (value < 0) { DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, -value); DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, F("-")); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index 0aec187049..1ec51bec22 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -1,8 +1,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Version: 3.6.3 + * Date: 2021/08/09 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as @@ -152,6 +152,7 @@ #define ICON_PIDValue ICON_Contact #define ICON_ProbeOffsetX ICON_StepX #define ICON_ProbeOffsetY ICON_StepY +#define ICON_ProbeOffsetZ ICON_StepZ #define ICON_ProbeSet ICON_SetEndTemp #define ICON_ProbeTest ICON_SetEndTemp #define ICON_Pwrlossr ICON_Motion @@ -392,14 +393,14 @@ namespace DWINUI { // iNum: Number of digits // x/y: Upper-left coordinate // value: Integer value - inline void Draw_Int(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + inline void Draw_Int(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { DWIN_Draw_IntValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, x, y, value); } - inline void Draw_Int(uint8_t iNum, uint16_t value) { + inline void Draw_Int(uint8_t iNum, long value) { DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); MoveBy(iNum * Get_font_width(font), 0); } - inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { + inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, x, y, value); } inline void Draw_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { @@ -423,23 +424,23 @@ namespace DWINUI { // fNum: Number of decimal digits // x/y: Upper-left point // value: Float value - inline void Draw_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); } - inline void Draw_Float(uint8_t iNum, uint8_t fNum, long value) { + inline void Draw_Float(uint8_t iNum, uint8_t fNum, float value) { DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); } - inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); } - inline void Draw_Float(uint16_t color, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Float(uint16_t color, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(false, true, 0, font, color, backcolor, iNum, fNum, x, y, value); } - inline void Draw_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); } - inline void Draw_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); } @@ -453,21 +454,21 @@ namespace DWINUI { // fNum: Number of decimal digits // x/y: Upper-left point // value: Float value - void Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, long value) { + void Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); + inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, float value) { Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); } - inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); } - inline void Draw_Signed_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Signed_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { Draw_Signed_Float(false, true, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); } - inline void Draw_Signed_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Signed_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { Draw_Signed_Float(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); } - inline void Draw_Signed_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + inline void Draw_Signed_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { Draw_Signed_Float(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); } From bcfaf3990a0e7eaac89ae8e075bb089c7dac1b38 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 10 Sep 2021 01:02:43 +0000 Subject: [PATCH 0652/2168] [cron] Bump distribution date (2021-09-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 54926116e7..5994181f0a 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-09" +//#define STRING_DISTRIBUTION_DATE "2021-09-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 427343637a..12c8b6b3ad 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 "2021-09-09" + #define STRING_DISTRIBUTION_DATE "2021-09-10" #endif /** From 67d82ff228789408f7f32e6c9af3108c989c0c90 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 10 Sep 2021 18:49:57 -0500 Subject: [PATCH 0653/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20JyersU?= =?UTF-8?q?I?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.h | 4 ---- Marlin/src/gcode/gcode.h | 4 ---- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 7 +++++-- 3 files changed, 5 insertions(+), 10 deletions(-) diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 6147d43f17..6428b77398 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -23,10 +23,6 @@ #include "inc/MarlinConfig.h" -#ifdef DEBUG_GCODE_PARSER - #include "gcode/parser.h" -#endif - #include #include #include diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index cd190387b0..16cee3481d 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -21,10 +21,6 @@ */ #pragma once -/** - * gcode.h - Temporary container for all gcode handlers - */ - /** * ----------------- * G-Codes in Marlin diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index e41e51bee4..2a2df68b1d 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -33,6 +33,7 @@ #include "../../marlinui.h" #include "../../../MarlinCore.h" +#include "../../../gcode/gcode.h" #include "../../../module/temperature.h" #include "../../../module/planner.h" #include "../../../module/settings.h" @@ -180,6 +181,7 @@ bool probe_deployed = false; CrealityDWINClass CrealityDWIN; #if HAS_MESH + struct Mesh_Settings { bool viewer_asymmetric_range = false; bool viewer_print_value = false; @@ -362,7 +364,7 @@ CrealityDWINClass CrealityDWIN; if (v_min > 3e+10F) v_min = 0.0000001; if (v_max > 3e+10F) v_max = 0.0000001; if (range > 3e+10F) range = 0.0000001; - char msg[32]; + char msg[46]; if (viewer_asymmetric_range) { dtostrf(-v_min, 1, 3, str_1); dtostrf( v_max, 1, 3, str_2); @@ -378,7 +380,8 @@ CrealityDWINClass CrealityDWIN; }; Mesh_Settings mesh_conf; -#endif + +#endif // HAS_MESH /* General Display Functions */ From ce6d6225019640afbdb0a9dc6db26a4e03ca4c4f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 10 Sep 2021 19:47:03 -0500 Subject: [PATCH 0654/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20TOUCH=5FUI=5FFTD?= =?UTF-8?q?I=5FEVE=20warnings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/debug_out.h | 1 - .../lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 4 ++++ .../ftdi_eve_lib/extended/text_ellipsis.cpp | 5 ++--- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 2 +- .../ftdi_eve_lib/extended/unicode/unicode.h | 6 +++--- .../extui/ftdi_eve_touch_ui/generic/string_format.cpp | 10 +++++++--- 6 files changed, 17 insertions(+), 11 deletions(-) diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index 3187e03254..4e30a5306e 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -56,7 +56,6 @@ #include "debug_section.h" #define DEBUG_SECTION(N,S,D) SectionLog N(PSTR(S),D) - #define DEBUG_ECHOPGM_P(P) SERIAL_ECHOPGM_P(P) #define DEBUG_ECHO_START SERIAL_ECHO_START #define DEBUG_ERROR_START SERIAL_ERROR_START #define DEBUG_CHAR SERIAL_CHAR diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 2b7eca0cce..4e11c73226 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -296,3 +296,7 @@ #endif #endif // !__MARLIN_FIRMWARE__ + +#ifndef SD_SPI_SPEED + #define SD_SPI_SPEED SPI_FULL_SPEED +#endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index 4262dd1155..463d5ad316 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -34,7 +34,6 @@ namespace FTDI { #define CHAR_WIDTH(c) use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c] #else #define CHAR_WIDTH(c) utf8_fm.get_char_width(c) - constexpr bool use_utf8 = false; #endif FontMetrics utf8_fm(font); CLCD::FontMetrics clcd_fm; @@ -46,12 +45,12 @@ namespace FTDI { // split and still allow the ellipsis to fit. int16_t lineWidth = 0; char *breakPoint = str; - char *next = str; + const char *next = str; while (*next) { const utf8_char_t c = get_utf8_char_and_inc(next); lineWidth += CHAR_WIDTH(c); if (lineWidth + ellipsisWidth < w) - breakPoint = next; + breakPoint = (char*)next; } if (lineWidth > w) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 2da5d55ff0..15e613cf69 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -66,7 +66,7 @@ * character (this is not the unicode codepoint) */ - utf8_char_t FTDI::get_utf8_char_and_inc(const char *&c) { + utf8_char_t FTDI::get_utf8_char_and_inc(char *&c) { utf8_char_t val = *(uint8_t*)c++; if ((val & 0xC0) == 0xC0) while ((*c & 0xC0) == 0x80) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h index 3ca6dfd563..391c8bf6cf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h @@ -51,14 +51,14 @@ namespace FTDI { /* Returns the next character in a UTF8 string, without incrementing */ - inline utf8_char_t get_utf8_char(const char *c) {return get_utf8_char_and_inc(c);} + inline utf8_char_t get_utf8_char(const char *c) { return get_utf8_char_and_inc(c); } void load_utf8_data(uint32_t addr); #else typedef char utf8_char_t; - inline utf8_char_t get_utf8_char_and_inc(const char *&c) {return *c++;} - inline utf8_char_t get_utf8_char(const char *c) {return *c;} + inline utf8_char_t get_utf8_char_and_inc(const char *&c) { return *c++; } + inline utf8_char_t get_utf8_char(const char *c) { return *c; } inline void load_utf8_data(uint32_t) {} #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp index 1f3640e3a1..ed24a9d9ed 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/string_format.cpp @@ -27,8 +27,10 @@ #define ROUND(val) uint16_t((val)+0.5) -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wno-format" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wno-format" +#endif /** * Formats a temperature string (e.g. "100°C") @@ -103,6 +105,8 @@ void format_position(char *str, float x, float y, float z) { sprintf_P(str, PSTR("%s; %s; %s " S_FMT), num1, num2, num3, GET_TEXT(MSG_UNITS_MM)); } -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif #endif // TOUCH_UI_FTDI_EVE From 69ab2bc40fe947c9edce487509ab4508376e8f56 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 11 Sep 2021 00:58:31 +0000 Subject: [PATCH 0655/2168] [cron] Bump distribution date (2021-09-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5994181f0a..4c4414d63c 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-10" +//#define STRING_DISTRIBUTION_DATE "2021-09-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 12c8b6b3ad..90b7a7e1f2 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 "2021-09-10" + #define STRING_DISTRIBUTION_DATE "2021-09-11" #endif /** From 209dca10890982aa4c992464e0388eff0c36e0f4 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Fri, 10 Sep 2021 19:03:46 -0600 Subject: [PATCH 0656/2168] =?UTF-8?q?=F0=9F=9A=B8=20Enhance=20FTDI=20Eve?= =?UTF-8?q?=20Touch=20UI=20file=20select=20dialog=20(#22742)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../generic/confirm_start_print_dialog_box.cpp | 6 +++--- .../generic/confirm_start_print_dialog_box.h | 5 ++--- .../ftdi_eve_touch_ui/generic/files_screen.cpp | 18 +++++++++--------- .../ftdi_eve_touch_ui/generic/files_screen.h | 10 +++++----- 4 files changed, 19 insertions(+), 20 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp index 47aac62860..7f566539a1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.cpp @@ -33,7 +33,7 @@ using namespace ExtUI; constexpr static ConfirmStartPrintDialogBoxData &mydata = screen_data.ConfirmStartPrintDialogBox; void ConfirmStartPrintDialogBox::onRedraw(draw_mode_t) { - const char *filename = getLongFilename(); + const char *filename = getFilename(); char buffer[strlen_P(GET_TEXT(MSG_START_PRINT_CONFIRMATION)) + strlen(filename) + 1]; sprintf_P(buffer, GET_TEXT(MSG_START_PRINT_CONFIRMATION), filename); drawMessage((const char *)buffer); @@ -52,10 +52,10 @@ bool ConfirmStartPrintDialogBox::onTouchEnd(uint8_t tag) { } } -const char *ConfirmStartPrintDialogBox::getFilename(bool longName) { +const char *ConfirmStartPrintDialogBox::getFilename(bool shortName) { FileList files; files.seek(mydata.file_index, true); - return longName ? files.longFilename() : files.shortFilename(); + return shortName ? files.shortFilename() : files.filename(); } void ConfirmStartPrintDialogBox::show(uint8_t file_index) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h index e073ed55fa..1f74fde94b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_start_print_dialog_box.h @@ -31,10 +31,9 @@ struct ConfirmStartPrintDialogBoxData { class ConfirmStartPrintDialogBox : public DialogBoxBaseClass, public UncachedScreen { private: - inline static const char *getShortFilename() {return getFilename(false);} - inline static const char *getLongFilename() {return getFilename(true);} + inline static const char *getShortFilename() {return getFilename(true);} - static const char *getFilename(bool longName); + static const char *getFilename(bool shortName = false); public: static void onRedraw(draw_mode_t); static bool onTouchEnd(uint8_t); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp index 8b9c877fc5..5076e58adf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -70,10 +70,10 @@ void FilesScreen::onEntry() { BaseScreen::onEntry(); } -const char *FilesScreen::getSelectedFilename(bool longName) { +const char *FilesScreen::getSelectedFilename(bool shortName) { FileList files; files.seek(getSelectedFileIndex(), true); - return longName ? files.longFilename() : files.shortFilename(); + return shortName ? files.shortFilename() : files.filename(); } void FilesScreen::drawSelectedFile() { @@ -132,13 +132,13 @@ void FilesScreen::drawFileList() { mydata.num_page = max(1,ceil(float(files.count()) / FILES_PER_PAGE)); mydata.cur_page = min(mydata.cur_page, mydata.num_page-1); mydata.flags.is_root = files.isAtRootDir(); + mydata.flags.is_empty = true; uint16_t fileIndex = mydata.cur_page * FILES_PER_PAGE; for (uint8_t i = 0; i < FILES_PER_PAGE; i++, fileIndex++) { - if (files.seek(fileIndex)) - drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); - else - break; + if (!files.seek(fileIndex)) break; + drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); + mydata.flags.is_empty = false; } } @@ -252,11 +252,11 @@ bool FilesScreen::onTouchEnd(uint8_t tag) { mydata.scroll_pos = 0; mydata.scroll_max = 0; if (FTDI::ftdi_chip >= 810) { - const char *longFilename = getSelectedLongFilename(); - if (longFilename[0]) { + const char *filename = getSelectedFilename(); + if (filename[0]) { CommandProcessor cmd; constexpr int dim[4] = {LIST_POS}; - const uint16_t text_width = cmd.font(font_medium).text_width(longFilename); + const uint16_t text_width = cmd.font(font_medium).text_width(filename); if (text_width > dim[2]) mydata.scroll_max = text_width - dim[2] + MARGIN_L + MARGIN_R + 10; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h index bf2b415364..cb950d4cac 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.h @@ -27,8 +27,9 @@ struct FilesScreenData { struct { - uint8_t is_dir : 1; - uint8_t is_root : 1; + uint8_t is_dir : 1; + uint8_t is_root : 1; + uint8_t is_empty : 1; } flags; uint8_t selected_tag; uint8_t num_page; @@ -46,9 +47,8 @@ class FilesScreen : public BaseScreen, public CachedScreen Date: Sat, 11 Sep 2021 00:48:20 -0500 Subject: [PATCH 0657/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LPC1768=20SD-bas?= =?UTF-8?q?ed=20EEPROM=20debug?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #22746 --- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 42 +++++++++++++++--------- Marlin/src/pins/stm32f4/pins_ARMED.h | 6 ++-- 2 files changed, 30 insertions(+), 18 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index 122c8ef81a..6570a599a4 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 @@ -20,12 +19,19 @@ * along with this program. If not, see . * */ + +/** + * Implementation of EEPROM settings in SD Card + */ + #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) +//#define DEBUG_SD_EEPROM_EMULATION + #include "../shared/eeprom_api.h" #include @@ -38,9 +44,11 @@ FATFS fat_fs; FIL eeprom_file; bool eeprom_file_open = false; +#define EEPROM_FILENAME "eeprom.dat" #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(0x1000) // 4KiB of Emulated EEPROM #endif + size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { @@ -50,7 +58,7 @@ bool PersistentStore::access_start() { MSC_Release_Lock(); return false; } - FRESULT res = f_open(&eeprom_file, "eeprom.dat", FA_OPEN_ALWAYS | FA_WRITE | FA_READ); + FRESULT res = f_open(&eeprom_file, EEPROM_FILENAME, FA_OPEN_ALWAYS | FA_WRITE | FA_READ); if (res) MSC_Release_Lock(); if (res == FR_OK) { @@ -81,18 +89,20 @@ bool PersistentStore::access_finish() { // This extra chit-chat goes away soon, but is helpful for now // to see errors that are happening in read_data / write_data static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) { - PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); - SERIAL_CHAR(' '); - SERIAL_ECHOPGM_P(rw_str); - SERIAL_ECHOLNPGM("_data(", pos, ",", value, ",", size, ", ...)"); - if (total) { - SERIAL_ECHOPGM(" f_"); + #if ENABLED(DEBUG_SD_EEPROM_EMULATION) + PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); + SERIAL_CHAR(' '); SERIAL_ECHOPGM_P(rw_str); - SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_"); - SERIAL_ECHOLNPGM_P(write ? PSTR("written=") : PSTR("read="), total); - } - else - SERIAL_ECHOLNPGM(" f_lseek()=", s); + SERIAL_ECHOLNPGM("_data(", pos, ",", *value, ",", size, ", ...)"); + if (total) { + SERIAL_ECHOPGM(" f_"); + SERIAL_ECHOPGM_P(rw_str); + SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_"); + SERIAL_ECHOLNPGM_P(write ? PSTR("written=") : PSTR("read="), total); + } + else + SERIAL_ECHOLNPGM(" f_lseek()=", s); + #endif } // File function return codes for type FRESULT. This goes away soon, but diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 4d0369b044..7cccac7caa 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -38,8 +38,10 @@ #define BOARD_INFO_NAME "Arm'ed" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif // // Limit Switches From 953d283e5360104072790a12ea1a78f69087c05b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Sep 2021 01:13:02 -0500 Subject: [PATCH 0658/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20E3V2?= =?UTF-8?q?=20Enhanced?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fix #22741 --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 254 ++++++++++++++++++-------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 4 +- 2 files changed, 185 insertions(+), 73 deletions(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 9e43e4198e..cea36e21d6 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -33,13 +33,15 @@ #include "../../../MarlinCore.h" #include "../../../core/serial.h" #include "../../../core/macros.h" -#include "../../../gcode/queue.h" #include "../../../module/temperature.h" #include "../../../module/printcounter.h" #include "../../../module/motion.h" #include "../../../module/planner.h" +#include "../../../gcode/gcode.h" +#include "../../../gcode/queue.h" + #if HAS_FILAMENT_SENSOR #include "../../../feature/runout.h" #endif @@ -187,16 +189,24 @@ MenuClass *LevBedMenu = nullptr; MenuClass *MoveMenu = nullptr; MenuClass *ControlMenu = nullptr; MenuClass *AdvancedSettings = nullptr; -TERN_(HAS_HOME_OFFSET, MenuClass *HomeOffMenu = nullptr); -TERN_(HAS_BED_PROBE, MenuClass *ProbeSetMenu = nullptr); +#if HAS_HOME_OFFSET + MenuClass *HomeOffMenu = nullptr; +#endif +#if HAS_BED_PROBE + MenuClass *ProbeSetMenu = nullptr; +#endif MenuClass *FilSetMenu = nullptr; MenuClass *SelectColorMenu = nullptr; MenuClass *GetColorMenu = nullptr; MenuClass *TuneMenu = nullptr; MenuClass *MotionMenu = nullptr; MenuClass *FilamentMenu = nullptr; -TERN_(MESH_BED_LEVELING, MenuClass *ManualMesh = nullptr); -TERN_(HAS_HOTEND, MenuClass *PreheatMenu = nullptr); +#if ENABLED(MESH_BED_LEVELING) + MenuClass *ManualMesh = nullptr; +#endif +#if HAS_HOTEND + MenuClass *PreheatMenu = nullptr; +#endif MenuClass *TemperatureMenu = nullptr; MenuClass *MaxSpeedMenu = nullptr; MenuClass *MaxAccelMenu = nullptr; @@ -1558,6 +1568,7 @@ void EachMomentUpdate() { select_page.set(0); Goto_Main_Menu(); } + #if ENABLED(POWER_LOSS_RECOVERY) else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off static bool recovery_flag = false; @@ -1679,7 +1690,7 @@ void DWIN_MeshLevelingStart() { void DWIN_CompletedLeveling() { HMI_ReturnScreen(); } -#if ENABLED(MESH_BED_LEVELING) +#if HAS_MESH void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { char msg[33] = ""; char str_1[6] = ""; @@ -1837,10 +1848,10 @@ void DWIN_SetColorDefaults() { void DWIN_SetDataDefaults() { DWIN_SetColorDefaults(); DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); - TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); - TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); - TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); - TERN_(PREVENT_COLD_EXTRUSION, HMI_data.ExtMinT = EXTRUDE_MINTEMP); + TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); + TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); + TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); + TERN_(PREVENT_COLD_EXTRUSION, HMI_data.ExtMinT = EXTRUDE_MINTEMP); } void DWIN_StoreSettings(char *buff) { @@ -2112,9 +2123,9 @@ void SetHome() { #if HAS_PREHEAT void SetPreheat(const uint8_t i) { - TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[i].hotend_temp, 0)); + TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[i].hotend_temp, 0)); TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[i].bed_temp)); - TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[i].fan_speed)); + TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[i].fan_speed)); } void SetPreheat0() { SetPreheat(0); } void SetPreheat1() { SetPreheat(1); } @@ -2193,14 +2204,20 @@ void SetPID(celsius_t t, heater_id_t h) { planner.synchronize(); thermalManager.PID_autotune(t, h, HMI_data.PidCycles, true); } -TERN_(HAS_HOTEND, void HotendPID() { SetPID(HMI_data.HotendPidT, H_E0); }) -TERN_(HAS_HEATED_BED, void BedPID() { SetPID(HMI_data.BedPidT, H_BED); }) +#if HAS_HOTEND + void HotendPID() { SetPID(HMI_data.HotendPidT, H_E0); } +#endif +#if HAS_HEATED_BED + void BedPID() { SetPID(HMI_data.BedPidT, H_BED); } +#endif -void SetPwrLossr() { - recovery.enable(!recovery.enabled); - Draw_Chkb_Line(CurrentMenu->line(), recovery.enabled); - DWIN_UpdateLCD(); -} +#if ENABLED(POWER_LOSS_RECOVERY) + void SetPwrLossr() { + recovery.enable(!recovery.enabled); + Draw_Chkb_Line(CurrentMenu->line(), recovery.enabled); + DWIN_UpdateLCD(); + } +#endif #if HAS_LCD_BRIGHTNESS void ApplyBrightness() { ui.set_brightness(HMI_value.Value); } @@ -2250,11 +2267,15 @@ void Goto_LockScreen() { #endif #endif -TERN_(ADVANCED_PAUSE_FEATURE, void SetFilLoad() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); }); -TERN_(ADVANCED_PAUSE_FEATURE, void SetFilUnload() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); }); +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void SetFilLoad() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); } + void SetFilUnload() { SetPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); } +#endif -TERN_(PREVENT_COLD_EXTRUSION, void ApplyExtMinT() { thermalManager.extrude_min_temp = HMI_data.ExtMinT; thermalManager.allow_cold_extrude = (HMI_data.ExtMinT == 0); }); -TERN_(PREVENT_COLD_EXTRUSION, void SetExtMinT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP, ApplyExtMinT); }); +#if ENABLED(PREVENT_COLD_EXTRUSION) + void ApplyExtMinT() { thermalManager.extrude_min_temp = HMI_data.ExtMinT; thermalManager.allow_cold_extrude = (HMI_data.ExtMinT == 0); } + void SetExtMinT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP, ApplyExtMinT); } +#endif void RestoreDefaultsColors() { DWIN_SetColorDefaults(); @@ -2425,38 +2446,53 @@ void LevBedC () { LevBed(4); } #endif #if HAS_PREHEAT - TERN_(HAS_HOTEND, void SetPreheatEndTemp() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); }); - TERN_(HAS_HEATED_BED, void SetPreheatBedTemp() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); }); - TERN_(HAS_FAN, void SetPreheatFanSpeed() { SetPIntOnClick(0, 255); }); + #if HAS_HOTEND + void SetPreheatEndTemp() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); } + #endif + #if HAS_HEATED_BED + void SetPreheatBedTemp() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } + #endif + #if HAS_FAN + void SetPreheatFanSpeed() { SetPIntOnClick(0, 255); } + #endif #endif void ApplyMaxSpeed() { planner.set_max_feedrate(HMI_value.axis, HMI_value.Value / MINUNITMULT); } void SetMaxSpeedX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[X_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[X_AXIS], ApplyMaxSpeed); } void SetMaxSpeedY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Y_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Y_AXIS], ApplyMaxSpeed); } void SetMaxSpeedZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Z_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Z_AXIS], ApplyMaxSpeed); } -TERN_(HAS_HOTEND, void SetMaxSpeedE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[E_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[E_AXIS], ApplyMaxSpeed); }); +#if HAS_HOTEND + void SetMaxSpeedE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[E_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[E_AXIS], ApplyMaxSpeed); } +#endif void ApplyMaxAccel() { planner.set_max_acceleration(HMI_value.axis, HMI_value.Value); } void SetMaxAccelX() { HMI_value.axis = X_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[X_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[X_AXIS], ApplyMaxAccel); } void SetMaxAccelY() { HMI_value.axis = Y_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Y_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ApplyMaxAccel); } void SetMaxAccelZ() { HMI_value.axis = Z_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Z_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ApplyMaxAccel); } -TERN_(HAS_HOTEND, void SetMaxAccelE() { HMI_value.axis = E_AXIS; SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[E_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[E_AXIS], ApplyMaxAccel); }); +#if HAS_HOTEND + void SetMaxAccelE() { HMI_value.axis = E_AXIS; SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[E_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[E_AXIS], ApplyMaxAccel); } +#endif #if HAS_CLASSIC_JERK void ApplyMaxJerk() { planner.set_max_jerk(HMI_value.axis, HMI_value.Value / MINUNITMULT); } void SetMaxJerkX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[X_AXIS] * 2, UNITFDIGITS, planner.max_jerk[X_AXIS], ApplyMaxJerk); } void SetMaxJerkY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Y_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Y_AXIS], ApplyMaxJerk); } void SetMaxJerkZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Z_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Z_AXIS], ApplyMaxJerk); } - TERN_(HAS_HOTEND, void SetMaxJerkE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXJERK, default_max_jerk[E_AXIS] * 2, UNITFDIGITS, planner.max_jerk[E_AXIS], ApplyMaxJerk); }); + #if HAS_HOTEND + void SetMaxJerkE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXJERK, default_max_jerk[E_AXIS] * 2, UNITFDIGITS, planner.max_jerk[E_AXIS], ApplyMaxJerk); } + #endif #endif void SetStepsX() { HMI_value.axis = X_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } void SetStepsY() { HMI_value.axis = Y_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } -TERN_(HAS_HOTEND, void SetStepsE() { HMI_value.axis = E_AXIS; SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); }); - -TERN_(HAS_HOTEND, void SetHotendPidT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); }) -TERN_(HAS_HEATED_BED, void SetBedPidT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); }) +#if HAS_HOTEND + void SetStepsE() { HMI_value.axis = E_AXIS; SetPFloatOnClick( MIN_STEP, MAX_STEP, UNITFDIGITS); } + void SetHotendPidT() { SetPIntOnClick(MIN_ETEMP, MAX_ETEMP); } +#endif +#if HAS_HEATED_BED + void SetBedPidT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } +#endif #if HAS_HOTEND || HAS_HEATED_BED void SetPidCycles() { SetPIntOnClick(3, 50); } @@ -2649,7 +2685,9 @@ void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { DWINUI::Draw_String(VALX, MBASE(line), HMI_IsChinese() ? F("CN") : F("EN")); } -void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } +#if ENABLED(POWER_LOSS_RECOVERY) + void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } +#endif void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } @@ -3076,12 +3114,16 @@ void Draw_Prepare_Menu() { SetMenuTitle({133, 1, 28, 13}, {179, 0, 48, 14}, GET_TEXT_F(MSG_PREPARE)); DWINUI::MenuItemsPrepare(13); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); - TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu)); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); + #endif ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_MOVE_AXIS), onDrawMoveSubMenu, Draw_Move_Menu); ADDMENUITEM(ICON_LevBed, GET_TEXT(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); ADDMENUITEM(ICON_CloseMotor, GET_TEXT(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); ADDMENUITEM(ICON_Homing, GET_TEXT(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); - TERN_(MESH_BED_LEVELING, ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu)); + #if ENABLED(MESH_BED_LEVELING) + ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); + #endif #if HAS_ZOFFSET_ITEM #if EITHER(HAS_BED_PROBE, BABYSTEPPING) ADDMENUITEM(ICON_SetZOffset, GET_TEXT(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); @@ -3094,7 +3136,9 @@ void Draw_Prepare_Menu() { ADDMENUITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, SetPreheat1); ADDMENUITEM(ICON_CustomPreheat, GET_TEXT(MSG_PREHEAT_CUSTOM), onDrawMenuItem, SetPreheat2); #endif - TERN_(HAS_PREHEAT, ADDMENUITEM(ICON_Cool, GET_TEXT(MSG_COOLDOWN), onDrawCooldown, SetCoolDown)); + #if HAS_PREHEAT + ADDMENUITEM(ICON_Cool, GET_TEXT(MSG_COOLDOWN), onDrawCooldown, SetCoolDown); + #endif ADDMENUITEM(ICON_Language, PSTR("UI Language"), onDrawLanguage, SetLanguage); } CurrentMenu->Draw(); @@ -3148,15 +3192,31 @@ void Draw_AdvancedSettings_Menu() { SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG DWINUI::MenuItemsPrepare(11); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - TERN_(HAS_HOME_OFFSET, ADDMENUITEM(ICON_HomeOffset, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu)); - TERN_(HAS_BED_PROBE, ADDMENUITEM(ICON_ProbeSet, GET_TEXT(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu)); - TERN_(HAS_HOTEND, ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu)); - TERN_(HAS_HEATED_BED, ADDMENUITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu)); - TERN_(HAS_FILAMENT_SENSOR, ADDMENUITEM(ICON_FilSet, GET_TEXT(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu)); - TERN_(POWER_LOSS_RECOVERY, ADDMENUITEM(ICON_Pwrlossr, F("Power-loss recovery"), onDrawPwrLossR, SetPwrLossr)); - TERN_(HAS_LCD_BRIGHTNESS, ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness)); + #if HAS_HOME_OFFSET + ADDMENUITEM(ICON_HomeOffset, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); + #endif + #if HAS_BED_PROBE + ADDMENUITEM(ICON_ProbeSet, GET_TEXT(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); + #endif + #if HAS_HOTEND + ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu); + #endif + #if HAS_HEATED_BED + ADDMENUITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu); + #endif + #if HAS_FILAMENT_SENSOR + ADDMENUITEM(ICON_FilSet, GET_TEXT(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); + #endif + #if ENABLED(POWER_LOSS_RECOVERY) + ADDMENUITEM(ICON_Pwrlossr, F("Power-loss recovery"), onDrawPwrLossR, SetPwrLossr); + #endif + #if HAS_LCD_BRIGHTNESS + ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); + #endif ADDMENUITEM(ICON_Scolor, F("Select Colors"), onDrawSubMenu, Draw_SelectColors_Menu); - TERN_(SOUND_MENU_ITEM, ADDMENUITEM(ICON_Sound, F("Enable Sound"), onDrawEnableSound, SetEnableSound)); + #if ENABLED(SOUND_MENU_ITEM) + ADDMENUITEM(ICON_Sound, F("Enable Sound"), onDrawEnableSound, SetEnableSound); + #endif ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); } CurrentMenu->Draw(); @@ -3173,7 +3233,9 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_MoveX, GET_TEXT(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); ADDMENUITEM_P(ICON_MoveY, GET_TEXT(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); ADDMENUITEM_P(ICON_MoveZ, GET_TEXT(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_Extruder, GET_TEXT(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e)); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_Extruder, GET_TEXT(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); + #endif } CurrentMenu->Draw(); if (!all_axes_trusted()) ui.set_status_P(PSTR("WARNING: position is unknow")); @@ -3223,11 +3285,19 @@ void Draw_Move_Menu() { CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); DWINUI::MenuItemsPrepare(6); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - TERN_(HAS_FILAMENT_SENSOR, ADDMENUITEM(ICON_Runout, GET_TEXT(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable)); - TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance())); - TERN_(PREVENT_COLD_EXTRUSION, ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT)); - TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilLoad, GET_TEXT(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length)); - TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length)); + #if HAS_FILAMENT_SENSOR + ADDMENUITEM(ICON_Runout, GET_TEXT(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); + #endif + #if HAS_FILAMENT_RUNOUT_DISTANCE + ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); + #endif + #if ENABLED(PREVENT_COLD_EXTRUSION) + ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); + #endif + #if ENABLED(ADVANCED_PAUSE_FEATURE) + ADDMENUITEM_P(ICON_FilLoad, GET_TEXT(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); + ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); + #endif } CurrentMenu->Draw(); } @@ -3289,16 +3359,26 @@ void Draw_Tune_Menu() { DWINUI::MenuItemsPrepare(10); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); ADDMENUITEM_P(ICON_Speed, GET_TEXT(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); - TERN_(HAS_HOTEND, HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target)); - TERN_(HAS_HEATED_BED, BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target)); - TERN_(HAS_FAN, FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0])); + #if HAS_HOTEND + HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + #endif + #if HAS_FAN + FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + #endif #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); - TERN_(ADVANCED_PAUSE_FEATURE, ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament)); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + #endif ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); - TERN_(HAS_LCD_BRIGHTNESS, ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness)); + #if HAS_LCD_BRIGHTNESS + ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); + #endif } CurrentMenu->Draw(); } @@ -3313,7 +3393,9 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); ADDMENUITEM(ICON_MaxSpeed, GET_TEXT(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); ADDMENUITEM(ICON_MaxAccelerated, GET_TEXT(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); - TERN_(HAS_CLASSIC_JERK, ADDMENUITEM(ICON_MaxJerk, GET_TEXT(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu)); + #if HAS_CLASSIC_JERK + ADDMENUITEM(ICON_MaxJerk, GET_TEXT(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); + #endif ADDMENUITEM(ICON_Step, GET_TEXT(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } @@ -3331,8 +3413,10 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); ADDMENUITEM(ICON_Park, GET_TEXT(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); - TERN_(FILAMENT_LOAD_UNLOAD_GCODES, ADDMENUITEM(ICON_FilUnload, GET_TEXT(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament)); - TERN_(FILAMENT_LOAD_UNLOAD_GCODES, ADDMENUITEM(ICON_FilLoad, GET_TEXT(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament)); + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + ADDMENUITEM(ICON_FilUnload, GET_TEXT(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); + ADDMENUITEM(ICON_FilLoad, GET_TEXT(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); + #endif } CurrentMenu->Draw(); } @@ -3364,10 +3448,18 @@ void Draw_Motion_Menu() { SetMenuTitle(cn, en, text); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp)); - TERN_(HAS_HEATED_BED, ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp)); - TERN_(HAS_FAN, ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed)); - TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom)); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); + #endif + #if HAS_HEATED_BED + ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); + #endif + #if HAS_FAN + ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + #endif } CurrentMenu->Draw(); } @@ -3403,9 +3495,15 @@ void Draw_Temperature_Menu() { SetMenuTitle({236, 2, 28, 12}, {56, 15, 85, 14}, GET_TEXT_F(MSG_TEMPERATURE)); DWINUI::MenuItemsPrepare(7); ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - TERN_(HAS_HOTEND, HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target)); - TERN_(HAS_HEATED_BED, BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target)); - TERN_(HAS_FAN, FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0])); + #if HAS_HOTEND + HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + #endif + #if HAS_FAN + FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + #endif #if HAS_HOTEND ADDMENUITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); ADDMENUITEM(ICON_SetABSPreheat, F(PREHEAT_2_LABEL " Preheat Settings"), onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); @@ -3428,7 +3526,9 @@ void Draw_MaxSpeed_Menu() { ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS])); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + #endif } CurrentMenu->Draw(); } @@ -3444,7 +3544,9 @@ void Draw_MaxAccel_Menu() { ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); ADDMENUITEM_P(ICON_MaxAccY, GET_TEXT(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); ADDMENUITEM_P(ICON_MaxAccZ, GET_TEXT(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS])); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + #endif } CurrentMenu->Draw(); } @@ -3461,7 +3563,9 @@ void Draw_MaxAccel_Menu() { ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); ADDMENUITEM_P(ICON_MaxSpeedJerkY, GET_TEXT(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); ADDMENUITEM_P(ICON_MaxSpeedJerkZ, GET_TEXT(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS])); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); + #endif } CurrentMenu->Draw(); } @@ -3478,7 +3582,9 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_StepX, GET_TEXT(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); ADDMENUITEM_P(ICON_StepY, GET_TEXT(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); ADDMENUITEM_P(ICON_StepZ, GET_TEXT(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); - TERN_(HAS_HOTEND, ADDMENUITEM_P(ICON_StepE, GET_TEXT(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS])); + #if HAS_HOTEND + ADDMENUITEM_P(ICON_StepE, GET_TEXT(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); + #endif } CurrentMenu->Draw(); } @@ -3498,7 +3604,9 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); - TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); + #if ENABLED(EEPROM_SETTINGS) + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + #endif } CurrentMenu->Draw(); } @@ -3519,7 +3627,9 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); - TERN_(EEPROM_SETTINGS, ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom)); + #if ENABLED(EEPROM_SETTINGS) + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + #endif } CurrentMenu->Draw(); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index ee83f9ad7c..db4cc2121f 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -196,7 +196,9 @@ void DWIN_StatusChanged(const char * const text); void DWIN_StatusChanged_P(PGM_P const text); void DWIN_StartHoming(); void DWIN_CompletedHoming(); -TERN_(MESH_BED_LEVELING, void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval)); +#if HAS_MESH + void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); +#endif void DWIN_MeshLevelingStart(); void DWIN_CompletedLeveling(); void DWIN_PidTuning(pidresult_t result); From 453e60958a8cde6d7541b4dc3a99d054b53eb695 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Sep 2021 01:32:39 -0500 Subject: [PATCH 0659/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20JyersU?= =?UTF-8?q?I?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fix #22735, #22736 --- Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp | 4 +++- Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp | 4 +++- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 14 ++++++++------ Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp | 4 +++- Marlin/src/lcd/marlinui.h | 2 +- 5 files changed, 18 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp index f46fef073e..6bb8d79be8 100644 --- a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp @@ -145,7 +145,9 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #if ENCODER_5X_STEPS_PER_SEC + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #endif } EncoderRate.lastEncoderTime = ms; } diff --git a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp index 4f815fdee0..de478f79f4 100644 --- a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp @@ -145,7 +145,9 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #if ENCODER_5X_STEPS_PER_SEC + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #endif } EncoderRate.lastEncoderTime = ms; } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 2a2df68b1d..6f76fe3d32 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -4757,11 +4757,13 @@ void CrealityDWINClass::Start_Print(bool sd) { printing = true; statusmsg[0] = '\0'; if (sd) { - if (recovery.valid()) { - SdFile *diveDir = nullptr; - const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); - card.selectFileByName(fname); - } + #if ENABLED(POWER_LOSS_RECOVERY) + if (recovery.valid()) { + SdFile *diveDir = nullptr; + const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); + card.selectFileByName(fname); + } + #endif strcpy_P(filename, card.longest_filename()); } else @@ -4801,7 +4803,7 @@ void MarlinUI::update() { CrealityDWIN.Update(); } void CrealityDWINClass::State_Update() { if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { - if (!printing) Start_Print((card.isFileOpen() || recovery.valid())); + if (!printing) Start_Print(card.isFileOpen() || TERN0(POWER_LOSS_RECOVERY, recovery.valid())); else Stop_Print(); } if (print_job_timer.isPaused() != paused) { diff --git a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp index 47ddc90184..23494aa693 100644 --- a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp @@ -145,7 +145,9 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #if ENCODER_5X_STEPS_PER_SEC + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + #endif } EncoderRate.lastEncoderTime = ms; } diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index d3a3c9d521..e947ac9e5e 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -596,7 +596,7 @@ public: static inline bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static inline void _pause_show_message() {} From 6b9b2c5d7382b30dabc2f1fb360d62a819f5ec3d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Sep 2021 02:15:05 -0500 Subject: [PATCH 0660/2168] =?UTF-8?q?=F0=9F=A9=B9=20Warn=20about=20user=20?= =?UTF-8?q?feedback=20requirement?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/mmu/mmu2.cpp | 2 +- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/gcode/sd/M1001.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 4 ++++ Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 8 ++++---- Marlin/src/module/probe.cpp | 4 ++-- 7 files changed, 14 insertions(+), 10 deletions(-) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 31e64f4953..cf03eaf7f6 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -962,7 +962,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { BUZZ(200, 404); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); - wait_for_user_response(); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); BUZZ(200, 404); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index d9b2521403..f9e3d1b9c2 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -522,7 +522,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT))); - wait_for_user_response(0, true); // Wait for LCD click or M108 + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108 TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING))); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index cb37bfec24..9ba6ed5fc7 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -83,7 +83,7 @@ void GcodeSuite::M0_M1() { TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR)); - wait_for_user_response(ms); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(ms)); TERN_(HAS_LCD_MENU, ui.reset_status()); } diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 14bd712d27..f5ee6a94d1 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -97,7 +97,7 @@ void GcodeSuite::M1001() { printerEventLEDs.onPrintCompleted(); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR)); - wait_for_user_response(SEC_TO_MS(TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30))); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(SEC_TO_MS(TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)))); printerEventLEDs.onResumeAfterWait(); } #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 3c00d84142..35ee74b5aa 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -999,6 +999,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif +#if !HAS_RESUME_CONTINUE && DISABLED(HOST_PROMPT_SUPPORT) && DISABLED(EXTENSIBLE_UI) + #warning "Your Configuration provides no method to acquire user feedback!" +#endif + /** * Instant Freeze */ diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 810f376f82..ba119abc37 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -54,9 +54,9 @@ void _man_probe_pt(const xy_pos_t &xy) { #if ENABLED(DELTA_AUTO_CALIBRATION) - #include "../../MarlinCore.h" // for wait_for_user_response() - #include "../../gcode/gcode.h" - + #if HAS_RESUME_CONTINUE + #include "../../MarlinCore.h" // for wait_for_user_response() + #endif #if ENABLED(HOST_PROMPT_SUPPORT) #include "../../feature/host_actions.h" // for host_prompt_do #endif @@ -66,7 +66,7 @@ void _man_probe_pt(const xy_pos_t &xy) { ui.defer_status_screen(); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress"))); - wait_for_user_response(); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.goto_previous_screen_no_defer(); return current_position.z; } diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 16ff166493..3b8a4a520f 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -141,7 +141,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() ui.return_to_status(); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR)); - wait_for_user_response(); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); ui.goto_screen(prev_screen); @@ -298,7 +298,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, PSTR("Stow Probe"), CONTINUE_STR)); - wait_for_user_response(); + TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); } while (ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED)); From 011329fe55f82e0c64c48a6bc983c10569206fb3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Sep 2021 02:47:53 -0500 Subject: [PATCH 0661/2168] =?UTF-8?q?=F0=9F=90=9B=20No=20probe=20enum=20fo?= =?UTF-8?q?r=20DELTA=20+=20SENSORLESS=5FPROBING?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fix #22729 --- Marlin/src/inc/Conditionals_LCD.h | 5 ++++- Marlin/src/module/endstops.h | 4 +++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a7bde803ba..fc7e05b896 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -931,7 +931,10 @@ #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 #endif - #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) + #if BOTH(DELTA, SENSORLESS_PROBING) + #define HAS_DELTA_SENSORLESS_PROBING 1 + #endif + #if NONE(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING) #define USES_Z_MIN_PROBE_PIN 1 #endif #if Z_HOME_TO_MIN && TERN1(USES_Z_MIN_PROBE_PIN, ENABLED(USE_PROBE_FOR_Z_HOMING)) diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index e688d3a788..a35966a98c 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -59,7 +59,9 @@ enum EndstopEnum : char { _ES_ITEM(HAS_Z4_MAX, Z4_MAX) // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) - _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(USES_Z_MIN_PROBE_PIN, = Z_MIN)) + #if !HAS_DELTA_SENSORLESS_PROBING + _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(USES_Z_MIN_PROBE_PIN, = Z_MIN)) + #endif // The total number of states NUM_ENDSTOP_STATES From 08e581d5d7c6cfcedf400862fcfcd146c6ce837f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 11 Sep 2021 15:41:42 -0500 Subject: [PATCH 0662/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20more=20HAS=5FD?= =?UTF-8?q?ELTA=5FSENSORLESS=5FPROBING?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G33.cpp | 2 +- Marlin/src/module/delta.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/probe.cpp | 14 +++++++------- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 597801cf52..95a862b5f7 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -425,7 +425,7 @@ void GcodeSuite::G33() { const bool stow_after_each = parser.seen_test('E'); - #if ENABLED(SENSORLESS_PROBING) + #if HAS_DELTA_SENSORLESS_PROBING probe.test_sensitivity.x = !parser.seen_test('X'); TERN_(HAS_Y_AXIS, probe.test_sensitivity.y = !parser.seen_test('Y')); TERN_(HAS_Z_AXIS, probe.test_sensitivity.z = !parser.seen_test('Z')); diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 899848d7f2..4401db5a5b 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -254,7 +254,7 @@ void home_delta() { current_position.z = DIFF_TERN(HAS_BED_PROBE, delta_height + 10, probe.offset.z); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); - TERN_(SENSORLESS_PROBING,endstops.report_states()); + TERN_(HAS_DELTA_SENSORLESS_PROBING, endstops.report_states()); // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index b5315f2f01..d29fd3ecb3 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -595,7 +595,7 @@ void _O2 Endstops::report_states() { // The following routines are called from an ISR context. It could be the temperature ISR, the // endstop ISR or the Stepper ISR. -#if BOTH(DELTA, SENSORLESS_PROBING) +#if HAS_DELTA_SENSORLESS_PROBING #define __ENDSTOP(AXIS, ...) AXIS ##_MAX #define _ENDSTOP_PIN(AXIS, ...) AXIS ##_MAX_PIN #define _ENDSTOP_INVERTING(AXIS, ...) AXIS ##_MAX_ENDSTOP_INVERTING diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 3b8a4a520f..071ff25c20 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -493,7 +493,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) sensorless_t stealth_states { false }; - #if ENABLED(DELTA) + #if HAS_DELTA_SENSORLESS_PROBING if (probe.test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall if (probe.test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); #endif @@ -509,7 +509,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { // Check to see if the probe was triggered const bool probe_triggered = - #if BOTH(DELTA, SENSORLESS_PROBING) + #if HAS_DELTA_SENSORLESS_PROBING endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else TEST(endstops.trigger_state(), Z_MIN_PROBE) @@ -521,7 +521,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) endstops.not_homing(); - #if ENABLED(DELTA) + #if HAS_DELTA_SENSORLESS_PROBING if (probe.test_sensitivity.x) tmc_disable_stallguard(stepperX, stealth_states.x); if (probe.test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); #endif @@ -765,7 +765,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif // On delta keep Z below clip height or do_blocking_move_to will abort - xyz_pos_t npos = { rx, ry, _MIN(TERN(DELTA, delta_clip_start_height, current_position.z), current_position.z) }; + xyz_pos_t npos = { rx, ry, TERN(DELTA, _MIN(delta_clip_start_height, current_position.z), current_position.z) }; if (probe_relative) { // The given position is in terms of the probe if (!can_reach(npos)) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); @@ -827,7 +827,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai */ void Probe::enable_stallguard_diag1() { #if ENABLED(SENSORLESS_PROBING) - #if ENABLED(DELTA) + #if HAS_DELTA_SENSORLESS_PROBING stealth_states.x = tmc_enable_stallguard(stepperX); stealth_states.y = tmc_enable_stallguard(stepperY); #endif @@ -842,7 +842,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai void Probe::disable_stallguard_diag1() { #if ENABLED(SENSORLESS_PROBING) endstops.not_homing(); - #if ENABLED(DELTA) + #if HAS_DELTA_SENSORLESS_PROBING tmc_disable_stallguard(stepperX, stealth_states.x); tmc_disable_stallguard(stepperY, stealth_states.y); #endif @@ -907,6 +907,6 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif } -#endif // SENSORLESS_PROBING +#endif // SENSORLESS_PROBING || SENSORLESS_HOMING #endif // HAS_BED_PROBE From afe4cb7fee73878917a55ccca7e67a24fea423f8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 12 Sep 2021 01:02:08 +0000 Subject: [PATCH 0663/2168] [cron] Bump distribution date (2021-09-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4c4414d63c..8560812e1e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-11" +//#define STRING_DISTRIBUTION_DATE "2021-09-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 90b7a7e1f2..6e445422c8 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 "2021-09-11" + #define STRING_DISTRIBUTION_DATE "2021-09-12" #endif /** From 3a457c9d13701428a4a276aaf43eb7961e9503a1 Mon Sep 17 00:00:00 2001 From: tome9111991 <57866234+tome9111991@users.noreply.github.com> Date: Sun, 12 Sep 2021 21:56:40 +0200 Subject: [PATCH 0664/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20JyersUI=20for=20?= =?UTF-8?q?LPC176x=20(#22745)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/LPC1768/MarlinSerial.h | 2 ++ Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 43 ++++++++++++------------ Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp | 2 +- 4 files changed, 26 insertions(+), 23 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index fc2fc57378..ca4e2decab 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -107,7 +107,7 @@ extern DefaultSerial1 USBSerial; #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() MSerial0.available() + #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.available() #endif #endif diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 808d19f8c5..3e6848a1e3 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -46,6 +46,8 @@ public: void end() {} + uint8_t availableForWrite(void) { /* flushTX(); */ return TX_BUFFER_SIZE; } + #if ENABLED(EMERGENCY_PARSER) bool recv_callback(const char c) override; #endif diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 6f76fe3d32..c02aa48b1a 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -307,16 +307,16 @@ CrealityDWINClass CrealityDWIN; const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x; const uint16_t cell_width_px = total_width_px / GRID_MAX_POINTS_X; const uint16_t cell_height_px = total_width_px / GRID_MAX_POINTS_Y; - const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = max(v_min, v_max); + const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); // Clear background from previous selection and select new square - DWIN_Draw_Rectangle(1, Color_Bg_Black, max(0, padding_x - gridline_width), max(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); + DWIN_Draw_Rectangle(1, Color_Bg_Black, _MAX(0, padding_x - gridline_width), _MAX(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); if (selected >= 0) { const auto selected_y = selected / GRID_MAX_POINTS_X; const auto selected_x = selected - (GRID_MAX_POINTS_X * selected_y); const auto start_y_px = padding_y_top + selected_y * cell_height_px; const auto start_x_px = padding_x + selected_x * cell_width_px; - DWIN_Draw_Rectangle(1, Color_White, max(0, start_x_px - gridline_width), max(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); + DWIN_Draw_Rectangle(1, Color_White, _MAX(0, start_x_px - gridline_width), _MAX(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); } // Draw value square grid @@ -326,21 +326,20 @@ CrealityDWINClass CrealityDWIN; const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px; const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; - DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ - isnan(mesh_z_values[x][y]) ? Color_Grey : ( // gray if undefined + DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ + isnan(mesh_z_values[x][y]) ? Color_Grey : ( // gray if undefined (mesh_z_values[x][y] < 0 ? - (uint16_t)round(0b11111 * -mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative - (uint16_t)round(0b111111 * mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive - min(0b11111, (((uint8_t)abs(mesh_z_values[x][y]) / 10) * 4))), // + blue stepping for every mm - start_x_px, start_y_px, end_x_px, end_y_px); - while (LCD_SERIAL.availableForWrite() < 32) { // wait for serial to be available without blocking and resetting the MCU - gcode.process_subcommands_now_P("G4 P10"); - planner.synchronize(); - } + (uint16_t)round(0x1F * -mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)round(0x3F * mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive + _MIN(0x1F, (((uint8_t)abs(mesh_z_values[x][y]) / 10) * 4))), // + blue stepping for every mm + start_x_px, start_y_px, end_x_px, end_y_px + ); + + safe_delay(10); + LCD_SERIAL.flushTX(); + // Draw value text on if (viewer_print_value) { - gcode.process_subcommands_now_P("G4 P10"); // still fails without additional delay... - planner.synchronize(); int8_t offset_x, offset_y = cell_height_px / 2 - 6; if (isnan(mesh_z_values[x][y])) { // undefined DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); @@ -355,12 +354,14 @@ CrealityDWINClass CrealityDWIN; DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); } + safe_delay(10); + LCD_SERIAL.flushTX(); } } } void Set_Mesh_Viewer_Status() { // TODO: draw gradient with values as a legend instead - float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = max(v_min, v_max); + float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); if (v_min > 3e+10F) v_min = 0.0000001; if (v_max > 3e+10F) v_max = 0.0000001; if (range > 3e+10F) range = 0.0000001; @@ -470,8 +471,8 @@ void CrealityDWINClass::Draw_Title(const char * title) { void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { const uint8_t label_offset_y = !(label1 && label2) ? 0 : MENU_CHR_H * 3 / 5; - const uint8_t label1_offset_x = !centered ? LBLX : LBLX * 4/5 + max(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2); - const uint8_t label2_offset_x = !centered ? LBLX : LBLX * 4/5 + max(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); + const uint8_t label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2); + const uint8_t label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); if (label1) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label if (label2) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon @@ -501,7 +502,7 @@ void CrealityDWINClass::Draw_Menu(uint8_t menu, uint8_t select/*=0*/, uint8_t sc last_menu = active_menu; if (process == Menu) last_selection = selection; } - selection = min(select, Get_Menu_Size(menu)); + selection = _MIN(select, Get_Menu_Size(menu)); scrollpos = scroll; if (selection - scrollpos > MROWS) scrollpos = selection - MROWS; @@ -4975,11 +4976,11 @@ void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { void CrealityDWINClass::Save_Settings(char *buff) { TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = mesh_conf.tilt_grid - 1); eeprom_settings.corner_pos = corner_pos * 10; - memcpy(buff, &eeprom_settings, min(sizeof(eeprom_settings), eeprom_data_size)); + memcpy(buff, &eeprom_settings, _MIN(sizeof(eeprom_settings), eeprom_data_size)); } void CrealityDWINClass::Load_Settings(const char *buff) { - memcpy(&eeprom_settings, buff, min(sizeof(eeprom_settings), eeprom_data_size)); + memcpy(&eeprom_settings, buff, _MIN(sizeof(eeprom_settings), eeprom_data_size)); TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; corner_pos = eeprom_settings.corner_pos / 10.0f; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp index 5380d1b93e..92f4be4548 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp @@ -92,7 +92,7 @@ bool DWIN_Handshake(void) { #endif LCD_SERIAL.begin(LCD_BAUDRATE); const millis_t serial_connect_timeout = millis() + 1000UL; - while (!LCD_SERIAL && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } size_t i = 0; DWIN_Byte(i, 0x00); From c9d54bc3f34c18691a051c0a9f196010dd7c7de9 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 13 Sep 2021 11:03:24 +1200 Subject: [PATCH 0665/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Trigorilla=20Pro?= =?UTF-8?q?=20HAL/STM32=20build=20offset=20(#22761)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 1 - 1 file changed, 1 deletion(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index a27d275fc1..da7cedd3a3 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -352,7 +352,6 @@ platform = ${stm32_variant.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx -board_build.offset = 0x7000 build_flags = ${stm32_variant.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${stm32_variant.build_unflags} From 37c488fda1176e9e50531d0ea7e9d66c74cef2d4 Mon Sep 17 00:00:00 2001 From: Luc Van Daele Date: Mon, 13 Sep 2021 02:35:37 +0200 Subject: [PATCH 0666/2168] =?UTF-8?q?=F0=9F=9A=B8=20G33=20R=20and=20O=20op?= =?UTF-8?q?tions=20(#22707)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G33.cpp | 65 ++++++++++++-------- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 3 +- Marlin/src/module/delta.cpp | 22 ------- Marlin/src/module/delta.h | 13 ---- 4 files changed, 40 insertions(+), 63 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 95a862b5f7..8867c168d2 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -69,6 +69,8 @@ enum CalEnum : char { // the 7 main calibration points - float lcd_probe_pt(const xy_pos_t &xy); +float dcr; + void ac_home() { endstops.enable(true); TERN_(SENSORLESS_HOMING, probe.set_homing_current(true)); @@ -175,9 +177,9 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool /** * - Probe a point */ -static float calibration_probe(const xy_pos_t &xy, const bool stow) { +static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) { #if HAS_BED_PROBE - return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true, false); + return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true, probe_at_offset); #else UNUSED(stow); return lcd_probe_pt(xy); @@ -187,7 +189,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow) { /** * - Probe a grid */ -static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const bool towers_set, const bool stow_after_each) { +static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) { const bool _0p_calibration = probe_points == 0, _1p_calibration = probe_points == 1 || probe_points == -1, _4p_calibration = probe_points == 2, @@ -209,11 +211,9 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi if (!_0p_calibration) { - const float dcr = delta_calibration_radius(); - if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // probe the center const xy_pos_t center{0}; - z_pt[CEN] += calibration_probe(center, stow_after_each); + z_pt[CEN] += calibration_probe(center, stow_after_each, probe_at_offset); if (isnan(z_pt[CEN])) return false; } @@ -224,7 +224,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi const float a = RADIANS(210 + (360 / NPP) * (rad - 1)), r = dcr * 0.1; const xy_pos_t vec = { cos(a), sin(a) }; - z_pt[CEN] += calibration_probe(vec * r, stow_after_each); + z_pt[CEN] += calibration_probe(vec * r, stow_after_each, probe_at_offset); if (isnan(z_pt[CEN])) return false; } z_pt[CEN] /= float(_7p_2_intermediates ? 7 : probe_points); @@ -249,7 +249,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi r = dcr * (1 - 0.1 * (zig_zag ? offset - circle : circle)), interpol = FMOD(rad, 1); const xy_pos_t vec = { cos(a), sin(a) }; - const float z_temp = calibration_probe(vec * r, stow_after_each); + const float z_temp = calibration_probe(vec * r, stow_after_each, probe_at_offset); if (isnan(z_temp)) return false; // split probe point to neighbouring calibration points z_pt[uint8_t(LROUND(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90))); @@ -276,7 +276,6 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1]) { xyz_pos_t pos{0}; - const float dcr = delta_calibration_radius(); LOOP_CAL_ALL(rad) { const float a = RADIANS(210 + (360 / NPP) * (rad - 1)), r = (rad == CEN ? 0.0f : dcr); @@ -287,7 +286,7 @@ static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_ } static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1]) { - const float r_quot = delta_calibration_radius() / delta_radius; + const float r_quot = dcr / delta_radius; #define ZPP(N,I,A) (((1.0f + r_quot * (N)) / 3.0f) * mm_at_pt_axis[I].A) #define Z00(I, A) ZPP( 0, I, A) @@ -328,7 +327,7 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t d } static float auto_tune_h() { - const float r_quot = delta_calibration_radius() / delta_radius; + const float r_quot = dcr / delta_radius; return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR } @@ -373,6 +372,8 @@ static float auto_tune_a() { * P3 Probe all positions: center, towers and opposite towers. Calibrate all. * P4-P10 Probe all positions at different intermediate locations and average them. * + * Rn.nn override default calibration Radius + * * T Don't calibrate tower angle corrections * * Cn.nn Calibration precision; when omitted calibrates to maximum precision @@ -387,6 +388,8 @@ static float auto_tune_a() { * * E Engage the probe for each point * + * O Probe at offset points (this is wrong but it seems to work) + * * With SENSORLESS_PROBING: * Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.) * X Don't activate stallguard on X. @@ -403,7 +406,27 @@ void GcodeSuite::G33() { return; } - const bool towers_set = !parser.seen_test('T'); + const bool probe_at_offset = TERN0(HAS_PROBE_XY_OFFSET, parser.boolval('O')), + towers_set = !parser.seen_test('T'); + + float max_dcr = dcr = DELTA_PRINTABLE_RADIUS; + #if HAS_PROBE_XY_OFFSET + // For offset probes the calibration radius is set to a safe but non-optimal value + dcr -= HYPOT(probe.offset_xy.x, probe.offset_xy.y); + if (probe_at_offset) { + // With probe positions both probe and nozzle need to be within the printable area + max_dcr = dcr; + } + // else with nozzle positions there is a risk of the probe being outside the bed + // but as long the nozzle stays within the printable area there is no risk of + // the effector crashing into the towers. + #endif + + if (parser.seenval('R')) dcr = parser.value_float(); + if (!WITHIN(dcr, 0, max_dcr)) { + SERIAL_ECHOLNPGM("?calibration (R)adius implausible."); + return; + } const float calibration_precision = parser.floatval('C', 0.0f); if (calibration_precision < 0) { @@ -453,18 +476,6 @@ void GcodeSuite::G33() { SERIAL_ECHOLNPGM("G33 Auto Calibrate"); - const float dcr = delta_calibration_radius(); - - if (!_1p_calibration && !_0p_calibration) { // test if the outer radius is reachable - LOOP_CAL_RAD(axis) { - const float a = RADIANS(210 + (360 / NPP) * (axis - 1)); - if (!position_is_reachable(cos(a) * dcr, sin(a) * dcr)) { - SERIAL_ECHOLNPGM("?Bed calibration radius implausible."); - return; - } - } - } - // Report settings PGM_P const checkingac = PSTR("Checking... AC"); SERIAL_ECHOPGM_P(checkingac); @@ -487,7 +498,7 @@ void GcodeSuite::G33() { // Probe the points zero_std_dev_old = zero_std_dev; - if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each)) { + if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each, probe_at_offset)) { SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666"); return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); } @@ -526,11 +537,11 @@ void GcodeSuite::G33() { #define Z0(I) ZP(0, I) // calculate factors - if (_7p_9_center) calibration_radius_factor = 0.9f; + if (_7p_9_center) dcr *= 0.9f; h_factor = auto_tune_h(); r_factor = auto_tune_r(); a_factor = auto_tune_a(); - calibration_radius_factor = 1.0f; + dcr /= 0.9f; switch (probe_points) { case 0: diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index ba119abc37..c9bcb895fc 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -88,8 +88,9 @@ void _man_probe_pt(const xy_pos_t &xy) { } void _goto_tower_a(const_float_t a) { + constexpr float dcr = DELTA_PRINTABLE_RADIUS; xy_pos_t tower_vec = { cos(RADIANS(a)), sin(RADIANS(a)) }; - _man_probe_pt(tower_vec * delta_calibration_radius()); + _man_probe_pt(tower_vec * dcr); } void _goto_tower_x() { _goto_tower_a(210); } void _goto_tower_y() { _goto_tower_a(330); } diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 4401db5a5b..2a4efb47da 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -82,28 +82,6 @@ void recalc_delta_settings() { set_all_unhomed(); } -/** - * Get a safe radius for calibration - */ - -#if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) - - #if ENABLED(DELTA_AUTO_CALIBRATION) - float calibration_radius_factor = 1; - #endif - - float delta_calibration_radius() { - return calibration_radius_factor * ( - #if HAS_BED_PROBE - FLOOR((DELTA_PRINTABLE_RADIUS) - _MAX(HYPOT(probe.offset_xy.x, probe.offset_xy.y), PROBING_MARGIN)) - #else - DELTA_PRINTABLE_RADIUS - #endif - ); - } - -#endif - /** * Delta Inverse Kinematics * diff --git a/Marlin/src/module/delta.h b/Marlin/src/module/delta.h index 308e206700..f1e43c7e4c 100644 --- a/Marlin/src/module/delta.h +++ b/Marlin/src/module/delta.h @@ -45,19 +45,6 @@ extern abc_float_t delta_diagonal_rod_trim; */ void recalc_delta_settings(); -/** - * Get a safe radius for calibration - */ -#if ENABLED(DELTA_AUTO_CALIBRATION) - extern float calibration_radius_factor; -#else - constexpr float calibration_radius_factor = 1; -#endif - -#if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) - float delta_calibration_radius(); -#endif - /** * Delta Inverse Kinematics * From 29d3996a55d00059437f6c1194bac5eec5b7b2e2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Sep 2021 19:37:33 -0500 Subject: [PATCH 0667/2168] =?UTF-8?q?=F0=9F=93=8C=20Creality=204.3.1=20boa?= =?UTF-8?q?rd=20variants=20(#22704)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Chico --- Marlin/src/core/boards.h | 26 +++++++++++--------- Marlin/src/pins/pins.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 8 +++--- Marlin/src/pins/stm32f1/pins_CREALITY_V431.h | 19 +++++++++++--- 4 files changed, 35 insertions(+), 20 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index dd181baed9..879d02de61 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -340,17 +340,21 @@ #define BOARD_CREALITY_V427 4040 // Creality v4.2.7 (STM32F103RE) #define BOARD_CREALITY_V4210 4041 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 #define BOARD_CREALITY_V431 4042 // Creality v4.3.1 (STM32F103RE) -#define BOARD_CREALITY_V452 4043 // Creality v4.5.2 (STM32F103RE) -#define BOARD_CREALITY_V453 4044 // Creality v4.5.3 (STM32F103RE) -#define BOARD_TRIGORILLA_PRO 4045 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4046 // FLYmaker FLY MINI (STM32F103RCT6) -#define BOARD_FLSUN_HISPEED 4047 // FLSUN HiSpeedV1 (STM32F103VET6) -#define BOARD_BEAST 4048 // STM32F103RET6 Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4049 // STM32F103ZET6 Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4050 // STM32F103VET6 controller -#define BOARD_ZONESTAR_ZM3E2 4051 // Zonestar ZM3E2 (STM32F103RCT6) -#define BOARD_ZONESTAR_ZM3E4 4052 // Zonestar ZM3E4 V1 (STM32F103VCT6) -#define BOARD_ZONESTAR_ZM3E4V2 4053 // Zonestar ZM3E4 V2 (STM32F103VCT6) +#define BOARD_CREALITY_V431_A 4043 // Creality v4.3.1a (STM32F103RE) +#define BOARD_CREALITY_V431_B 4044 // Creality v4.3.1b (STM32F103RE) +#define BOARD_CREALITY_V431_C 4045 // Creality v4.3.1c (STM32F103RE) +#define BOARD_CREALITY_V431_D 4046 // Creality v4.3.1d (STM32F103RE) +#define BOARD_CREALITY_V452 4047 // Creality v4.5.2 (STM32F103RE) +#define BOARD_CREALITY_V453 4048 // Creality v4.5.3 (STM32F103RE) +#define BOARD_TRIGORILLA_PRO 4049 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4050 // FLYmaker FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4051 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4052 // STM32F103RET6 Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4053 // STM32F103ZET6 Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4054 // STM32F103VET6 controller +#define BOARD_ZONESTAR_ZM3E2 4055 // Zonestar ZM3E2 (STM32F103RCT6) +#define BOARD_ZONESTAR_ZM3E4 4056 // Zonestar ZM3E4 V1 (STM32F103VCT6) +#define BOARD_ZONESTAR_ZM3E4V2 4057 // Zonestar ZM3E4 V2 (STM32F103VCT6) // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 7a0d932c61..fa64bc7fbc 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -549,7 +549,7 @@ #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V427) #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple -#elif MB(CREALITY_V431) +#elif MB(CREALITY_V431, CREALITY_V431_A, CREALITY_V431_B, CREALITY_V431_C, CREALITY_V431_D) #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V452) #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 2aa48b7499..c60d4dc2ba 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -88,37 +88,37 @@ // // Steppers // -#define X_ENABLE_PIN PC3 #ifndef X_STEP_PIN #define X_STEP_PIN PC2 #endif #ifndef X_DIR_PIN #define X_DIR_PIN PB9 #endif +#define X_ENABLE_PIN PC3 // Shared -#define Y_ENABLE_PIN PC3 #ifndef Y_STEP_PIN #define Y_STEP_PIN PB8 #endif #ifndef Y_DIR_PIN #define Y_DIR_PIN PB7 #endif +#define Y_ENABLE_PIN X_ENABLE_PIN -#define Z_ENABLE_PIN PC3 #ifndef Z_STEP_PIN #define Z_STEP_PIN PB6 #endif #ifndef Z_DIR_PIN #define Z_DIR_PIN PB5 #endif +#define Z_ENABLE_PIN X_ENABLE_PIN -#define E0_ENABLE_PIN PC3 #ifndef E0_STEP_PIN #define E0_STEP_PIN PB4 #endif #ifndef E0_DIR_PIN #define E0_DIR_PIN PB3 #endif +#define E0_ENABLE_PIN X_ENABLE_PIN // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h index e8ae84da8f..2f1f2ffb41 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h @@ -31,10 +31,21 @@ // // Steppers // -#define X_STEP_PIN PB8 -#define X_DIR_PIN PB7 +#if MB(CREALITY_V431, CREALITY_V431_A, CREALITY_V431_B) -#define Y_STEP_PIN PC2 -#define Y_DIR_PIN PB9 + #define X_STEP_PIN PB8 + #define X_DIR_PIN PB7 + + #define Y_STEP_PIN PC2 + #define Y_DIR_PIN PB9 + +#endif + +#if MB(CREALITY_V431_B, CREALITY_V431_C) + + #define E0_STEP_PIN PB3 + #define E0_DIR_PIN PB4 + +#endif #include "pins_CREALITY_V4.h" From 84f66627c4557ce9a4f231af6b483d59c777bfc4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 13 Sep 2021 01:39:56 +0000 Subject: [PATCH 0668/2168] [cron] Bump distribution date (2021-09-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8560812e1e..d00c13fc80 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-12" +//#define STRING_DISTRIBUTION_DATE "2021-09-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6e445422c8..14d7030a94 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 "2021-09-12" + #define STRING_DISTRIBUTION_DATE "2021-09-13" #endif /** From ea7e777cb13f314ddfeab81e29d7b7a2fc67e7b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Sep 2021 21:21:35 -0500 Subject: [PATCH 0669/2168] =?UTF-8?q?=F0=9F=8E=A8=20Tweak=20custom=20menu?= =?UTF-8?q?=20item=20code?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_configuration.cpp | 49 ++++++---------------- Marlin/src/lcd/menu/menu_main.cpp | 39 ++++------------- 2 files changed, 21 insertions(+), 67 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 2c33e890bf..44c99dd0a9 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -353,11 +353,6 @@ void menu_advanced_settings(); #define HAS_CUSTOM_ITEM_CONF(N) (defined(CONFIG_MENU_ITEM_##N##_DESC) && defined(CONFIG_MENU_ITEM_##N##_GCODE)) - #define CUSTOM_TEST_CONF(N) do{ \ - constexpr char c = CONFIG_MENU_ITEM_##N##_GCODE[strlen(CONFIG_MENU_ITEM_##N##_GCODE) - 1]; \ - static_assert(c != '\n' && c != '\r', "CONFIG_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ - }while(0) - #ifdef CUSTOM_MENU_CONFIG_SCRIPT_DONE #define _DONE_SCRIPT "\n" CUSTOM_MENU_CONFIG_SCRIPT_DONE #else @@ -365,115 +360,97 @@ void menu_advanced_settings(); #endif #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(PSTR(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } #define _CUSTOM_ITEM_CONF(N) ACTION_ITEM_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_CONF(N)); - #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ + #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ SUBMENU_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), []{ \ - MenuItem_confirm::confirm_screen( \ - GCODE_LAMBDA_CONF(N), \ - ui.goto_previous_screen, \ + MenuItem_confirm::confirm_screen( \ + GCODE_LAMBDA_CONF(N), \ + ui.goto_previous_screen, \ PSTR(CONFIG_MENU_ITEM_##N##_DESC "?") \ - ); \ + ); \ }) - #define CUSTOM_ITEM_CONF(N) do{ if (ENABLED(CONFIG_MENU_ITEM_##N##_CONFIRM)) _CUSTOM_ITEM_CONF_CONFIRM(N); else _CUSTOM_ITEM_CONF(N); }while(0) + #define CUSTOM_ITEM_CONF(N) do{ \ + constexpr char c = CONFIG_MENU_ITEM_##N##_GCODE[strlen(CONFIG_MENU_ITEM_##N##_GCODE) - 1]; \ + static_assert(c != '\n' && c != '\r', "CONFIG_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ + if (ENABLED(CONFIG_MENU_ITEM_##N##_CONFIRM)) \ + _CUSTOM_ITEM_CONF_CONFIRM(N); \ + else \ + _CUSTOM_ITEM_CONF(N); \ + }while(0) #if HAS_CUSTOM_ITEM_CONF(1) - CUSTOM_TEST_CONF(1); CUSTOM_ITEM_CONF(1); #endif #if HAS_CUSTOM_ITEM_CONF(2) - CUSTOM_TEST_CONF(2); CUSTOM_ITEM_CONF(2); #endif #if HAS_CUSTOM_ITEM_CONF(3) - CUSTOM_TEST_CONF(3); CUSTOM_ITEM_CONF(3); #endif #if HAS_CUSTOM_ITEM_CONF(4) - CUSTOM_TEST_CONF(4); CUSTOM_ITEM_CONF(4); #endif #if HAS_CUSTOM_ITEM_CONF(5) - CUSTOM_TEST_CONF(5); CUSTOM_ITEM_CONF(5); #endif #if HAS_CUSTOM_ITEM_CONF(6) - CUSTOM_TEST_CONF(6); CUSTOM_ITEM_CONF(6); #endif #if HAS_CUSTOM_ITEM_CONF(7) - CUSTOM_TEST_CONF(7); CUSTOM_ITEM_CONF(7); #endif #if HAS_CUSTOM_ITEM_CONF(8) - CUSTOM_TEST_CONF(8); CUSTOM_ITEM_CONF(8); #endif #if HAS_CUSTOM_ITEM_CONF(9) - CUSTOM_TEST_CONF(9); CUSTOM_ITEM_CONF(9); #endif #if HAS_CUSTOM_ITEM_CONF(10) - CUSTOM_TEST_CONF(10); CUSTOM_ITEM_CONF(10); #endif #if HAS_CUSTOM_ITEM_CONF(11) - CUSTOM_TEST_CONF(11); CUSTOM_ITEM_CONF(11); #endif #if HAS_CUSTOM_ITEM_CONF(12) - CUSTOM_TEST_CONF(12); CUSTOM_ITEM_CONF(12); #endif #if HAS_CUSTOM_ITEM_CONF(13) - CUSTOM_TEST_CONF(13); CUSTOM_ITEM_CONF(13); #endif #if HAS_CUSTOM_ITEM_CONF(14) - CUSTOM_TEST_CONF(14); CUSTOM_ITEM_CONF(14); #endif #if HAS_CUSTOM_ITEM_CONF(15) - CUSTOM_TEST_CONF(15); CUSTOM_ITEM_CONF(15); #endif #if HAS_CUSTOM_ITEM_CONF(16) - CUSTOM_TEST_CONF(16); CUSTOM_ITEM_CONF(16); #endif #if HAS_CUSTOM_ITEM_CONF(17) - CUSTOM_TEST_CONF(17); CUSTOM_ITEM_CONF(17); #endif #if HAS_CUSTOM_ITEM_CONF(18) - CUSTOM_TEST_CONF(18); CUSTOM_ITEM_CONF(18); #endif #if HAS_CUSTOM_ITEM_CONF(19) - CUSTOM_TEST_CONF(19); CUSTOM_ITEM_CONF(19); #endif #if HAS_CUSTOM_ITEM_CONF(20) - CUSTOM_TEST_CONF(20); CUSTOM_ITEM_CONF(20); #endif #if HAS_CUSTOM_ITEM_CONF(21) - CUSTOM_TEST_CONF(21); CUSTOM_ITEM_CONF(21); #endif #if HAS_CUSTOM_ITEM_CONF(22) - CUSTOM_TEST_CONF(22); CUSTOM_ITEM_CONF(22); #endif #if HAS_CUSTOM_ITEM_CONF(23) - CUSTOM_TEST_CONF(23); CUSTOM_ITEM_CONF(23); #endif #if HAS_CUSTOM_ITEM_CONF(24) - CUSTOM_TEST_CONF(24); CUSTOM_ITEM_CONF(24); #endif #if HAS_CUSTOM_ITEM_CONF(25) - CUSTOM_TEST_CONF(25); CUSTOM_ITEM_CONF(25); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 8fce2038a3..be12fb5134 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -118,11 +118,6 @@ void menu_configuration(); #define HAS_CUSTOM_ITEM_MAIN(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) - #define CUSTOM_TEST_MAIN(N) do{ \ - constexpr char c = MAIN_MENU_ITEM_##N##_GCODE[strlen(MAIN_MENU_ITEM_##N##_GCODE) - 1]; \ - static_assert(c != '\n' && c != '\r', "MAIN_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ - }while(0) - #ifdef MAIN_MENU_ITEM_SCRIPT_DONE #define _DONE_SCRIPT "\n" MAIN_MENU_ITEM_SCRIPT_DONE #else @@ -139,106 +134,88 @@ void menu_configuration(); ); \ }) - #define CUSTOM_ITEM_MAIN(N) do{ if (ENABLED(MAIN_MENU_ITEM_##N##_CONFIRM)) _CUSTOM_ITEM_MAIN_CONFIRM(N); else _CUSTOM_ITEM_MAIN(N); }while(0) + #define CUSTOM_ITEM_MAIN(N) do{ \ + constexpr char c = MAIN_MENU_ITEM_##N##_GCODE[strlen(MAIN_MENU_ITEM_##N##_GCODE) - 1]; \ + static_assert(c != '\n' && c != '\r', "MAIN_MENU_ITEM_" STRINGIFY(N) "_GCODE cannot have a newline at the end. Please remove it."); \ + if (ENABLED(MAIN_MENU_ITEM_##N##_CONFIRM)) \ + _CUSTOM_ITEM_MAIN_CONFIRM(N); \ + else \ + _CUSTOM_ITEM_MAIN(N); \ + }while(0) #if HAS_CUSTOM_ITEM_MAIN(1) - CUSTOM_TEST_MAIN(1); CUSTOM_ITEM_MAIN(1); #endif #if HAS_CUSTOM_ITEM_MAIN(2) - CUSTOM_TEST_MAIN(2); CUSTOM_ITEM_MAIN(2); #endif #if HAS_CUSTOM_ITEM_MAIN(3) - CUSTOM_TEST_MAIN(3); CUSTOM_ITEM_MAIN(3); #endif #if HAS_CUSTOM_ITEM_MAIN(4) - CUSTOM_TEST_MAIN(4); CUSTOM_ITEM_MAIN(4); #endif #if HAS_CUSTOM_ITEM_MAIN(5) - CUSTOM_TEST_MAIN(5); CUSTOM_ITEM_MAIN(5); #endif #if HAS_CUSTOM_ITEM_MAIN(6) - CUSTOM_TEST_MAIN(6); CUSTOM_ITEM_MAIN(6); #endif #if HAS_CUSTOM_ITEM_MAIN(7) - CUSTOM_TEST_MAIN(7); CUSTOM_ITEM_MAIN(7); #endif #if HAS_CUSTOM_ITEM_MAIN(8) - CUSTOM_TEST_MAIN(8); CUSTOM_ITEM_MAIN(8); #endif #if HAS_CUSTOM_ITEM_MAIN(9) - CUSTOM_TEST_MAIN(9); CUSTOM_ITEM_MAIN(9); #endif #if HAS_CUSTOM_ITEM_MAIN(10) - CUSTOM_TEST_MAIN(10); CUSTOM_ITEM_MAIN(10); #endif #if HAS_CUSTOM_ITEM_MAIN(11) - CUSTOM_TEST_MAIN(11); CUSTOM_ITEM_MAIN(11); #endif #if HAS_CUSTOM_ITEM_MAIN(12) - CUSTOM_TEST_MAIN(12); CUSTOM_ITEM_MAIN(12); #endif #if HAS_CUSTOM_ITEM_MAIN(13) - CUSTOM_TEST_MAIN(13); CUSTOM_ITEM_MAIN(13); #endif #if HAS_CUSTOM_ITEM_MAIN(14) - CUSTOM_TEST_MAIN(14); CUSTOM_ITEM_MAIN(14); #endif #if HAS_CUSTOM_ITEM_MAIN(15) - CUSTOM_TEST_MAIN(15); CUSTOM_ITEM_MAIN(15); #endif #if HAS_CUSTOM_ITEM_MAIN(16) - CUSTOM_TEST_MAIN(16); CUSTOM_ITEM_MAIN(16); #endif #if HAS_CUSTOM_ITEM_MAIN(17) - CUSTOM_TEST_MAIN(17); CUSTOM_ITEM_MAIN(17); #endif #if HAS_CUSTOM_ITEM_MAIN(18) - CUSTOM_TEST_MAIN(18); CUSTOM_ITEM_MAIN(18); #endif #if HAS_CUSTOM_ITEM_MAIN(19) - CUSTOM_TEST_MAIN(19); CUSTOM_ITEM_MAIN(19); #endif #if HAS_CUSTOM_ITEM_MAIN(20) - CUSTOM_TEST_MAIN(20); CUSTOM_ITEM_MAIN(20); #endif #if HAS_CUSTOM_ITEM_MAIN(21) - CUSTOM_TEST_MAIN(21); CUSTOM_ITEM_MAIN(21); #endif #if HAS_CUSTOM_ITEM_MAIN(22) - CUSTOM_TEST_MAIN(22); CUSTOM_ITEM_MAIN(22); #endif #if HAS_CUSTOM_ITEM_MAIN(23) - CUSTOM_TEST_MAIN(23); CUSTOM_ITEM_MAIN(23); #endif #if HAS_CUSTOM_ITEM_MAIN(24) - CUSTOM_TEST_MAIN(24); CUSTOM_ITEM_MAIN(24); #endif #if HAS_CUSTOM_ITEM_MAIN(25) - CUSTOM_TEST_MAIN(25); CUSTOM_ITEM_MAIN(25); #endif END_MENU(); From 24460052d245bc9b56813aab67d52a96a858e034 Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Sun, 12 Sep 2021 21:30:09 -0500 Subject: [PATCH 0670/2168] =?UTF-8?q?=E2=9C=A8=20MKS=20Robin=20Nano=20V1.3?= =?UTF-8?q?=20(STM32F407VET6)=20(#22749)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 1 + Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 9 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 4 +- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 184 +-------------- .../pins/stm32f1/pins_MKS_ROBIN_NANO_common.h | 210 ++++++++++++++++++ .../stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h | 45 ++++ .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 9 +- ini/stm32f4.ini | 24 ++ 9 files changed, 292 insertions(+), 196 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h create mode 100644 Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 879d02de61..46b2e5cf0c 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -401,6 +401,7 @@ #define BOARD_FYSETC_CHEETAH_V20 4231 // FYSETC Cheetah V2.0 #define BOARD_TH3D_EZBOARD_LITE_V2 4232 // TH3D EZBoard Lite v2.0 #define BOARD_INDEX_REV03 4233 // Index PnP Controller REV03 (STM32F407VET6/VGT6) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4234 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VET6) // // ARM Cortex M7 diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index e324c32def..68430fe517 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -347,13 +347,8 @@ void tft_style_init() { style_num_key_rel.body.grad_color = LV_COLOR_KEY_BACKGROUND; style_num_key_rel.text.color = LV_COLOR_TEXT; style_num_key_rel.text.sel_color = LV_COLOR_TEXT; - #if HAS_SPI_FLASH_FONT - style_num_key_pre.text.font = &gb2312_puhui32; - style_num_key_rel.text.font = &gb2312_puhui32; - #else - style_num_key_pre.text.font = LV_FONT_DEFAULT; - style_num_key_rel.text.font = LV_FONT_DEFAULT; - #endif + style_num_key_pre.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_num_key_rel.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); style_num_key_pre.line.width = 0; style_num_key_rel.line.width = 0; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index cfd6db15fd..79990ea42a 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -192,9 +192,7 @@ void tft_lvgl_init() { systick_attach_callback(SysTick_Callback); - #if HAS_SPI_FLASH_FONT - init_gb2312_font(); - #endif + TERN_(HAS_SPI_FLASH_FONT, init_gb2312_font()); tft_style_init(); filament_pin_setup(); diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index fa64bc7fbc..0293da1dba 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -649,6 +649,8 @@ #include "stm32f4/pins_TH3D_EZBOARD_LITE_V2.h" // STM32F4 env:TH3D_EZBoard_Lite_V2 #elif MB(INDEX_REV03) #include "stm32f4/pins_INDEX_REV03.h" // STM32F4 env:Index_Mobo_Rev03 +#elif MB(MKS_ROBIN_NANO_V1_3_F4) + #include "stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h" // STM32F4 env:mks_robin_nano_v1_3_f4 // // ARM Cortex M7 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index 975ecb8bd5..c729274c54 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -26,200 +26,22 @@ * https://github.com/makerbase-mks/MKS-Robin-Nano-V1.X/tree/master/hardware */ -#if NOT_TARGET(STM32F1, STM32F1xx) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." -#endif +#define ALLOW_STM32DUINO +#include "env_validate.h" #define BOARD_INFO_NAME "MKS Robin Nano" -#define BOARD_NO_NATIVE_USB - -// Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 - // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // #define DISABLE_JTAG -// -// EEPROM -// -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) - #define FLASH_EEPROM_EMULATION - #define EEPROM_PAGE_SIZE (0x800U) // 2KB - #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) - #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB -#endif - -#define SPI_DEVICE 2 - -// -// Servos -// -#define SERVO0_PIN PA8 // Enable BLTOUCH - -// -// Limit Switches -// -#define X_STOP_PIN PA15 -#define Y_STOP_PIN PA12 -#define Z_MIN_PIN PA11 -#define Z_MAX_PIN PC4 - -// -// Steppers -// -#define X_ENABLE_PIN PE4 -#define X_STEP_PIN PE3 -#define X_DIR_PIN PE2 - -#define Y_ENABLE_PIN PE1 -#define Y_STEP_PIN PE0 -#define Y_DIR_PIN PB9 - -#define Z_ENABLE_PIN PB8 -#define Z_STEP_PIN PB5 -#define Z_DIR_PIN PB4 - -#define E0_ENABLE_PIN PB3 -#define E0_STEP_PIN PD6 -#define E0_DIR_PIN PD3 - -#define E1_ENABLE_PIN PA3 -#define E1_STEP_PIN PA6 -#define E1_DIR_PIN PA1 - -// -// Temperature Sensors -// -#define TEMP_0_PIN PC1 // TH1 -#define TEMP_1_PIN PC2 // TH2 -#define TEMP_BED_PIN PC0 // TB1 - -// -// Heaters / Fans -// -#ifndef HEATER_0_PIN - #define HEATER_0_PIN PC3 -#endif -#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) - #ifndef FAN1_PIN - #define FAN1_PIN PB0 - #endif -#else - #ifndef HEATER_1_PIN - #define HEATER_1_PIN PB0 - #endif -#endif -#ifndef FAN_PIN - #define FAN_PIN PB1 // FAN -#endif -#ifndef HEATER_BED_PIN - #define HEATER_BED_PIN PA0 -#endif - // // Thermocouples // //#define TEMP_0_CS_PIN PE5 // TC1 - CS1 //#define TEMP_0_CS_PIN PE6 // TC2 - CS2 -// -// Power Supply Control -// -#if ENABLED(MKS_PWC) - #if ENABLED(TFT_LVGL_UI) - #undef PSU_CONTROL - #undef MKS_PWC - #define SUICIDE_PIN PB2 - #define SUICIDE_PIN_STATE LOW - #else - #define PS_ON_PIN PB2 // PW_OFF - #endif - #define KILL_PIN PA2 - #define KILL_PIN_STATE HIGH -#endif - -// -// Misc. Functions -// -#if HAS_TFT_LVGL_UI - #define MT_DET_1_PIN PA4 - #define MT_DET_2_PIN PE6 - #define MT_DET_PIN_STATE LOW - - #define WIFI_IO0_PIN PC13 - #define WIFI_IO1_PIN PC7 - #define WIFI_RESET_PIN PA5 -#else - //#define POWER_LOSS_PIN PA2 // PW_DET - //#define PS_ON_PIN PB2 // PW_OFF - #define FIL_RUNOUT_PIN PA4 - #define FIL_RUNOUT2_PIN PE6 -#endif - //#define LED_PIN PB2 -// -// SD Card -// -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#define SDIO_SUPPORT -#define SDIO_CLOCK 4500000 // 4.5 MHz -#define SD_DETECT_PIN PD12 -#define ONBOARD_SD_CS_PIN PC11 - -// -// LCD / Controller -// -#define BEEPER_PIN PC5 - -// -// TFT with FSMC interface -// -#if HAS_FSMC_TFT - /** - * Note: MKS Robin TFT screens use various TFT controllers. - * If the screen stays white, disable 'TFT_RESET_PIN' - * to let the bootloader init the screen. - */ - #define TFT_RESET_PIN PC6 // FSMC_RST - #define TFT_BACKLIGHT_PIN PD13 - - #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h - #define DOGLCD_SCK -1 - - #define TOUCH_CS_PIN PA7 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 // SPI2_SCK - #define TOUCH_MISO_PIN PB14 // SPI2_MISO - #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI - - #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 - #define FSMC_RS_PIN PD11 - #define FSMC_DMA_DEV DMA2 - #define FSMC_DMA_CHANNEL DMA_CH5 - - #define TFT_CS_PIN FSMC_CS_PIN - #define TFT_RS_PIN FSMC_RS_PIN - - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 - - #define TFT_BUFFER_SIZE 14400 -#endif - -#define HAS_SPI_FLASH 1 -#if HAS_SPI_FLASH - #define SPI_FLASH_SIZE 0x1000000 // 16MB - #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 - #define SPI_FLASH_SCK_PIN PB13 -#endif +#include "pins_MKS_ROBIN_NANO_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h new file mode 100644 index 0000000000..c76175a35c --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -0,0 +1,210 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * MKS Robin Nano board common pin assignments + */ + +#if HOTENDS > 2 || E_STEPPERS > 2 + #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." +#endif + +#define BOARD_NO_NATIVE_USB + +// Avoid conflict with TIMER_SERVO when using the STM32 HAL +#define TEMP_TIMER 5 + +// +// EEPROM +// +#if ENABLED(SRAM_EEPROM_EMULATION) + #undef NO_EEPROM_SELECTED +#endif +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE (0x800U) // 2KB + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2KB +#endif + +#define SPI_DEVICE 2 + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches +// +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA12 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 + +// +// Steppers +// +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 + +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 + +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 + +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 + +#define E1_ENABLE_PIN PA3 +#define E1_STEP_PIN PA6 +#define E1_DIR_PIN PA1 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_BED_PIN PC0 // TB1 + +// +// Heaters / Fans +// +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PC3 +#endif +#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) + #ifndef FAN1_PIN + #define FAN1_PIN PB0 + #endif +#else + #ifndef HEATER_1_PIN + #define HEATER_1_PIN PB0 + #endif +#endif +#ifndef FAN_PIN + #define FAN_PIN PB1 // FAN +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PA0 +#endif + +// +// Power Supply Control +// +#if ENABLED(MKS_PWC) + #if ENABLED(TFT_LVGL_UI) + #undef PSU_CONTROL + #undef MKS_PWC + #define SUICIDE_PIN PB2 + #define SUICIDE_PIN_STATE LOW + #else + #define PS_ON_PIN PB2 // PW_OFF + #endif + #define KILL_PIN PA2 + #define KILL_PIN_STATE HIGH +#endif + +// +// Misc. Functions +// +#if HAS_TFT_LVGL_UI + #define MT_DET_1_PIN PA4 + #define MT_DET_2_PIN PE6 + #define MT_DET_PIN_STATE LOW + + #define WIFI_IO0_PIN PC13 + #define WIFI_IO1_PIN PC7 + #define WIFI_RESET_PIN PA5 +#else + //#define POWER_LOSS_PIN PA2 // PW_DET + //#define PS_ON_PIN PB2 // PW_OFF + #define FIL_RUNOUT_PIN PA4 + #define FIL_RUNOUT2_PIN PE6 +#endif + +// +// SD Card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#define SDIO_SUPPORT +#define SDIO_CLOCK 4500000 // 4.5 MHz +#define SD_DETECT_PIN PD12 +#define ONBOARD_SD_CS_PIN PC11 + +// +// LCD / Controller +// +#define BEEPER_PIN PC5 + +// +// TFT with FSMC interface +// +#if HAS_FSMC_TFT + /** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'TFT_RESET_PIN' + * to let the bootloader init the screen. + */ + #define TFT_RESET_PIN PC6 // FSMC_RST + #define TFT_BACKLIGHT_PIN PD13 + + #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h + #define DOGLCD_SCK -1 + + #define TOUCH_CS_PIN PA7 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 // SPI2_SCK + #define TOUCH_MISO_PIN PB14 // SPI2_MISO + #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI + + #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT + #define FSMC_CS_PIN PD7 + #define FSMC_RS_PIN PD11 + #define FSMC_DMA_DEV DMA2 + #define FSMC_DMA_CHANNEL DMA_CH5 + + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + + #define TFT_BUFFER_SIZE 14400 +#endif + +#define HAS_SPI_FLASH 1 +#if HAS_SPI_FLASH + #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_MOSI_PIN PB15 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_SCK_PIN PB13 +#endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h new file mode 100644 index 0000000000..3cba69a7b3 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h @@ -0,0 +1,45 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * MKS Robin nano V1.3 (STM32F407VET6) board pin assignments + * https://github.com/makerbase-mks/MKS-Robin-Nano-V1.X/tree/master/hardware + */ + +#define ALLOW_STM32DUINO +#include "env_validate.h" + +#define BOARD_INFO_NAME "MKS Robin Nano V1.3" + +// +// EEPROM +// Use one of these or SDCard-based Emulation will be used +// +#if NO_EEPROM_SELECTED + //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation + //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation +#endif + +#define LED_PIN PB1 + +#include "../stm32f1/pins_MKS_ROBIN_NANO_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index e78807e1af..c9762a6914 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -67,11 +67,10 @@ #define E0_DIAG_PIN PC4 #define E1_DIAG_PIN PE7 -// -#define X_STOP_PIN PA15 -#define Y_STOP_PIN PD2 -#define Z_MIN_PIN PC8 -#define Z_MAX_PIN PC4 +#define X_STOP_PIN X_DIAG_PIN +#define Y_STOP_PIN Y_DIAG_PIN +#define Z_MIN_PIN Z_DIAG_PIN +#define Z_MAX_PIN E0_DIAG_PIN // // Steppers diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 84256d3be9..c8f8676b68 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -464,3 +464,27 @@ board_upload.offset_address = 0x0800C000 build_flags = ${stm32_variant.build_flags} -DHSE_VALUE=12000000U -O0 debug_tool = stlink upload_protocol = stlink + +# +# BOARD_MKS_ROBIN_NANO_V1_3_F4 +# - MKS Robin Nano V1.3 (STM32F407VET6) 5 Pololu Plug +# - MKS Robin Nano-S V1.3 (STM32F407VET6) 4 TMC2225 + 1 Pololu Plug +# +[env:mks_robin_nano_v1_3_f4] +platform = ${common_stm32.platform} +extends = stm32_variant +board = marlin_STM32F407VGT6_CCM +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0x8000 +board_upload.offset_address = 0x08008000 +board_build.rename = Robin_nano35.bin +build_flags = ${stm32_variant.build_flags} + -DMCU_STM32F407VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 + -DSTM32_FLASH_SIZE=512 + -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 + -DHAL_SD_MODULE_ENABLED + -DHAL_SRAM_MODULE_ENABLED +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC +debug_tool = jlink +upload_protocol = jlink From d69c053225bab92bf53bec064a1830079a2092f9 Mon Sep 17 00:00:00 2001 From: Vert <45634861+Vertabreak@users.noreply.github.com> Date: Sun, 12 Sep 2021 22:39:52 -0400 Subject: [PATCH 0671/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20ENABLED=20=3D>?= =?UTF-8?q?=20EITHER=20typo=20(#22756)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/marlinui.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index fc7e05b896..7f8891b514 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -241,7 +241,7 @@ #define LCD_ST7920_DELAY_2 125 #define LCD_ST7920_DELAY_3 125 -#elif ENABLED(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) +#elif EITHER(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) #define IS_RRD_FG_SC 1 #define LCD_ST7920_DELAY_1 150 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 35ee74b5aa..5e627ff79c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -43,7 +43,7 @@ #define TEST2 1 #define TEST3 0 #define TEST4 true -#if ENABLED(TEST0) || !ENABLED(TEST2) || ENABLED(TEST3) +#if ENABLED(TEST0) || !ENABLED(TEST2) || ENABLED(TEST3) || !ENABLED(TEST1, TEST2, TEST4) #error "ENABLED is borked!" #endif #if BOTH(TEST0, TEST1) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 67ad99ba2b..5e5b7a94bc 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -32,7 +32,7 @@ #include "../feature/host_actions.h" #endif -#if ENABLED(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) +#if BOTH(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) #include "../feature/password/password.h" #endif From 000d412da60727661176fe6416c3517dd4b4be3d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Sep 2021 21:41:24 -0500 Subject: [PATCH 0672/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20CUSTOM=5FMENU=5F?= =?UTF-8?q?MAIN=5FSCRIPT=5FDONE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fix #22762 --- Marlin/src/lcd/menu/menu_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index be12fb5134..1bf6645e2e 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -118,8 +118,8 @@ void menu_configuration(); #define HAS_CUSTOM_ITEM_MAIN(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) - #ifdef MAIN_MENU_ITEM_SCRIPT_DONE - #define _DONE_SCRIPT "\n" MAIN_MENU_ITEM_SCRIPT_DONE + #ifdef CUSTOM_MENU_MAIN_SCRIPT_DONE + #define _DONE_SCRIPT "\n" CUSTOM_MENU_MAIN_SCRIPT_DONE #else #define _DONE_SCRIPT "" #endif From 798a8a7a0852c12fb8640c4a531fac70fbc57eda Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Sep 2021 16:28:12 -0500 Subject: [PATCH 0673/2168] =?UTF-8?q?=F0=9F=94=A7=20SPINDLE=5FLASER=5FPWM?= =?UTF-8?q?=20=3D>=20SPINDLE=5FLASER=5FUSE=5FPWM?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 30 ++++++++++++--------- Marlin/src/HAL/AVR/inc/SanityCheck.h | 4 +-- Marlin/src/HAL/LINUX/inc/SanityCheck.h | 2 +- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 2 +- Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h | 2 +- Marlin/src/HAL/STM32/inc/SanityCheck.h | 2 +- Marlin/src/feature/spindle_laser.cpp | 8 +++--- Marlin/src/feature/spindle_laser.h | 16 +++++------ Marlin/src/gcode/control/M3-M5.cpp | 6 ++--- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 18 +++++++------ Marlin/src/lcd/menu/menu_spindle_laser.cpp | 2 +- Marlin/src/module/stepper.cpp | 4 +-- Marlin/src/module/stepper.h | 6 ++--- 15 files changed, 57 insertions(+), 49 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6857c4063b..f525aef304 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3323,11 +3323,13 @@ //#define SPINDLE_FEATURE //#define LASER_FEATURE #if EITHER(SPINDLE_FEATURE, LASER_FEATURE) - #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if the on/off function is active HIGH - #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power - #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH - #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + #define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + #endif //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 #if ENABLED(AIR_EVACUATION) @@ -3383,17 +3385,21 @@ * Speed/Power = (PWMDC / 255 * 100 - SPEED_POWER_INTERCEPT) / SPEED_POWER_SLOPE * PWMDC = (spdpwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) / SPEED_POWER_SLOPE */ - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 5000 // (RPM) - #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM - #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 5000 // (RPM) + #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) + #endif #else - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 0 // (%) 0-100 - #define SPEED_POWER_MAX 100 // (%) 0-100 - #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 0 // (%) 0-100 + #define SPEED_POWER_MAX 100 // (%) 0-100 + #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) + #endif // Define the minimum and maximum test pulse time values for a laser test fire function #define LASER_TEST_PULSE_MIN 1 // Used with Laser Control Menu diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 51ba247953..79809b8f61 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -35,7 +35,7 @@ /** * Sanity checks for Spindle / Laser PWM */ -#if ENABLED(SPINDLE_LASER_PWM) +#if ENABLED(SPINDLE_LASER_USE_PWM) #include "../ServoTimers.h" // Needed to check timer availability (_useTimer3) #if SPINDLE_LASER_PWM_PIN == 4 || WITHIN(SPINDLE_LASER_PWM_PIN, 11, 13) #error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by a system interrupt." @@ -43,7 +43,7 @@ #error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by the servo system." #endif #elif defined(SPINDLE_LASER_FREQUENCY) - #error "SPINDLE_LASER_FREQUENCY requires SPINDLE_LASER_PWM." + #error "SPINDLE_LASER_FREQUENCY requires SPINDLE_LASER_USE_PWM." #endif /** diff --git a/Marlin/src/HAL/LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h index 45bb2662ac..36d3190a3e 100644 --- a/Marlin/src/HAL/LINUX/inc/SanityCheck.h +++ b/Marlin/src/HAL/LINUX/inc/SanityCheck.h @@ -26,7 +26,7 @@ */ // Emulating RAMPS -#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) +#if ENABLED(SPINDLE_LASER_USE_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 diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 23d797b2ab..3ea054589e 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -67,7 +67,7 @@ static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are in * 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) +//#if ENABLED(SPINDLE_LASER_USE_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 diff --git a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h index 104af9af5b..2d7bef23a3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h +++ b/Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h @@ -26,7 +26,7 @@ */ // Emulating RAMPS -#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) +#if ENABLED(SPINDLE_LASER_USE_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 diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 12ff2abec7..0f1a2acaa4 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -24,7 +24,7 @@ /** * Test STM32-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) +//#if ENABLED(SPINDLE_LASER_USE_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 diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 68a84e1aba..ea6fc4990e 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -64,7 +64,7 @@ void SpindleLaser::init() { #if ENABLED(SPINDLE_CHANGE_DIR) OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // Init rotation to clockwise (M3) #endif - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif @@ -83,7 +83,7 @@ void SpindleLaser::init() { #endif } -#if ENABLED(SPINDLE_LASER_PWM) +#if ENABLED(SPINDLE_LASER_USE_PWM) /** * Set the cutter PWM directly to the given ocr value * @@ -107,7 +107,7 @@ void SpindleLaser::init() { WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF _set_ocr(0); } -#endif // SPINDLE_LASER_PWM +#endif // SPINDLE_LASER_USE_PWM /** * Apply power for laser/spindle @@ -121,7 +121,7 @@ void SpindleLaser::apply_power(const uint8_t opwr) { if (opwr == last_power_applied) return; last_power_applied = opwr; power = opwr; - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) if (cutter.unitPower == 0 && CUTTER_UNIT_IS(RPM)) { ocr_off(); isReady = false; diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 9a2d05c79d..ba82c4d731 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -123,7 +123,7 @@ public: FORCE_INLINE static void refresh() { apply_power(power); } FORCE_INLINE static void set_power(const uint8_t upwr) { power = upwr; refresh(); } - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) private: @@ -186,7 +186,7 @@ public: } return upwr; } - #endif // SPINDLE_LASER_PWM + #endif // SPINDLE_LASER_USE_PWM /** * Enable/Disable spindle/laser @@ -195,7 +195,7 @@ public: static inline void set_enabled(const bool enable) { uint8_t value = 0; if (enable) { - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) if (power) value = power; else if (unitPower) @@ -249,7 +249,7 @@ public: #if HAS_LCD_MENU static inline void enable_with_dir(const bool reverse) { isReady = true; - const uint8_t ocr = TERN(SPINDLE_LASER_PWM, upower_to_ocr(menuPower), 255); + const uint8_t ocr = TERN(SPINDLE_LASER_USE_PWM, upower_to_ocr(menuPower), 255); if (menuPower) power = ocr; else @@ -262,7 +262,7 @@ public: FORCE_INLINE static void enable_reverse() { enable_with_dir(true); } FORCE_INLINE static void enable_same_dir() { enable_with_dir(is_reverse()); } - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) static inline void update_from_mpower() { if (isReady) power = upower_to_ocr(menuPower); unitPower = menuPower; @@ -308,14 +308,14 @@ public: isReady = false; unitPower = menuPower = 0; planner.laser_inline.status.isPlanned = false; - TERN(SPINDLE_LASER_PWM, inline_ocr_power, inline_power)(0); + TERN(SPINDLE_LASER_USE_PWM, inline_ocr_power, inline_power)(0); } } // Set the power for subsequent movement blocks static void inline_power(const cutter_power_t upwr) { unitPower = menuPower = upwr; - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) #if ENABLED(SPEED_POWER_RELATIVE) && !CUTTER_UNIT_IS(RPM) // relative mode does not turn laser off at 0, except for RPM planner.laser_inline.status.isEnabled = true; planner.laser_inline.power = upower_to_ocr(upwr); @@ -332,7 +332,7 @@ public: static inline void inline_direction(const bool) { /* never */ } - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) static inline void inline_ocr_power(const uint8_t ocrpwr) { isReady = ocrpwr > 0; planner.laser_inline.status.isEnabled = ocrpwr > 0; diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index ff5ab5086e..ecae8b06c6 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -72,7 +72,7 @@ void GcodeSuite::M3_M4(const bool is_M4) { #if ENABLED(SPINDLE_SERVO) cutter.unitPower = spwr; #else - cutter.unitPower = TERN(SPINDLE_LASER_PWM, + cutter.unitPower = TERN(SPINDLE_LASER_USE_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0); #endif @@ -86,7 +86,7 @@ void GcodeSuite::M3_M4(const bool is_M4) { if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { // Laser power in inline mode cutter.inline_direction(is_M4); // Should always be unused - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) if (parser.seen('O')) { cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0); cutter.inline_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) @@ -105,7 +105,7 @@ void GcodeSuite::M3_M4(const bool is_M4) { planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power cutter.set_reverse(is_M4); - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) if (parser.seenval('O')) { cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0); cutter.ocr_set_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 477d43ed63..e3b90b65b3 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -215,7 +215,7 @@ void GcodeSuite::get_destination_from_command() { // Set the laser power in the planner to configure this move if (parser.seen('S')) { const float spwr = parser.value_float(); - cutter.inline_power(TERN(SPINDLE_LASER_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0)); + cutter.inline_power(TERN(SPINDLE_LASER_USE_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0)); } else if (ENABLED(LASER_MOVE_G0_OFF) && parser.codenum == 0) // G0 cutter.set_inline_enabled(false); diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 9fae92affe..94332c9268 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -658,7 +658,7 @@ #endif // Add features that need hardware PWM here -#if ANY(FAST_PWM_FAN, SPINDLE_LASER_PWM) +#if ANY(FAST_PWM_FAN, SPINDLE_LASER_USE_PWM) #define NEEDS_HARDWARE_PWM 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 5e627ff79c..ab8b252ba6 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -593,6 +593,8 @@ #error "ARC_SUPPORT no longer uses ARC_SEGMENTS_PER_R." #elif ENABLED(ARC_SUPPORT) && (!defined(MIN_ARC_SEGMENT_MM) || !defined(MAX_ARC_SEGMENT_MM)) #error "ARC_SUPPORT now requires MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM." +#elif defined(SPINDLE_LASER_PWM) + #error "SPINDLE_LASER_PWM (true) is now set with SPINDLE_LASER_USE_PWM (enabled)." #endif #if MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) @@ -3558,8 +3560,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER." #endif #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) - #if DISABLED(SPINDLE_LASER_PWM) - #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_PWM to function." + #if DISABLED(SPINDLE_LASER_USE_PWM) + #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_USE_PWM to function." #elif ENABLED(S_CURVE_ACCELERATION) //#ifndef LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN // #define LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN @@ -3591,21 +3593,21 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN or SPINDLE_SERVO to control the power." #elif ENABLED(SPINDLE_CHANGE_DIR) && !PIN_EXISTS(SPINDLE_DIR) #error "SPINDLE_DIR_PIN is required for SPINDLE_CHANGE_DIR." - #elif ENABLED(SPINDLE_LASER_PWM) + #elif ENABLED(SPINDLE_LASER_USE_PWM) #if !defined(SPINDLE_LASER_PWM_PIN) || SPINDLE_LASER_PWM_PIN < 0 - #error "SPINDLE_LASER_PWM_PIN is required for SPINDLE_LASER_PWM." + #error "SPINDLE_LASER_PWM_PIN is required for SPINDLE_LASER_USE_PWM." #elif !_TEST_PWM(SPINDLE_LASER_PWM_PIN) #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin." #elif !defined(SPINDLE_LASER_PWM_INVERT) #error "SPINDLE_LASER_PWM_INVERT is required for (SPINDLE|LASER)_FEATURE." #elif !(defined(SPEED_POWER_INTERCEPT) && defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP)) - #error "SPINDLE_LASER_PWM equation constant(s) missing." + #error "SPINDLE_LASER_USE_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) - #error "SPINDLE_LASER_PWM pin conflicts with X_MIN_PIN." + #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MIN_PIN." #elif _PIN_CONFLICT(X_MAX) - #error "SPINDLE_LASER_PWM pin conflicts with X_MAX_PIN." + #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MAX_PIN." #elif _PIN_CONFLICT(Z_STEP) - #error "SPINDLE_LASER_PWM pin conflicts with Z_STEP_PIN." + #error "SPINDLE_LASER_USE_PWM pin conflicts with Z_STEP_PIN." #elif _PIN_CONFLICT(CASE_LIGHT) #error "SPINDLE_LASER_PWM_PIN conflicts with CASE_LIGHT_PIN." #elif _PIN_CONFLICT(E0_AUTO_FAN) diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index a28c614c91..26f555ad62 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -41,7 +41,7 @@ START_MENU(); BACK_ITEM(MSG_MAIN); - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) // Change the cutter's "current power" value without turning the cutter on or off // Power is displayed and set in units and range according to CUTTER_POWER_UNIT EDIT_ITEM_FAST(CUTTER_MENU_POWER_TYPE, MSG_CUTTER(POWER), &cutter.menuPower, diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index aea5f88c06..83aa15063b 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2255,7 +2255,7 @@ uint32_t Stepper::block_phase_isr() { } #else if (stat.isPlanned) { // Planner controls the laser - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) cutter.ocr_set_power( stat.isEnabled ? current_block->laser.power : 0 // ON with power or OFF ); @@ -2303,7 +2303,7 @@ uint32_t Stepper::block_phase_isr() { // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed const power_status_t stat = planner.laser_inline.status; if (stat.isPlanned) { // Planner controls the laser - #if ENABLED(SPINDLE_LASER_PWM) + #if ENABLED(SPINDLE_LASER_USE_PWM) cutter.ocr_set_power( stat.isEnabled ? planner.laser_inline.power : 0 // ON with power or OFF ); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 236ba5ee98..d2f42b63fc 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -372,11 +372,11 @@ class Stepper { uint8_t cur_power; // Current laser power bool cruise_set; // Power set up for cruising? - #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + uint16_t till_update; // Countdown to the next update + #else uint32_t last_step_count, // Step count from the last update acc_step_count; // Bresenham counter for laser accel/decel - #else - uint16_t till_update; // Countdown to the next update #endif } stepper_laser_t; From 3587ef2e8f3086104754f1e5e192f0584a709627 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Sep 2021 16:38:51 -0500 Subject: [PATCH 0674/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20old=20spindle/la?= =?UTF-8?q?ser=20options?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 4 ++-- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 24 +++++++++++------------ 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 27ec998891..dcf25da070 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -112,9 +112,9 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if ENABLED(SPINDLE_LASER_ENABLE) +#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! + #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM #endif diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index a43f10fc93..01769fbff0 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -224,28 +224,28 @@ #endif // -// Case Light +// M3/M4/M5 - Spindle/Laser Control // -#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN) +#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_DIR_PIN 65 #endif #endif // -// M3/M4/M5 - Spindle/Laser Control +// Case Light // -#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE) +#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) #if !NUM_SERVOS // Prefer the servo connector - #define SPINDLE_LASER_ENABLE_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #define CASE_LIGHT_PIN 6 // Hardware PWM #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENABLE_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define CASE_LIGHT_PIN 44 // Hardware PWM #endif #endif From 370ea116f46f78536d99ec140a2de2d1d52942f5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Roman=20Morav=C4=8D=C3=ADk?= Date: Tue, 14 Sep 2021 00:10:30 +0200 Subject: [PATCH 0675/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Slovak=20lang?= =?UTF-8?q?uage=20(#22752)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_sk.h | 40 +++++++++++++++++++++++++-- 1 file changed, 37 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 2fda9b8794..284fb9554a 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -68,10 +68,22 @@ namespace Language_sk { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Uvolniť motory"); PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Ponuka ladenia"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. priebehu"); + PROGMEM Language_Str MSG_HOMING = _UxGT("Parkovanie"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Domovská pozícia"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Domov os X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Domov os Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Domov os ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Domov os ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Domov os ") LCD_STR_K; + PROGMEM Language_Str MSG_FILAMENT_SET = _UxGT("Nastav. filamentu"); + PROGMEM Language_Str MSG_FILAMENT_MAN = _UxGT("Správa filamentu"); + PROGMEM Language_Str MSG_LEVBED_FL = _UxGT("Ľavý predný"); + PROGMEM Language_Str MSG_LEVBED_FR = _UxGT("Pravý predný"); + PROGMEM Language_Str MSG_LEVBED_C = _UxGT("Stred"); + PROGMEM Language_Str MSG_LEVBED_BL = _UxGT("Ľavý zadný"); + PROGMEM Language_Str MSG_LEVBED_BR = _UxGT("Pravý zadný"); + PROGMEM Language_Str MSG_MANUAL_MESH = _UxGT("Ručná mriežka"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto-zarovn. Z"); PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterácia G34: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Klesajúca presnosť!"); @@ -85,6 +97,9 @@ namespace Language_sk { PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Ofset"); PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = LCD_STR_I _UxGT(" Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_J = LCD_STR_J _UxGT(" Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_K = LCD_STR_K _UxGT(" Ofset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); @@ -264,6 +279,9 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Posunúť X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Posunúť Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Posunúť Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Posunúť ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Posunúť ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Posunúť ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudér"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudér *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); @@ -275,7 +293,13 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Posunúť o 1,0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Rýchlosť"); + PROGMEM Language_Str MSG_MAXSPEED = _UxGT("Max rýchl. (mm/s)"); + PROGMEM Language_Str MSG_MAXSPEED_X = _UxGT("Max rýchl. ") LCD_STR_A; + PROGMEM Language_Str MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") LCD_STR_B; + PROGMEM Language_Str MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") LCD_STR_C; + PROGMEM Language_Str MSG_MAXSPEED_E = _UxGT("Max rýchl. ") LCD_STR_E; PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Tryska ~"); @@ -306,9 +330,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto-teplota"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Zap"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Vyp"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID kalibrácia"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID kalibrácia *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID kal. dokončená"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Kalibrácia PID"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Kalibrácia PID *"); + PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("Cykly PID"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Kal. PID dokončená"); PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-kal. zlyhala. Zlý extrúder."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala. Príliš vysoká tepl."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Auto-kal. zlyhala! Čas vypršal."); @@ -480,6 +505,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Zasunúť sondu Z"); PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Vysunúť sondu Z"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Najskôr os %s%s%s domov"); + PROGMEM Language_Str MSG_ZPROBE_SETTINGS = _UxGT("Nastav. sondy"); PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Ofsety sondy Z"); PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X ofset"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y ofset"); @@ -488,6 +514,9 @@ namespace Language_sk { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); @@ -584,6 +613,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); + PROGMEM Language_Str MSG_RUNOUT_ENABLE = _UxGT("Zapnúť senzor"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); @@ -703,6 +733,7 @@ namespace Language_sk { #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Zohriať"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Zohrievanie..."); + PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Zohrievanie dokonč."); PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Sprievodca sondy Z"); PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Referencia Z"); @@ -718,4 +749,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD karta"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB disk"); } From 23d10ceccb16e5886a6441a364fcbc08391287fe Mon Sep 17 00:00:00 2001 From: Desuuuu Date: Fri, 10 Sep 2021 12:15:08 +0200 Subject: [PATCH 0676/2168] =?UTF-8?q?=F0=9F=8E=A8=20Use=20ExtUI=20API=20wh?= =?UTF-8?q?ere=20applicable?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 21 ++++++------------- .../extui/dgus_reloaded/DGUSSetupHandler.cpp | 4 ++-- .../lcd/extui/dgus_reloaded/DGUSTxHandler.cpp | 10 +++------ 4 files changed, 12 insertions(+), 25 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 6a96411863..d8815b7ec5 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2566,7 +2566,7 @@ // - Copy the downloaded DWIN_SET folder to the SD card. // // RELOADED (T5UID1) -// - Download https://github.com/Desuuuu/DGUS-reloaded +// - Download https://github.com/Desuuuu/DGUS-reloaded/releases // - Copy the downloaded DWIN_SET folder to the SD card. // //#define DGUS_LCD_UI_ORIGIN diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 5f36dac7f6..20a4bee234 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -63,13 +63,13 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { } if (vp.addr == DGUS_Addr::SCREENCHANGE_Idle - && (printingIsActive() || printingIsPaused())) { + && (ExtUI::isPrinting() || ExtUI::isPrintingPaused())) { dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while printing")); return; } if (vp.addr == DGUS_Addr::SCREENCHANGE_Printing - && (!printingIsActive() && !printingIsPaused())) { + && (!ExtUI::isPrinting() && !ExtUI::isPrintingPaused())) { dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while idle")); return; } @@ -166,7 +166,7 @@ void DGUSRxHandler::PrintAbort(DGUS_VP &vp, void *data_ptr) { return; } - if (!printingIsActive() && !printingIsPaused()) { + if (!ExtUI::isPrinting() && !ExtUI::isPrintingPaused()) { dgus_screen_handler.TriggerFullUpdate(); return; } @@ -183,7 +183,7 @@ void DGUSRxHandler::PrintPause(DGUS_VP &vp, void *data_ptr) { return; } - if (!printingIsActive()) { + if (!ExtUI::isPrinting()) { dgus_screen_handler.TriggerFullUpdate(); return; } @@ -200,7 +200,7 @@ void DGUSRxHandler::PrintResume(DGUS_VP &vp, void *data_ptr) { return; } - if (!printingIsPaused()) { + if (!ExtUI::isPrintingPaused()) { dgus_screen_handler.TriggerFullUpdate(); return; } @@ -984,20 +984,11 @@ void DGUSRxHandler::WaitAbort(DGUS_VP &vp, void *data_ptr) { return; } - if (!printingIsPaused() - #if ENABLED(ADVANCED_PAUSE_FEATURE) - || !did_pause_print - #endif - ) { + if (!ExtUI::isPrintingPaused()) { dgus_screen_handler.TriggerFullUpdate(); return; } - #if ENABLED(ADVANCED_PAUSE_FEATURE) - did_pause_print = 0; - #endif - - ExtUI::setUserConfirmed(); ExtUI::stopPrint(); dgus_screen_handler.TriggerFullUpdate(); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp index c12282c4ef..0d94751fc2 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -47,7 +47,7 @@ #endif bool DGUSSetupHandler::PrintStatus() { - if (printingIsActive() || printingIsPaused()) { + if (ExtUI::isPrinting() || ExtUI::isPrintingPaused()) { return true; } @@ -56,7 +56,7 @@ bool DGUSSetupHandler::PrintStatus() { } bool DGUSSetupHandler::PrintAdjust() { - if (printingIsActive() || printingIsPaused()) { + if (ExtUI::isPrinting() || ExtUI::isPrintingPaused()) { return true; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index 04362b07e8..b2fa8c18b3 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -214,7 +214,7 @@ void DGUSTxHandler::Percent(DGUS_VP &vp) { void DGUSTxHandler::StatusIcons(DGUS_VP &vp) { uint16_t icons = 0; - if (printingIsActive()) { + if (ExtUI::isPrinting()) { icons |= (uint16_t)DGUS_Data::StatusIcon::PAUSE; dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, @@ -227,7 +227,7 @@ void DGUSTxHandler::StatusIcons(DGUS_VP &vp) { DGUS_Control::PAUSE); } - if (printingIsPaused()) { + if (ExtUI::isPrintingPaused()) { icons |= (uint16_t)DGUS_Data::StatusIcon::RESUME; dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, @@ -561,11 +561,7 @@ void DGUSTxHandler::FilamentUsed(DGUS_VP &vp) { void DGUSTxHandler::WaitIcons(DGUS_VP &vp) { uint16_t icons = 0; - if (printingIsPaused() - #if ENABLED(ADVANCED_PAUSE_FEATURE) - && did_pause_print - #endif - ) { + if (ExtUI::isPrintingPaused()) { icons |= (uint16_t)DGUS_Data::WaitIcon::ABORT; dgus_display.EnableControl(DGUS_Screen::WAIT, From 5a04cf0514c819d25f7eea0a9c95e17022d7bf1e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Sep 2021 18:46:30 -0500 Subject: [PATCH 0677/2168] =?UTF-8?q?=F0=9F=94=96=20Configurations=20versi?= =?UTF-8?q?on=2002000902?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/Version.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d8815b7ec5..741652422f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -35,7 +35,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02000901 +#define CONFIGURATION_H_VERSION 02000902 //=========================================================================== //============================= Getting Started ============================= diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index f525aef304..622251c35a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -30,7 +30,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 02000901 +#define CONFIGURATION_ADV_H_VERSION 02000902 //=========================================================================== //============================= Thermal Settings ============================ diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 14d7030a94..8dec4e29f7 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02000901 +#define MARLIN_HEX_VERSION 02000902 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif From ae22a920178555585142a5299ff77ec50d9fcc2e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 14 Sep 2021 01:17:33 +0000 Subject: [PATCH 0678/2168] [cron] Bump distribution date (2021-09-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d00c13fc80..6f61eceb48 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-13" +//#define STRING_DISTRIBUTION_DATE "2021-09-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8dec4e29f7..be693c73c8 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 "2021-09-13" + #define STRING_DISTRIBUTION_DATE "2021-09-14" #endif /** From c2e4b1626f0cce82a55e8de9dc98ed9381e1d9ad Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Tue, 14 Sep 2021 04:07:08 +0200 Subject: [PATCH 0679/2168] =?UTF-8?q?=E2=9C=A8=20TFT=20Screen/Backlight=20?= =?UTF-8?q?Sleep=20(#22617)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 + Marlin/src/MarlinCore.cpp | 3 +- Marlin/src/inc/Conditionals_LCD.h | 3 ++ .../dogm/u8g_dev_tft_upscale_from_128x64.cpp | 50 +++++++++++++------ Marlin/src/lcd/marlinui.cpp | 17 ++++++- Marlin/src/lcd/marlinui.h | 6 ++- Marlin/src/lcd/menu/menu.cpp | 1 + Marlin/src/lcd/tft/touch.cpp | 33 +++++++++++- Marlin/src/lcd/tft/touch.h | 10 +++- Marlin/src/lcd/tft/ui_1024x600.cpp | 1 + Marlin/src/lcd/tft/ui_320x240.cpp | 1 + Marlin/src/lcd/tft/ui_480x320.cpp | 1 + Marlin/src/lcd/tft/ui_common.cpp | 21 ++++++++ Marlin/src/lcd/tft/ui_common.h | 4 ++ Marlin/src/lcd/tft_io/tft_io.h | 1 - Marlin/src/lcd/touch/touch_buttons.cpp | 36 ++++++++++++- Marlin/src/lcd/touch/touch_buttons.h | 11 +++- 17 files changed, 176 insertions(+), 25 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 741652422f..12d1ee7064 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2780,6 +2780,8 @@ #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus + //#define TOUCH_IDLE_SLEEP 300 // (secs) Turn off the TFT backlight if set (5mn) + #define TOUCH_SCREEN_CALIBRATION //#define TOUCH_CALIBRATION_X 12316 diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5bbfcd087b..07a9d0186f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -542,6 +542,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ CODE; \ queue.inject_P(PSTR(BUTTON##N##_GCODE)); \ + TERN_(HAS_LCD_MENU, ui.quick_feedback()); \ } \ } \ }while(0) @@ -1354,7 +1355,7 @@ void setup() { #endif #if HAS_TOUCH_BUTTONS - SETUP_RUN(touch.init()); + SETUP_RUN(touchBt.init()); #endif TERN_(HAS_M206_COMMAND, current_position += home_offset); // Init current position based on home_offset diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 7f8891b514..023bf46426 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1360,6 +1360,9 @@ // This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046' #if ENABLED(TOUCH_SCREEN) + #if TOUCH_IDLE_SLEEP + #define HAS_TOUCH_SLEEP 1 + #endif #if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046) #define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 #endif diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index 9b5f206fa9..df7b4000a9 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -73,13 +73,18 @@ TFT_IO tftio; #define HEIGHT LCD_PIXEL_HEIGHT #define PAGE_HEIGHT 8 -#include "../touch/touch_buttons.h" - #if ENABLED(TOUCH_SCREEN_CALIBRATION) #include "../tft_io/touch_calibration.h" #include "../marlinui.h" #endif +#if HAS_TOUCH_BUTTONS + #include "../touch/touch_buttons.h" + #if HAS_TOUCH_SLEEP + #define HAS_TOUCH_BUTTONS_SLEEP 1 + #endif +#endif + #define X_HI (UPSCALE(TFT_PIXEL_OFFSET_X, WIDTH) - 1) #define Y_HI (UPSCALE(TFT_PIXEL_OFFSET_Y, HEIGHT) - 1) @@ -340,6 +345,18 @@ static uint8_t page; } #endif // HAS_TOUCH_BUTTONS +static void u8g_upscale_clear_lcd(u8g_t *u8g, u8g_dev_t *dev, uint16_t *buffer) { + setWindow(u8g, dev, 0, 0, (TFT_WIDTH) - 1, (TFT_HEIGHT) - 1); + #if HAS_LCD_IO + UNUSED(buffer); + tftio.WriteMultiple(TFT_MARLINBG_COLOR, (TFT_WIDTH) * (TFT_HEIGHT)); + #else + memset2(buffer, TFT_MARLINBG_COLOR, (TFT_WIDTH) / 2); + for (uint16_t i = 0; i < (TFT_HEIGHT) * sq(GRAPHICAL_TFT_UPSCALE); i++) + u8g_WriteSequence(u8g, dev, (TFT_WIDTH) / 2, (uint8_t *)buffer); + #endif +} + static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) { @@ -365,27 +382,32 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u tftio.Init(); tftio.InitTFT(); TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); - - // Clear Screen - setWindow(u8g, dev, 0, 0, (TFT_WIDTH) - 1, (TFT_HEIGHT) - 1); - #if HAS_LCD_IO - tftio.WriteMultiple(TFT_MARLINBG_COLOR, (TFT_WIDTH) * (TFT_HEIGHT)); - #else - memset2(buffer, TFT_MARLINBG_COLOR, (TFT_WIDTH) / 2); - for (uint16_t i = 0; i < (TFT_HEIGHT) * sq(GRAPHICAL_TFT_UPSCALE); i++) - u8g_WriteSequence(u8g, dev, (TFT_WIDTH) / 2, (uint8_t *)buffer); - #endif + u8g_upscale_clear_lcd(u8g, dev, buffer); return 0; case U8G_DEV_MSG_STOP: preinit = true; break; - case U8G_DEV_MSG_PAGE_FIRST: + case U8G_DEV_MSG_PAGE_FIRST: { page = 0; + #if HAS_TOUCH_BUTTONS_SLEEP + static bool sleepCleared; + if (touchBt.isSleeping()) { + if (!sleepCleared) { + sleepCleared = true; + u8g_upscale_clear_lcd(u8g, dev, buffer); + IF_ENABLED(HAS_TOUCH_BUTTONS, redrawTouchButtons = true); + } + break; + } + else + sleepCleared = false; + #endif TERN_(HAS_TOUCH_BUTTONS, drawTouchButtons(u8g, dev)); setWindow(u8g, dev, TFT_PIXEL_OFFSET_X, TFT_PIXEL_OFFSET_Y, X_HI, Y_HI); - break; + } break; case U8G_DEV_MSG_PAGE_NEXT: + if (TERN0(HAS_TOUCH_BUTTONS_SLEEP, touchBt.isSleeping())) break; if (++page > (HEIGHT / PAGE_HEIGHT)) return 1; LOOP_L_N(y, PAGE_HEIGHT) { diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 5e5b7a94bc..40f815a3e7 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -673,8 +673,20 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; draw_kill_screen(); } - void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { + #if HAS_TOUCH_SLEEP + #if HAS_TOUCH_BUTTONS + #include "touch/touch_buttons.h" + #else + #include "tft/touch.h" + #endif + // Wake up a sleeping TFT + void MarlinUI::wakeup_screen() { + TERN(HAS_TOUCH_BUTTONS, touchBt.wakeUp(), touch.wakeUp()); + } + #endif + void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { + TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); // Wake up the TFT with most buttons TERN_(HAS_LCD_MENU, refresh()); #if HAS_ENCODER_ACTION @@ -926,7 +938,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; - TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); + TERN_(HAS_ENCODER_ACTION, touch_buttons = touchBt.read_buttons()); #endif @@ -955,6 +967,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; abs_diff = epps; // Treat as a full step size encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. } + TERN_(HAS_TOUCH_SLEEP, if (lastEncoderDiff != encoderDiff) wakeup_screen()); lastEncoderDiff = encoderDiff; #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index e947ac9e5e..be016f8683 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -435,11 +435,15 @@ public: static millis_t next_filament_display; #endif + #if HAS_TOUCH_SLEEP + static void wakeup_screen(); + #endif + static void quick_feedback(const bool clear_buttons=true); #if HAS_BUZZER static void completion_feedback(const bool good=true); #else - static inline void completion_feedback(const bool=true) {} + static inline void completion_feedback(const bool=true) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); } #endif #if DISABLED(LIGHTWEIGHT_UI) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index dd52eb2b5b..a177f32932 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -285,6 +285,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if HAS_BUZZER void MarlinUI::completion_feedback(const bool good/*=true*/) { + TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); // Wake up on rotary encoder click... if (good) { BUZZ(100, 659); BUZZ(100, 698); diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 64dfaa5755..7262536e77 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -47,7 +47,10 @@ millis_t Touch::last_touch_ms = 0, Touch::time_to_hold, Touch::repeat_delay, Touch::touch_time; -TouchControlType Touch::touch_control_type = NONE; +TouchControlType Touch::touch_control_type = NONE; +#if HAS_TOUCH_SLEEP + millis_t Touch::next_sleep_ms; // = 0 +#endif #if HAS_RESUME_CONTINUE extern bool wait_for_user; #endif @@ -56,6 +59,7 @@ void Touch::init() { TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); reset(); io.Init(); + TERN_(HAS_TOUCH_SLEEP, wakeUp()); enable(); } @@ -271,9 +275,34 @@ bool Touch::get_point(int16_t *x, int16_t *y) { #elif ENABLED(TFT_TOUCH_DEVICE_GT911) bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y)); #endif - + #if HAS_TOUCH_SLEEP + if (is_touched) + wakeUp(); + else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) + sleepTimeout(); + #endif return is_touched; } + +#if HAS_TOUCH_SLEEP + + void Touch::sleepTimeout() { + #if PIN_EXISTS(TFT_BACKLIGHT) + OUT_WRITE(TFT_BACKLIGHT_PIN, LOW); + #endif + next_sleep_ms = TSLP_SLEEPING; + } + void Touch::wakeUp() { + if (isSleeping()) { + #if PIN_EXISTS(TFT_BACKLIGHT) + WRITE(TFT_BACKLIGHT_PIN, HIGH); + #endif + } + next_sleep_ms = millis() + SEC_TO_MS(TOUCH_IDLE_SLEEP); + } + +#endif // HAS_TOUCH_SLEEP + Touch touch; bool MarlinUI::touch_pressed() { diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 54dfb420d8..238453f765 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -90,6 +90,9 @@ typedef struct __attribute__((__packed__)) { #define UBL_REPEAT_DELAY 125 #define FREE_MOVE_RANGE 32 +#define TSLP_PREINIT 0 +#define TSLP_SLEEPING 1 + class Touch { private: static TOUCH_DRIVER_CLASS io; @@ -121,7 +124,12 @@ class Touch { } static void disable() { enabled = false; } static void enable() { enabled = true; } - + #if HAS_TOUCH_SLEEP + static millis_t next_sleep_ms; + static inline bool isSleeping() { return next_sleep_ms == TSLP_SLEEPING; } + static void sleepTimeout(); + static void wakeUp(); + #endif static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data = 0); }; diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 18c50c92f7..db75c36ef9 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -47,6 +47,7 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) + if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { add_control(164, TFT_HEIGHT - 50, PAGE_UP, imgPageUp, encoderTopLine > 0); add_control(796, TFT_HEIGHT - 50, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 786dc61f60..deffbae94c 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -47,6 +47,7 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) + if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { add_control(48, 206, PAGE_UP, imgPageUp, encoderTopLine > 0); add_control(240, 206, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 02e3354d93..c8333f7e4b 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -47,6 +47,7 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) + if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { add_control(104, TFT_HEIGHT - 34, PAGE_UP, imgPageUp, encoderTopLine > 0); add_control(344, TFT_HEIGHT - 34, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index 7c053e7be7..a5f41874b0 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -37,6 +37,27 @@ static xy_uint_t cursor; bool draw_menu_navigation = false; #endif +#if HAS_TOUCH_SLEEP + + bool lcd_sleep_task() { + static bool sleepCleared; + if (touch.isSleeping()) { + tft.queue.reset(); + if (!sleepCleared) { + sleepCleared = true; + ui.clear_lcd(); + tft.queue.async(); + } + touch.idle(); + return true; + } + else + sleepCleared = false; + return false; + } + +#endif + void menu_line(const uint8_t row, uint16_t color) { cursor.set(0, row); tft.canvas(0, TFT_TOP_LINE_Y + cursor.y * MENU_LINE_HEIGHT, TFT_WIDTH, MENU_ITEM_HEIGHT); diff --git a/Marlin/src/lcd/tft/ui_common.h b/Marlin/src/lcd/tft/ui_common.h index 759712b64c..d3ffd4bc31 100644 --- a/Marlin/src/lcd/tft/ui_common.h +++ b/Marlin/src/lcd/tft/ui_common.h @@ -51,6 +51,10 @@ void draw_fan_status(uint16_t x, uint16_t y, const bool blink); void menu_line(const uint8_t row, uint16_t color=COLOR_BACKGROUND); void menu_item(const uint8_t row, bool sel = false); +#if HAS_TOUCH_SLEEP + bool lcd_sleep_task(); +#endif + #define ABSOLUTE_ZERO -273.15 #if HAS_TEMP_CHAMBER && HOTENDS > 1 diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 0e4322f0d7..65602240d6 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -59,7 +59,6 @@ #define TFT_ROTATION TFT_NO_ROTATION #endif - // TFT_ORIENTATION is the "sum" of TFT_DEFAULT_ORIENTATION plus user TFT_ROTATION #define TFT_ORIENTATION ((TFT_DEFAULT_ORIENTATION) ^ (TFT_ROTATION)) diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index c9476bd2bb..2d6158961e 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -38,6 +38,10 @@ #include "../tft_io/touch_calibration.h" #endif +#if HAS_TOUCH_SLEEP + millis_t TouchButtons::next_sleep_ms; +#endif + #include "../buttons.h" // For EN_C bit mask #include "../marlinui.h" // For ui.refresh #include "../tft_io/tft_io.h" @@ -50,15 +54,24 @@ #define BUTTON_AREA_TOP BUTTON_Y_LO #define BUTTON_AREA_BOT BUTTON_Y_HI -TouchButtons touch; +TouchButtons touchBt; -void TouchButtons::init() { touchIO.Init(); } +void TouchButtons::init() { + touchIO.Init(); + TERN_(HAS_TOUCH_SLEEP, next_sleep_ms = millis() + SEC_TO_MS(TOUCH_IDLE_SLEEP)); +} uint8_t TouchButtons::read_buttons() { #ifdef HAS_WIRED_LCD int16_t x, y; const bool is_touched = (TERN(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration.orientation, TOUCH_ORIENTATION) == TOUCH_PORTRAIT ? touchIO.getRawPoint(&y, &x) : touchIO.getRawPoint(&x, &y)); + #if HAS_TOUCH_SLEEP + if (is_touched) + wakeUp(); + else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) + sleepTimeout(); + #endif if (!is_touched) return 0; #if ENABLED(TOUCH_SCREEN_CALIBRATION) @@ -96,4 +109,23 @@ uint8_t TouchButtons::read_buttons() { return 0; } +#if HAS_TOUCH_SLEEP + + void TouchButtons::sleepTimeout() { + #if PIN_EXISTS(TFT_BACKLIGHT) + OUT_WRITE(TFT_BACKLIGHT_PIN, LOW); + #endif + next_sleep_ms = TSLP_SLEEPING; + } + void TouchButtons::wakeUp() { + if (isSleeping()) { + #if PIN_EXISTS(TFT_BACKLIGHT) + WRITE(TFT_BACKLIGHT_PIN, HIGH); + #endif + } + next_sleep_ms = millis() + SEC_TO_MS(TOUCH_IDLE_SLEEP); + } + +#endif // HAS_TOUCH_SLEEP + #endif // HAS_TOUCH_BUTTONS diff --git a/Marlin/src/lcd/touch/touch_buttons.h b/Marlin/src/lcd/touch/touch_buttons.h index a79bb15be4..36be0ee134 100644 --- a/Marlin/src/lcd/touch/touch_buttons.h +++ b/Marlin/src/lcd/touch/touch_buttons.h @@ -50,10 +50,19 @@ #define BUTTON_Y_HI (TFT_HEIGHT) - BUTTON_SPACING #define BUTTON_Y_LO BUTTON_Y_HI - BUTTON_HEIGHT +#define TSLP_PREINIT 0 +#define TSLP_SLEEPING 1 + class TouchButtons { public: static void init(); static uint8_t read_buttons(); + #if HAS_TOUCH_SLEEP + static millis_t next_sleep_ms; + static bool isSleeping() { return next_sleep_ms == TSLP_SLEEPING; } + static void sleepTimeout(); + static void wakeUp(); + #endif }; -extern TouchButtons touch; +extern TouchButtons touchBt; From 21e8f99500554d69cb91ac2be0b4ab1497bf9fac Mon Sep 17 00:00:00 2001 From: Dakkaron Date: Wed, 15 Sep 2021 02:00:48 +0200 Subject: [PATCH 0680/2168] =?UTF-8?q?=E2=9C=A8=20M282=20-=20Detach=20Servo?= =?UTF-8?q?=20(#22760)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 7 +++-- Marlin/src/gcode/control/M280.cpp | 2 +- Marlin/src/gcode/control/M282.cpp | 45 ++++++++++++++++++++++++++++++ Marlin/src/gcode/gcode.cpp | 3 ++ Marlin/src/gcode/gcode.h | 4 +++ Marlin/src/inc/Conditionals_post.h | 11 ++++++-- Marlin/src/module/servo.cpp | 8 +++--- Marlin/src/module/servo.h | 1 + buildroot/tests/LPC1768 | 3 +- ini/features.ini | 1 + platformio.ini | 5 ++-- 11 files changed, 76 insertions(+), 14 deletions(-) create mode 100644 Marlin/src/gcode/control/M282.cpp diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 12d1ee7064..5abb4fd729 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2936,9 +2936,9 @@ * Set this manually if there are extra servos needing manual control. * Set to 0 to turn off servo support. */ -//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command +//#define NUM_SERVOS 3 // Note: Servo index starts with 0 for M280-M282 commands -// (ms) Delay before the next move will start, to give the servo time to reach its target angle. +// (ms) Delay before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. #define SERVO_DELAY { 300 } @@ -2948,3 +2948,6 @@ // Edit servo angles with M281 and save to EEPROM with M500 //#define EDITABLE_SERVO_ANGLES + +// Disable servo with M282 to reduce power consumption, noise, and heat when not in use +//#define SERVO_DETACH_GCODE diff --git a/Marlin/src/gcode/control/M280.cpp b/Marlin/src/gcode/control/M280.cpp index 187c9a9b19..f285adf47f 100644 --- a/Marlin/src/gcode/control/M280.cpp +++ b/Marlin/src/gcode/control/M280.cpp @@ -39,7 +39,7 @@ void GcodeSuite::M280() { if (parser.seen('S')) { const int a = parser.value_int(); if (a == -1) - servo[servo_index].detach(); + DETACH_SERVO(servo_index); else MOVE_SERVO(servo_index, a); } diff --git a/Marlin/src/gcode/control/M282.cpp b/Marlin/src/gcode/control/M282.cpp new file mode 100644 index 0000000000..5fe2e6e328 --- /dev/null +++ b/Marlin/src/gcode/control/M282.cpp @@ -0,0 +1,45 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SERVO_DETACH_GCODE) + +#include "../gcode.h" +#include "../../module/servo.h" + +/** + * M282: Detach Servo. P + */ +void GcodeSuite::M282() { + + if (!parser.seen('P')) return; + + const int servo_index = parser.value_int(); + if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) + DETACH_SERVO(servo_index); + else + SERIAL_ECHO_MSG("Servo ", servo_index, " out of range"); + +} + +#endif // SERVO_DETACH_GCODE diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index e3b90b65b3..4e7c3df78d 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -717,6 +717,9 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if ENABLED(EDITABLE_SERVO_ANGLES) case 281: M281(); break; // M281: Set servo angles #endif + #if ENABLED(SERVO_DETACH_GCODE) + case 282: M282(); break; // M282: Detach servo + #endif #endif #if ENABLED(BABYSTEPPING) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 16cee3481d..aa38b7de4a 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -192,6 +192,7 @@ * M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS) * M280 - Set servo position absolute: "M280 P S". (Requires servos) * M281 - Set servo min|max position: "M281 P L U". (Requires EDITABLE_SERVO_ANGLES) + * M282 - Detach servo: "M282 P". (Requires SERVO_DETACH_GCODE) * M290 - Babystepping (Requires BABYSTEPPING) * M300 - Play beep sound S P * M301 - Set PID parameters P I and D. (Requires PIDTEMP) @@ -862,6 +863,9 @@ private: static void M281(); static void M281_report(const bool forReplay=true); #endif + #if ENABLED(SERVO_DETACH_GCODE) + static void M282(); + #endif #endif #if ENABLED(BABYSTEPPING) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 61a9ea2c9a..5b7526b74b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2593,9 +2593,14 @@ #endif #if NUM_SERVOS > 0 #define HAS_SERVOS 1 -#endif -#if HAS_SERVOS && defined(PAUSE_SERVO_OUTPUT) && defined(RESUME_SERVO_OUTPUT) - #define HAS_PAUSE_SERVO_OUTPUT 1 + #if defined(PAUSE_SERVO_OUTPUT) && defined(RESUME_SERVO_OUTPUT) + #define HAS_PAUSE_SERVO_OUTPUT 1 + #endif +#else + #undef SERVO_DELAY + #undef DEACTIVATE_SERVOS_AFTER_MOVE + #undef EDITABLE_SERVO_ANGLES + #undef SERVO_DETACH_GCODE #endif // Sensors diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 9b71dd390f..231efe84e1 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -39,19 +39,19 @@ HAL_SERVO_LIB servo[NUM_SERVOS]; void servo_init() { #if NUM_SERVOS >= 1 && HAS_SERVO_0 servo[0].attach(SERVO0_PIN); - servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position. + DETACH_SERVO(0); // Just set up the pin. We don't have a position yet. Don't move to a random position. #endif #if NUM_SERVOS >= 2 && HAS_SERVO_1 servo[1].attach(SERVO1_PIN); - servo[1].detach(); + DETACH_SERVO(1); #endif #if NUM_SERVOS >= 3 && HAS_SERVO_2 servo[2].attach(SERVO2_PIN); - servo[2].detach(); + DETACH_SERVO(2); #endif #if NUM_SERVOS >= 4 && HAS_SERVO_3 servo[3].attach(SERVO3_PIN); - servo[3].detach(); + DETACH_SERVO(3); #endif } diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 3b5a5e7e2c..73dbbdddb7 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -110,6 +110,7 @@ #endif // HAS_SERVO_ANGLES #define MOVE_SERVO(I, P) servo[I].move(P) +#define DETACH_SERVO(I) servo[I].detach() extern HAL_SERVO_LIB servo[NUM_SERVOS]; void servo_init(); diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 26e3710890..92ba286693 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -28,7 +28,8 @@ restore_configs opt_set MOTHERBOARD BOARD_MKS_SBASE \ EXTRUDERS 2 TEMP_SENSOR_1 1 \ NUM_SERVOS 2 SERVO_DELAY '{ 300, 300 }' -opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR ULTIMAKERCONTROLLER REALTIME_REPORTING_COMMANDS FULL_REPORT_TO_HOST_FEATURE +opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR EDITABLE_SERVO_ANGLES SERVO_DETACH_GCODE \ + ULTIMAKERCONTROLLER REALTIME_REPORTING_COMMANDS FULL_REPORT_TO_HOST_FEATURE exec_test $1 $2 "MKS SBASE with SWITCHING_NOZZLE, Grbl Realtime Report" "$3" restore_configs diff --git a/ini/features.ini b/ini/features.ini index 6ad375e594..b4398378ad 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -173,6 +173,7 @@ HAS_SMART_EFF_MOD = src_filter=+ COOLANT_CONTROL|AIR_ASSIST = src_filter=+ AIR_EVACUATION = src_filter=+ HAS_SOFTWARE_ENDSTOPS = src_filter=+ +SERVO_DETACH_GCODE = src_filter=+ HAS_DUPLICATION_MODE = src_filter=+ LIN_ADVANCE = src_filter=+ PHOTO_GCODE = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 5502069800..5e40455098 100644 --- a/platformio.ini +++ b/platformio.ini @@ -87,7 +87,7 @@ default_src_filter = + - - + - - - - - - - - - - - - + - - - - - - - - - @@ -166,7 +166,6 @@ default_src_filter = + - - + - - - - - - - - @@ -243,7 +242,7 @@ default_src_filter = + - - + - - - - - - - + - - - - - # From 9c8ad57f626bbb84d1f7f2c2262f3b101f91e664 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 15 Sep 2021 00:59:31 +0000 Subject: [PATCH 0681/2168] [cron] Bump distribution date (2021-09-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6f61eceb48..12ec86b460 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-14" +//#define STRING_DISTRIBUTION_DATE "2021-09-15" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index be693c73c8..6dec849a4e 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 "2021-09-14" + #define STRING_DISTRIBUTION_DATE "2021-09-15" #endif /** From 8235ae9cc00b10362ca9f6e79acb4516c08557af Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Wed, 15 Sep 2021 01:44:28 -0500 Subject: [PATCH 0682/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20DWIN=20Enhanced?= =?UTF-8?q?=20Tune=20menu=20during=20homing=20(#22773)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 239 +++++++++-------- Marlin/src/lcd/e3v2/creality/dwin_lcd.h | 3 - Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 340 +++++++++++------------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 16 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 45 ++-- 5 files changed, 299 insertions(+), 344 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 76d77e4cab..5593147b7a 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -30,6 +30,9 @@ #include "dwin.h" +//#define USE_STRING_HEADINGS +//#define USE_STRING_TITLES + #if ENABLED(LCD_BED_LEVELING) && DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define HAS_ONESTEP_LEVELING 1 #endif @@ -141,6 +144,17 @@ millis_t dwin_heat_time = 0; uint8_t checkkey = 0; +enum SelectItem : uint8_t { + PAGE_PRINT = 0, + PAGE_PREPARE, + PAGE_CONTROL, + PAGE_INFO_LEVELING, + + PRINT_SETUP = 0, + PRINT_PAUSE_RESUME, + PRINT_STOP +}; + typedef struct { uint8_t now, last; void set(uint8_t v) { now = last = v; } @@ -235,7 +249,7 @@ void ICON_Print() { { 1, { 417, 449 }, 30, 14 }, { 1, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 0, ICON_Print_0, ico, txt); + ICON_Button(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt); } // @@ -247,7 +261,7 @@ void ICON_Prepare() { { 33, { 417, 449 }, 51, 14 }, { 31, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 1, ICON_Prepare_0, ico, txt); + ICON_Button(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt); } // @@ -259,7 +273,7 @@ void ICON_Control() { { 85, { 417, 449 }, 46, 14 }, { 61, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 2, ICON_Control_0, ico, txt); + ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt); } // @@ -271,7 +285,7 @@ void ICON_StartInfo() { { 133, { 417, 449 }, 23, 14 }, { 91, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 3, ICON_Info_0, ico, txt); + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Info_0, ico, txt); } // @@ -283,7 +297,7 @@ void ICON_Leveling() { { 88, { 433, 464 }, 36, 14 }, { 211, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 3, ICON_Leveling_0, ico, txt); + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Leveling_0, ico, txt); } // @@ -295,7 +309,7 @@ void ICON_Tune() { { 0, { 433, 464 }, 32, 14 }, { 121, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 0, ICON_Setup_0, ico, txt); + ICON_Button(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt); } // @@ -307,7 +321,7 @@ void ICON_Pause() { { 157, { 417, 449 }, 39, 14 }, { 181, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 1, ICON_Pause_0, ico, txt); + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt); } // @@ -319,7 +333,7 @@ void ICON_Resume() { { 33, { 433, 464 }, 53, 14 }, { 1, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 1, ICON_Continue_0, ico, txt); + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt); } void ICON_ResumeOrPause() { @@ -338,7 +352,7 @@ void ICON_Stop() { { 196, { 417, 449 }, 29, 14 }, { 151, { 405, 447 }, 27, 12 } }; - ICON_Button(select_print.now == 2, ICON_Stop_0, ico, txt); + ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt); } inline void Clear_Title_Bar() { @@ -467,6 +481,7 @@ inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) // // Draw Menus // +#define CASE_BACK 0 #define MOTION_CASE_RATE 1 #define MOTION_CASE_ACCEL 2 @@ -759,7 +774,7 @@ void Draw_Prepare_Menu() { #endif } - if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back + if (PVISI(0)) Draw_Back_First(select_prepare.now == CASE_BACK); // < Back if (PVISI(PREPARE_CASE_MOVE)) Item_Prepare_Move(PSCROL(PREPARE_CASE_MOVE)); // Move > if (PVISI(PREPARE_CASE_DISA)) Item_Prepare_Disable(PSCROL(PREPARE_CASE_DISA)); // Disable Stepper if (PVISI(PREPARE_CASE_HOME)) Item_Prepare_Home(PSCROL(PREPARE_CASE_HOME)); // Auto Home @@ -775,7 +790,7 @@ void Draw_Prepare_Menu() { #endif if (PVISI(PREPARE_CASE_LANG)) Item_Prepare_Lang(PSCROL(PREPARE_CASE_LANG)); // Language CN/EN - if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); + if (select_prepare.now != CASE_BACK) Draw_Menu_Cursor(PSCROL(select_prepare.now)); } // @@ -860,7 +875,7 @@ void Draw_Control_Menu() { #endif } - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + if (CVISI(0)) Draw_Back_First(select_control.now == CASE_BACK); // < Back if (CVISI(CONTROL_CASE_TEMP)) Item_Control_Temp(CSCROL(CONTROL_CASE_TEMP)); // Temperature > if (CVISI(CONTROL_CASE_MOVE)) Item_Control_Motion(CSCROL(CONTROL_CASE_MOVE)); // Motion > @@ -897,7 +912,7 @@ void Draw_Control_Menu() { if (CVISI(CONTROL_CASE_ADVSET)) Item_Control_Advanced(CSCROL(CONTROL_CASE_ADVSET)); if (CVISI(CONTROL_CASE_INFO)) Item_Control_Info(CSCROL(CONTROL_CASE_INFO)); - if (select_control.now && CVISI(select_control.now)) + if (select_control.now != CASE_BACK && CVISI(select_control.now)) Draw_Menu_Cursor(CSCROL(select_control.now)); // Draw icons and lines @@ -977,8 +992,8 @@ void Draw_Tune_Menu() { #endif } - Draw_Back_First(select_tune.now == 0); - if (select_tune.now) Draw_Menu_Cursor(select_tune.now); + Draw_Back_First(select_tune.now == CASE_BACK); + if (select_tune.now != CASE_BACK) Draw_Menu_Cursor(select_tune.now); Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); Draw_Edit_Integer3(TUNE_CASE_SPEED, feedrate_percentage); @@ -1042,8 +1057,8 @@ void Draw_Motion_Menu() { #endif } - Draw_Back_First(select_motion.now == 0); - if (select_motion.now) Draw_Menu_Cursor(select_motion.now); + Draw_Back_First(select_motion.now == CASE_BACK); + if (select_motion.now != CASE_BACK) Draw_Menu_Cursor(select_motion.now); uint8_t i = 0; #define _MOTION_ICON(N) Draw_Menu_Line(++i, ICON_MaxSpeed + (N) - 1) @@ -1179,15 +1194,15 @@ void Popup_window_PauseOrStop() { Clear_Main_Window(); Draw_Popup_Bkgd_60(); if (HMI_IsChinese()) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop + if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause + else if (select_print.now == PRINT_STOP) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); // Print DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); } else { - if (select_print.now == 1) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == PRINT_STOP) DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); } @@ -1823,7 +1838,7 @@ void MarlinUI::refresh() { /* Nothing to see here */ } void Init_SDItem_Shift() { shift_amt = 0; - shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT + shift_ms = select_file.now != CASE_BACK && strlen(shift_name) > MENU_CHAR_LIMIT ? millis() + 750UL : 0; } @@ -2068,45 +2083,45 @@ void HMI_MainMenu() { if (encoder_diffState == ENCODER_DIFF_CW) { if (select_page.inc(4)) { switch (select_page.now) { - case 0: ICON_Print(); break; - case 1: ICON_Print(); ICON_Prepare(); break; - case 2: ICON_Prepare(); ICON_Control(); break; - case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_PRINT: ICON_Print(); break; + case PAGE_PREPARE: ICON_Print(); ICON_Prepare(); break; + case PAGE_CONTROL: ICON_Prepare(); ICON_Control(); break; + case PAGE_INFO_LEVELING: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_page.dec()) { switch (select_page.now) { - case 0: ICON_Print(); ICON_Prepare(); break; - case 1: ICON_Prepare(); ICON_Control(); break; - case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; - case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_PRINT: ICON_Print(); ICON_Prepare(); break; + case PAGE_PREPARE: ICON_Prepare(); ICON_Control(); break; + case PAGE_CONTROL: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_INFO_LEVELING: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_page.now) { - case 0: // Print File + case PAGE_PRINT: checkkey = SelectFile; Draw_Print_File_Menu(); break; - case 1: // Prepare + case PAGE_PREPARE: checkkey = Prepare; select_prepare.reset(); index_prepare = MROWS; Draw_Prepare_Menu(); break; - case 2: // Control + case PAGE_CONTROL: checkkey = Control; select_control.reset(); index_control = MROWS; Draw_Control_Menu(); break; - case 3: // Leveling or Info + case PAGE_INFO_LEVELING: #if HAS_ONESTEP_LEVELING checkkey = Leveling; HMI_Leveling(); @@ -2196,7 +2211,7 @@ void HMI_SelectFile() { } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { // Back + if (select_file.now == CASE_BACK) { // Back select_page.set(0); Goto_MainMenu(); } @@ -2257,43 +2272,32 @@ void HMI_Printing() { if (encoder_diffState == ENCODER_DIFF_CW) { if (select_print.inc(3)) { switch (select_print.now) { - case 0: ICON_Tune(); break; - case 1: - ICON_Tune(); - ICON_ResumeOrPause(); - break; - case 2: - ICON_ResumeOrPause(); - ICON_Stop(); - break; + case PRINT_SETUP: ICON_Tune(); break; + case PRINT_PAUSE_RESUME: ICON_Tune(); ICON_ResumeOrPause(); break; + case PRINT_STOP: ICON_ResumeOrPause(); ICON_Stop(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_print.dec()) { switch (select_print.now) { - case 0: - ICON_Tune(); - ICON_ResumeOrPause(); - break; - case 1: - ICON_ResumeOrPause(); - ICON_Stop(); - break; - case 2: ICON_Stop(); break; + case PRINT_SETUP: ICON_Tune(); ICON_ResumeOrPause(); break; + case PRINT_PAUSE_RESUME: ICON_ResumeOrPause(); ICON_Stop(); break; + case PRINT_STOP: ICON_Stop(); break; } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_print.now) { - case 0: // Tune + case PRINT_SETUP: checkkey = Tune; HMI_ValueStruct.show_mode = 0; select_tune.reset(); index_tune = MROWS; Draw_Tune_Menu(); break; - case 1: // Pause + + case PRINT_PAUSE_RESUME: if (HMI_flag.pause_flag) { ICON_Pause(); @@ -2317,7 +2321,7 @@ void HMI_Printing() { } break; - case 2: // Stop + case PRINT_STOP: HMI_flag.select_flag = true; checkkey = Print_window; Popup_window_PauseOrStop(); @@ -2339,14 +2343,14 @@ void HMI_PauseOrStop() { else if (encoder_diffState == ENCODER_DIFF_CCW) Draw_Select_Highlight(true); else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_print.now == 1) { // pause window + if (select_print.now == PRINT_PAUSE_RESUME) { if (HMI_flag.select_flag) { HMI_flag.pause_action = true; queue.inject_P(PSTR("M25")); } Goto_PrintProcess(); } - else if (select_print.now == 2) { // stop window + else if (select_print.now == PRINT_STOP) { if (HMI_flag.select_flag) { checkkey = Back_Main; wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user @@ -2395,8 +2399,8 @@ void Draw_Move_Menu() { #endif } - Draw_Back_First(select_axis.now == 0); - if (select_axis.now) Draw_Menu_Cursor(select_axis.now); + Draw_Back_First(select_axis.now == CASE_BACK); + if (select_axis.now != CASE_BACK) Draw_Menu_Cursor(select_axis.now); // Draw separators and icons LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); @@ -2506,7 +2510,7 @@ void Draw_AdvancedSettings_Menu() { #endif } - if (AVISI(0)) Draw_Back_First(select_advset.now == 0); + if (AVISI(0)) Draw_Back_First(select_advset.now == CASE_BACK); if (AVISI(ADVSET_CASE_HOMEOFF)) Item_Adv_HomeOffsets(ASCROL(ADVSET_CASE_HOMEOFF)); // Set Home Offsets > #if HAS_ONESTEP_LEVELING if (AVISI(ADVSET_CASE_PROBEOFF)) Item_Adv_ProbeOffsets(ASCROL(ADVSET_CASE_PROBEOFF)); // Probe Offsets > @@ -2516,7 +2520,7 @@ void Draw_AdvancedSettings_Menu() { #if ENABLED(POWER_LOSS_RECOVERY) if (AVISI(ADVSET_CASE_PWRLOSSR)) Item_Adv_PLR(ASCROL(ADVSET_CASE_PWRLOSSR)); // Power-loss recovery #endif - if (select_advset.now) Draw_Menu_Cursor(ASCROL(select_advset.now)); + if (select_advset.now != CASE_BACK) Draw_Menu_Cursor(ASCROL(select_advset.now)); } void Item_HomeOffs_X(const uint8_t row) { @@ -2576,18 +2580,18 @@ void Draw_HomeOff_Menu() { DWIN_Frame_TitleCopy(1, 401, 91, 12); // "Home Offsets" #endif } - Draw_Back_First(select_item.now == 0); + Draw_Back_First(select_item.now == CASE_BACK); Item_HomeOffs_X(1); // "Home Offset X" Item_HomeOffs_Y(2); // "Home Offset Y" Item_HomeOffs_Z(3); // "Home Offset Z" - if (select_item.now) Draw_Menu_Cursor(select_item.now); + if (select_item.now != CASE_BACK) Draw_Menu_Cursor(select_item.now); } #if HAS_ONESTEP_LEVELING void Draw_ProbeOff_Menu() { Clear_Main_Window(); - Draw_Back_First(select_item.now == 0); + Draw_Back_First(select_item.now == CASE_BACK); if (false && HMI_IsChinese()) { // TODO: Chinese "Probe Offsets" } @@ -2609,7 +2613,7 @@ void Draw_HomeOff_Menu() { Draw_Edit_Signed_Float3(1, HMI_ValueStruct.Probe_OffX_scaled); Draw_Edit_Signed_Float3(2, HMI_ValueStruct.Probe_OffY_scaled); - if (select_item.now) Draw_Menu_Cursor(select_item.now); + if (select_item.now != CASE_BACK) Draw_Menu_Cursor(select_item.now); } #endif @@ -2682,11 +2686,11 @@ void HMI_Prepare() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_prepare.now) { - case 0: // Back + case CASE_BACK: select_page.set(1); Goto_MainMenu(); break; - case PREPARE_CASE_MOVE: // Axis move + case PREPARE_CASE_MOVE: checkkey = AxisMove; select_axis.reset(); Draw_Move_Menu(); @@ -2699,9 +2703,9 @@ void HMI_Prepare() { Draw_Edit_Signed_Float3(4, HMI_ValueStruct.Move_E_scaled); #endif break; - case PREPARE_CASE_DISA: // Disable steppers - queue.inject_P(PSTR("M84")); - break; + + case PREPARE_CASE_DISA: queue.inject_P(PSTR("M84")); break; + case PREPARE_CASE_HOME: // Homing checkkey = Last_Prepare; index_prepare = MROWS; @@ -2709,7 +2713,7 @@ void HMI_Prepare() { Popup_Window_Home(); break; #if HAS_ZOFFSET_ITEM - case PREPARE_CASE_ZOFF: // Z-offset + case PREPARE_CASE_ZOFF: #if EITHER(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.show_mode = -4; @@ -2724,24 +2728,24 @@ void HMI_Prepare() { break; #endif #if HAS_PREHEAT - case PREPARE_CASE_PLA: // PLA preheat + case PREPARE_CASE_PLA: TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0)); TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[0].bed_temp)); TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed)); break; - case PREPARE_CASE_ABS: // ABS preheat + case PREPARE_CASE_ABS: TERN_(HAS_HOTEND, thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0)); TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(ui.material_preset[1].bed_temp)); TERN_(HAS_FAN, thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed)); break; - case PREPARE_CASE_COOL: // Cool + case PREPARE_CASE_COOL: TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); #if HAS_HOTEND || HAS_HEATED_BED thermalManager.disable_all_heaters(); #endif break; #endif - case PREPARE_CASE_LANG: // Toggle Language + case PREPARE_CASE_LANG: HMI_ToggleLanguage(); Draw_Prepare_Menu(); break; @@ -2814,8 +2818,8 @@ void Draw_Temperature_Menu() { #endif } - Draw_Back_First(select_temp.now == 0); - if (select_temp.now) Draw_Menu_Cursor(select_temp.now); + Draw_Back_First(select_temp.now == CASE_BACK); + if (select_temp.now != CASE_BACK) Draw_Menu_Cursor(select_temp.now); // Draw icons and lines uint8_t i = 0; @@ -2884,41 +2888,41 @@ void HMI_Control() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_control.now) { - case 0: // Back + case CASE_BACK: select_page.set(2); Goto_MainMenu(); break; - case CONTROL_CASE_TEMP: // Temperature + case CONTROL_CASE_TEMP: checkkey = TemperatureID; HMI_ValueStruct.show_mode = -1; select_temp.reset(); Draw_Temperature_Menu(); break; - case CONTROL_CASE_MOVE: // Motion + case CONTROL_CASE_MOVE: checkkey = Motion; select_motion.reset(); Draw_Motion_Menu(); break; #if ENABLED(EEPROM_SETTINGS) - case CONTROL_CASE_SAVE: { // Write EEPROM + case CONTROL_CASE_SAVE: { const bool success = settings.save(); HMI_AudioFeedback(success); } break; - case CONTROL_CASE_LOAD: { // Read EEPROM + case CONTROL_CASE_LOAD: { const bool success = settings.load(); HMI_AudioFeedback(success); } break; - case CONTROL_CASE_RESET: // Reset EEPROM + case CONTROL_CASE_RESET: settings.reset(); HMI_AudioFeedback(); break; #endif - case CONTROL_CASE_ADVSET: // Advanced Settings + case CONTROL_CASE_ADVSET: checkkey = AdvSet; select_advset.reset(); Draw_AdvancedSettings_Menu(); break; - case CONTROL_CASE_INFO: // Info + case CONTROL_CASE_INFO: checkkey = Info; Draw_Info_Menu(); break; @@ -2971,7 +2975,7 @@ void HMI_AxisMove() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_axis.now) { - case 0: // Back + case CASE_BACK: checkkey = Prepare; select_prepare.set(1); index_prepare = MROWS; @@ -2997,8 +3001,7 @@ void HMI_AxisMove() { break; #if HAS_HOTEND case 4: // Extruder - // window tips - #ifdef PREVENT_COLD_EXTRUSION + #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(0)) { HMI_flag.ETempTooLow_flag = true; Popup_Window_ETempTooLow(); @@ -3031,14 +3034,14 @@ void HMI_Temperature() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_temp.now) { - case 0: // Back + case CASE_BACK: checkkey = Control; select_control.set(1); index_control = MROWS; Draw_Control_Menu(); break; #if HAS_HOTEND - case TEMP_CASE_TEMP: // Nozzle temperature + case TEMP_CASE_TEMP: checkkey = ETemp; HMI_ValueStruct.E_Temp = thermalManager.degTargetHotend(0); Draw_Edit_Integer3(1, HMI_ValueStruct.E_Temp, true); @@ -3046,7 +3049,7 @@ void HMI_Temperature() { break; #endif #if HAS_HEATED_BED - case TEMP_CASE_BED: // Bed temperature + case TEMP_CASE_BED: checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = thermalManager.degTargetBed(); Draw_Edit_Integer3(2, HMI_ValueStruct.Bed_Temp, true); @@ -3054,7 +3057,7 @@ void HMI_Temperature() { break; #endif #if HAS_FAN - case TEMP_CASE_FAN: // Fan speed + case TEMP_CASE_FAN: checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; Draw_Edit_Integer3(3, HMI_ValueStruct.Fan_speed, true); @@ -3062,7 +3065,7 @@ void HMI_Temperature() { break; #endif #if HAS_HOTEND - case TEMP_CASE_PLA: { // PLA preheat setting + case TEMP_CASE_PLA: { checkkey = PLAPreheat; select_PLA.reset(); HMI_ValueStruct.show_mode = -2; @@ -3458,30 +3461,30 @@ void HMI_Motion() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_motion.now) { - case 0: // Back + case CASE_BACK: checkkey = Control; select_control.set(CONTROL_CASE_MOVE); index_control = MROWS; Draw_Control_Menu(); break; - case MOTION_CASE_RATE: // Max speed + case MOTION_CASE_RATE: checkkey = MaxSpeed; select_speed.reset(); Draw_Max_Speed_Menu(); break; - case MOTION_CASE_ACCEL: // Max acceleration + case MOTION_CASE_ACCEL: checkkey = MaxAcceleration; select_acc.reset(); Draw_Max_Accel_Menu(); break; #if HAS_CLASSIC_JERK - case MOTION_CASE_JERK: // Max jerk + case MOTION_CASE_JERK: checkkey = MaxJerk; select_jerk.reset(); Draw_Max_Jerk_Menu(); break; #endif - case MOTION_CASE_STEPS: // Steps per mm + case MOTION_CASE_STEPS: checkkey = Step; select_step.reset(); Draw_Steps_Menu(); @@ -3533,7 +3536,7 @@ void HMI_AdvSet() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_advset.now) { - case 0: // Back + case CASE_BACK: checkkey = Control; select_control.set(CONTROL_CASE_ADVSET); index_control = CONTROL_CASE_ADVSET; @@ -3541,7 +3544,7 @@ void HMI_AdvSet() { break; #if HAS_HOME_OFFSET - case ADVSET_CASE_HOMEOFF: // Home Offsets + case ADVSET_CASE_HOMEOFF: checkkey = HomeOff; select_item.reset(); HMI_ValueStruct.Home_OffX_scaled = home_offset[X_AXIS] * 10; @@ -3552,7 +3555,7 @@ void HMI_AdvSet() { #endif #if HAS_ONESTEP_LEVELING - case ADVSET_CASE_PROBEOFF: // Probe Offsets + case ADVSET_CASE_PROBEOFF: checkkey = ProbeOff; select_item.reset(); HMI_ValueStruct.Probe_OffX_scaled = probe.offset.x * 10; @@ -3562,21 +3565,21 @@ void HMI_AdvSet() { #endif #if HAS_HOTEND - case ADVSET_CASE_HEPID: // Nozzle PID Autotune + case ADVSET_CASE_HEPID: thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); thermalManager.PID_autotune(ui.material_preset[0].hotend_temp, H_E0, 10, true); break; #endif #if HAS_HEATED_BED - case ADVSET_CASE_BEDPID: // Bed PID Autotune + case ADVSET_CASE_BEDPID: thermalManager.setTargetBed(ui.material_preset[0].bed_temp); thermalManager.PID_autotune(ui.material_preset[0].bed_temp, H_BED, 10, true); break; #endif #if ENABLED(POWER_LOSS_RECOVERY) - case ADVSET_CASE_PWRLOSSR: // Power-loss recovery + case ADVSET_CASE_PWRLOSSR: recovery.enable(!recovery.enabled); Draw_Checkbox_Line(ADVSET_CASE_PWRLOSSR + MROWS - index_advset, recovery.enabled); break; @@ -3603,7 +3606,7 @@ void HMI_AdvSet() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_item.now) { - case 0: // Back + case CASE_BACK: checkkey = AdvSet; select_advset.set(ADVSET_CASE_HOMEOFF); Draw_AdvancedSettings_Menu(); @@ -3665,7 +3668,7 @@ void HMI_AdvSet() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_item.now) { - case 0: // Back + case CASE_BACK: checkkey = AdvSet; select_advset.set(ADVSET_CASE_PROBEOFF); Draw_AdvancedSettings_Menu(); @@ -3675,7 +3678,7 @@ void HMI_AdvSet() { Draw_Edit_Signed_Float3(1, HMI_ValueStruct.Probe_OffX_scaled, true); EncoderRate.enabled = true; break; - case 2: // Probe Offset X + case 2: // Probe Offset Y checkkey = ProbeOffY; Draw_Edit_Signed_Float3(2, HMI_ValueStruct.Probe_OffY_scaled, true); EncoderRate.enabled = true; @@ -3822,14 +3825,14 @@ void HMI_Tune() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_PLA.now) { - case 0: // Back + case CASE_BACK: checkkey = TemperatureID; select_temp.now = TEMP_CASE_PLA; HMI_ValueStruct.show_mode = -1; Draw_Temperature_Menu(); break; #if HAS_HOTEND - case PREHEAT_CASE_TEMP: // Nozzle temperature + case PREHEAT_CASE_TEMP: checkkey = ETemp; HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; Draw_Edit_Integer3(PREHEAT_CASE_TEMP, ui.material_preset[0].hotend_temp, true); @@ -3837,7 +3840,7 @@ void HMI_Tune() { break; #endif #if HAS_HEATED_BED - case PREHEAT_CASE_BED: // Bed temperature + case PREHEAT_CASE_BED: checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; Draw_Edit_Integer3(PREHEAT_CASE_BED, ui.material_preset[0].bed_temp, true); @@ -3845,7 +3848,7 @@ void HMI_Tune() { break; #endif #if HAS_FAN - case PREHEAT_CASE_FAN: // Fan speed + case PREHEAT_CASE_FAN: checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; Draw_Edit_Integer3(PREHEAT_CASE_FAN, ui.material_preset[0].fan_speed, true); @@ -3853,7 +3856,7 @@ void HMI_Tune() { break; #endif #if ENABLED(EEPROM_SETTINGS) - case 4: { // Save PLA configuration + case PREHEAT_CASE_SAVE: { const bool success = settings.save(); HMI_AudioFeedback(success); } break; @@ -3878,14 +3881,14 @@ void HMI_Tune() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_ABS.now) { - case 0: // Back + case CASE_BACK: checkkey = TemperatureID; select_temp.now = TEMP_CASE_ABS; HMI_ValueStruct.show_mode = -1; Draw_Temperature_Menu(); break; #if HAS_HOTEND - case PREHEAT_CASE_TEMP: // Set nozzle temperature + case PREHEAT_CASE_TEMP: checkkey = ETemp; HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; Draw_Edit_Integer3(PREHEAT_CASE_TEMP, ui.material_preset[1].hotend_temp, true); @@ -3893,7 +3896,7 @@ void HMI_Tune() { break; #endif #if HAS_HEATED_BED - case PREHEAT_CASE_BED: // Set bed temperature + case PREHEAT_CASE_BED: checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; Draw_Edit_Integer3(PREHEAT_CASE_BED, ui.material_preset[1].bed_temp, true); @@ -3901,7 +3904,7 @@ void HMI_Tune() { break; #endif #if HAS_FAN - case PREHEAT_CASE_FAN: // Set fan speed + case PREHEAT_CASE_FAN: checkkey = FanSpeed; HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; Draw_Edit_Integer3(PREHEAT_CASE_FAN, ui.material_preset[1].fan_speed, true); @@ -3909,7 +3912,7 @@ void HMI_Tune() { break; #endif #if ENABLED(EEPROM_SETTINGS) - case PREHEAT_CASE_SAVE: { // Save ABS configuration + case PREHEAT_CASE_SAVE: { const bool success = settings.save(); HMI_AudioFeedback(success); } break; diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h index 262276f590..dab3806de6 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -31,9 +31,6 @@ #include -//#define USE_STRING_HEADINGS -//#define USE_STRING_TITLES - #define RECEIVED_NO_DATA 0x00 #define RECEIVED_SHAKE_HAND_ACK 0x01 diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index cea36e21d6..dd4f07cb3a 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -86,9 +86,6 @@ #define PAUSE_HEAT -#define USE_STRING_HEADINGS -#define USE_STRING_TITLES - #define MENU_CHAR_LIMIT 24 // Print speed limit @@ -133,8 +130,20 @@ HMI_data_t HMI_data; millis_t dwin_heat_time = 0; -uint8_t checkkey = MainMenu; -uint8_t last_checkkey = MainMenu; +uint8_t checkkey = MainMenu, last_checkkey = MainMenu; + +enum SelectItem : uint8_t { + PAGE_PRINT = 0, + PAGE_PREPARE, + PAGE_CONTROL, + PAGE_INFO_LEVELING, + PAGE_COUNT, + + PRINT_SETUP = 0, + PRINT_PAUSE_RESUME, + PRINT_STOP, + PRINT_COUNT +}; typedef struct { uint8_t now, last; @@ -266,7 +275,7 @@ void ICON_Print() { { 1, { 417, 449 }, 30, 14 }, { 1, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 0, ICON_Print_0, ico, txt); + ICON_Button(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt); } // @@ -278,7 +287,7 @@ void ICON_Prepare() { { 33, { 417, 449 }, 51, 14 }, { 31, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 1, ICON_Prepare_0, ico, txt); + ICON_Button(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt); } // @@ -290,7 +299,7 @@ void ICON_Control() { { 85, { 417, 449 }, 46, 14 }, { 61, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 2, ICON_Control_0, ico, txt); + ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt); } // @@ -302,7 +311,7 @@ void ICON_StartInfo() { { 133, { 417, 449 }, 23, 14 }, { 91, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 3, ICON_Info_0, ico, txt); + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Info_0, ico, txt); } // @@ -314,7 +323,7 @@ void ICON_Leveling() { { 88, { 433, 464 }, 36, 14 }, { 211, { 405, 447 }, 27, 15 } }; - ICON_Button(select_page.now == 3, ICON_Leveling_0, ico, txt); + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Leveling_0, ico, txt); } // @@ -326,7 +335,7 @@ void ICON_Tune() { { 0, { 433, 464 }, 32, 14 }, { 121, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 0, ICON_Setup_0, ico, txt); + ICON_Button(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt); } // @@ -338,7 +347,7 @@ void ICON_Pause() { { 157, { 417, 449 }, 39, 14 }, { 181, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 1, ICON_Pause_0, ico, txt); + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt); } // @@ -350,7 +359,7 @@ void ICON_Resume() { { 33, { 433, 464 }, 53, 14 }, { 1, { 405, 447 }, 27, 15 } }; - ICON_Button(select_print.now == 1, ICON_Continue_0, ico, txt); + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt); } // @@ -362,7 +371,7 @@ void ICON_Stop() { { 196, { 417, 449 }, 29, 14 }, { 151, { 405, 447 }, 27, 12 } }; - ICON_Button(select_print.now == 2, ICON_Stop_0, ico, txt); + ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt); } void Draw_Menu_Cursor(const uint8_t line) { @@ -537,14 +546,14 @@ void Popup_window_PauseOrStop() { if (HMI_IsChinese()) { DWINUI::ClearMenuArea(); Draw_Popup_Bkgd_60(); - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + else if (select_print.now == PRINT_STOP) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); DWINUI::Draw_Icon(ICON_Confirm_C, 26, 280); DWINUI::Draw_Icon(ICON_Cancel_C, 146, 280); } else { - DWIN_Draw_Popup(ICON_BLTouch, "Please confirm",(select_print.now == 1) ? GET_TEXT(MSG_PAUSE_PRINT) : GET_TEXT(MSG_STOP_PRINT)); + DWIN_Draw_Popup(ICON_BLTouch, "Please confirm", select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT(MSG_PAUSE_PRINT) : GET_TEXT(MSG_STOP_PRINT)); DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); } @@ -589,16 +598,9 @@ void Draw_Print_Labels() { DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain } else { - #ifdef USE_STRING_TITLES - Title.ShowCaption(GET_TEXT(MSG_PRINTING)); - DWINUI::Draw_String( 46, 173, F("Print Time")); - DWINUI::Draw_String(181, 173, F("Remain")); - #else - const uint16_t y = 168; - Title.FrameCopy(42, 0, 47, 14); // "Printing" - DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, y); // Printing Time - DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, y); // Remain - #endif + Title.ShowCaption(GET_TEXT(MSG_PRINTING)); + DWINUI::Draw_String( 46, 173, F("Print Time")); + DWINUI::Draw_String(181, 173, F("Remain")); } } @@ -678,13 +680,8 @@ void Draw_Main_Menu() { if (HMI_IsChinese()) Title.FrameCopy(2, 2, 26, 13); // "Home" etc - else { - #ifdef USE_STRING_HEADINGS - Title.ShowCaption(MACHINE_NAME); - #else - Title.FrameCopy(0, 2, 40, 11); // "Home" - #endif - } + else + Title.ShowCaption(MACHINE_NAME); DWINUI::Draw_Icon(ICON_LOGO, 71, 52); // CREALITY logo @@ -1075,11 +1072,7 @@ void Draw_Info_Menu() { DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" } else { - #ifdef USE_STRING_HEADINGS - Title.ShowCaption(GET_TEXT_F(MSG_INFO_SCREEN)); - #else - Title.FrameCopy(192, 15, 23, 12); // "Info" - #endif + Title.ShowCaption(GET_TEXT_F(MSG_INFO_SCREEN)); DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); // "Size" DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); // "Firmware Version" @@ -1098,13 +1091,8 @@ void Draw_Info_Menu() { void Draw_Print_File_Menu() { if (HMI_IsChinese()) Title.FrameCopy(0, 31, 56, 14); // "Print file" - else { - #ifdef USE_STRING_HEADINGS - Title.ShowCaption(GET_TEXT_F(MSG_MEDIA_MENU)); - #else - Title.FrameCopy(52, 31, 86, 11); // "Print file" - #endif - } + else + Title.ShowCaption(GET_TEXT_F(MSG_MEDIA_MENU)); Redraw_SD_List(); } @@ -1114,43 +1102,39 @@ void HMI_MainMenu() { if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_page.inc(4)) { + if (select_page.inc(PAGE_COUNT)) { switch (select_page.now) { - case 0: ICON_Print(); break; - case 1: ICON_Print(); ICON_Prepare(); break; - case 2: ICON_Prepare(); ICON_Control(); break; - case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_PRINT: ICON_Print(); break; + case PAGE_PREPARE: ICON_Print(); ICON_Prepare(); break; + case PAGE_CONTROL: ICON_Prepare(); ICON_Control(); break; + case PAGE_INFO_LEVELING: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_page.dec()) { switch (select_page.now) { - case 0: ICON_Print(); ICON_Prepare(); break; - case 1: ICON_Prepare(); ICON_Control(); break; - case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; - case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_PRINT: ICON_Print(); ICON_Prepare(); break; + case PAGE_PREPARE: ICON_Prepare(); ICON_Control(); break; + case PAGE_CONTROL: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; + case PAGE_INFO_LEVELING: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); break; } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_page.now) { - case 0: // Print File + case PAGE_PRINT: checkkey = SelectFile; Draw_Print_File_Menu(); break; - case 1: // Prepare - Draw_Prepare_Menu(); - break; + case PAGE_PREPARE: Draw_Prepare_Menu(); break; - case 2: // Control - Draw_Control_Menu(); - break; + case PAGE_CONTROL: Draw_Control_Menu(); break; - case 3: // Leveling or Info + case PAGE_INFO_LEVELING: #if HAS_ONESTEP_LEVELING - queue.inject_P(PSTR("G28XYO\nG28Z\nG29")); + queue.inject_P(PSTR("G28XYO\nG28Z\nG29")); // TODO: 'G29' should be homing when needed. Does it make sense for every LCD to do this differently? #else checkkey = Info; Draw_Info_Menu(); @@ -1238,8 +1222,8 @@ void HMI_SelectFile() { } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { // Back - select_page.set(0); + if (select_file.now == 0) { + select_page.set(PAGE_PRINT); Goto_Main_Menu(); } else if (hasUpDir && select_file.now == 1) { // CD-Up @@ -1276,7 +1260,8 @@ void HMI_SelectFile() { DWIN_Print_Started(true); } } -HMI_SelectFileExit: + + HMI_SelectFileExit: DWIN_UpdateLCD(); } @@ -1286,44 +1271,30 @@ void HMI_Printing() { if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_print.inc(3)) { + if (select_print.inc(PRINT_COUNT)) { switch (select_print.now) { - case 0: ICON_Tune(); break; - case 1: - ICON_Tune(); - ICON_ResumeOrPause(); - break; - case 2: - ICON_ResumeOrPause(); - ICON_Stop(); - break; + case PRINT_SETUP: ICON_Tune(); break; + case PRINT_PAUSE_RESUME: ICON_Tune(); ICON_ResumeOrPause(); break; + case PRINT_STOP: ICON_ResumeOrPause(); ICON_Stop(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_print.dec()) { switch (select_print.now) { - case 0: - ICON_Tune(); - ICON_ResumeOrPause(); - break; - case 1: - ICON_ResumeOrPause(); - ICON_Stop(); - break; - case 2: ICON_Stop(); break; + case PRINT_SETUP: ICON_Tune(); ICON_ResumeOrPause(); break; + case PRINT_PAUSE_RESUME: ICON_ResumeOrPause(); ICON_Stop(); break; + case PRINT_STOP: ICON_Stop(); break; } } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_print.now) { - case 0: // Tune - Draw_Tune_Menu(); - break; - case 1: // Pause + case PRINT_SETUP: Draw_Tune_Menu(); break; + case PRINT_PAUSE_RESUME: if (HMI_flag.pause_flag) { ICON_Pause(); - #ifndef ADVANCED_PAUSE_FEATURE + #if DISABLED(ADVANCED_PAUSE_FEATURE) char cmd[40]; cmd[0] = '\0'; #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) @@ -1346,7 +1317,7 @@ void HMI_Printing() { } break; - case 2: // Stop + case PRINT_STOP: HMI_flag.select_flag = true; checkkey = PauseOrStop; Popup_window_PauseOrStop(); @@ -1378,7 +1349,7 @@ void HMI_PauseOrStop() { else if (encoder_diffState == ENCODER_DIFF_CCW) Draw_Select_Highlight(true); else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_print.now == 1) { // pause window + if (select_print.now == PRINT_PAUSE_RESUME) { if (HMI_flag.select_flag) { HMI_flag.pause_action = true; ICON_Resume(); @@ -1389,7 +1360,7 @@ void HMI_PauseOrStop() { } Goto_PrintProcess(); } - else if (select_print.now == 2) { // stop window + else if (select_print.now == PRINT_STOP) { if (HMI_flag.select_flag) { checkkey = MainMenu; if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! @@ -1511,22 +1482,12 @@ void EachMomentUpdate() { if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { HMI_flag.pause_action = false; #if ENABLED(PAUSE_HEAT) - if (sdprint) { - TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.degTargetHotend(0)); - TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.degTargetBed()); - } - else { - TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.wholeDegHotend(0)); - TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.wholeDegBed()); - } + TERN_(HAS_HOTEND, resume_hotend_temp = sdprint ? thermalManager.degTargetHotend(0) : thermalManager.wholeDegHotend(0)); + TERN_(HAS_HEATED_BED, resume_bed_temp = sdprint ? thermalManager.degTargetBed() : thermalManager.wholeDegBed()); TERN_(HAS_FAN, resume_fan = thermalManager.fan_speed[0]); #endif - #if DISABLED(ADVANCED_PAUSE_FEATURE) - thermalManager.disable_all_heaters(); - #endif - #if DISABLED(PARK_HEAD_ON_PAUSE) - queue.inject_P(PSTR("G1 F1200 X0 Y0")); - #endif + IF_DISABLED(ADVANCED_PAUSE_FEATURE, thermalManager.disable_all_heaters()); + IF_DISABLED(PARK_HEAD_ON_PAUSE, queue.inject_P(PSTR("G1 F1200 X0 Y0"))); } if (checkkey == PrintProcess) { // print process @@ -1565,7 +1526,7 @@ void EachMomentUpdate() { else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop dwin_abort_flag = false; dwin_zoffset = BABY_Z_VAR; - select_page.set(0); + select_page.set(PAGE_PRINT); Goto_Main_Menu(); } @@ -1615,7 +1576,7 @@ void EachMomentUpdate() { watchdog_refresh(); } - select_print.set(0); + select_print.set(PRINT_SETUP); queue.inject_P(PSTR("M1000")); sdprint = true; Goto_PrintProcess(); @@ -1735,7 +1696,6 @@ void DWIN_PidTuning(pidresult_t result) { // Update filename on print void DWIN_Print_Header(const char *text = nullptr) { - static char headertxt[31] = ""; // Print header text if (text != nullptr) { @@ -1917,6 +1877,7 @@ void DWIN_Redraw_screen() { DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); DWINUI::Draw_Icon(ICON_Continue_E, 146, 280); Draw_Select_Highlight(true); + DWIN_UpdateLCD(); } // Handle responses such as: @@ -1981,7 +1942,6 @@ void DWIN_LockScreen(const bool flag) { // LiveUpdate: live update function when the encoder changes // Apply: update function when the encoder is pressed void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - last_checkkey = Menu; checkkey = process; HMI_value.MinValue = lo; HMI_value.MaxValue = hi; @@ -2092,13 +2052,9 @@ void Goto_InfoMenu(){ Draw_Info_Menu(); } -void DisableMotors() { - queue.inject_P(PSTR("M84")); -} +void DisableMotors() { queue.inject_P(PSTR("M84")); } -void AutoHome() { - queue.inject_P(G28_STR); -} +void AutoHome() { queue.inject_P(G28_STR); } void SetHome() { // Apply workspace offset, making the current position 0,0,0 @@ -2116,9 +2072,11 @@ void SetHome() { if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif } - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - void SetZOffset() { SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); } - #endif + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + void SetZOffset() { + SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); + } + #endif #endif #if HAS_PREHEAT @@ -2233,9 +2191,7 @@ void SetPID(celsius_t t, heater_id_t h) { } #endif -void Goto_LockScreen() { - DWIN_LockScreen(true); -} +void Goto_LockScreen() { DWIN_LockScreen(true); } #if HAS_HOME_OFFSET void ApplyHomeOffset() { set_home_offset(HMI_value.axis, HMI_value.Value / MINUNITMULT); } @@ -2327,6 +2283,7 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) + void ChangeFilament() { HMI_SaveProcessID(NothingToDo); queue.inject_P(PSTR("M600 B2")); @@ -2348,7 +2305,8 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } queue.inject_P(PSTR("M701 Z20")); } #endif -#endif + +#endif // ADVANCED_PAUSE_FEATURE void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW); } @@ -2414,6 +2372,7 @@ void LevBedBL() { LevBed(3); } void LevBedC () { LevBed(4); } #if ENABLED(MESH_BED_LEVELING) + void ManualMeshStart(){ ui.set_status_P(GET_TEXT(MSG_UBL_BUILD_MESH_MENU)); gcode.process_subcommands_now_P(PSTR("G28 XYO\nG28 Z\nM211 S0\nG29S1")); @@ -2443,7 +2402,8 @@ void LevBedC () { LevBed(4); } ui.set_status_P(GET_TEXT(MSG_UBL_STORAGE_MESH_MENU)); queue.inject_P(PSTR("M211 S1\nM500")); } -#endif + +#endif // MESH_BED_LEVELING #if HAS_PREHEAT #if HAS_HOTEND @@ -2516,6 +2476,7 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP SetFloatOnClick(0, 1000, 2, value, ApplyPIDd); } #endif + // Menuitem Drawing functions ================================================= void onDrawMenuItem(MenuItemClass* menuitem, int8_t line) { @@ -2721,7 +2682,6 @@ void onDrawGetColorItem(MenuItemClass* menuitem, int8_t line) { void onDrawPIDi(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_i(*(float*)static_cast(menuitem)->value)); } void onDrawPIDd(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_d(*(float*)static_cast(menuitem)->value)); } - void onDrawSpeedItem(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 116, 164, 171, 176); onDrawPIntMenu(menuitem, line); @@ -2748,30 +2708,6 @@ void onDrawSpeedItem(MenuItemClass* menuitem, int8_t line) { } #endif -void onDrawSpeed(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) menuitem->SetFrame(1, 173, 133, 228, 147); - onDrawSubMenu(menuitem, line); -} - -void onDrawAcc(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) { - menuitem->SetFrame(1, 173, 133, 200, 147); - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line) + 1); // ...Acceleration - } - onDrawSubMenu(menuitem, line); -} - -#if HAS_CLASSIC_JERK - void onDrawJerk(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) { - menuitem->SetFrame(1, 173, 133, 200, 147); - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(line)); // ...Jerk - } - onDrawSubMenu(menuitem, line); - } -#endif - void onDrawSteps(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 153, 148, 194, 161); onDrawSubMenu(menuitem, line); @@ -2786,10 +2722,10 @@ void onDrawSteps(MenuItemClass* menuitem, int8_t line) { #if HAS_PREHEAT #if HAS_HOTEND - void onDrawSetPreheatHotend(MenuItemClass* menuitem, int8_t line) { - if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 134, 56, 146); - onDrawPIntMenu(menuitem, line); - } + void onDrawSetPreheatHotend(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) menuitem->SetFrame(1, 1, 134, 56, 146); + onDrawPIntMenu(menuitem, line); + } #endif #if HAS_HEATED_BED void onDrawSetPreheatBed(MenuItemClass* menuitem, int8_t line) { @@ -2811,7 +2747,13 @@ void onDrawSteps(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 180, 89, 260, 100); onDrawSubMenu(menuitem,line); } -#endif // HAS_HOTEND +#endif // HAS_PREHEAT + +void onDrawSpeed(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) + menuitem->SetFrame(1, 173, 133, 228, 147); + onDrawSubMenu(menuitem, line); +} void onDrawMaxSpeedX(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { @@ -2847,9 +2789,17 @@ void onDrawMaxSpeedZ(MenuItemClass* menuitem, int8_t line) { } #endif +void onDrawAcc(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line) + 1); // ...Acceleration + } + onDrawSubMenu(menuitem, line); +} + void onDrawMaxAccelX(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(line)); // X } @@ -2858,7 +2808,7 @@ void onDrawMaxAccelX(MenuItemClass* menuitem, int8_t line) { void onDrawMaxAccelY(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(line)); // Y } @@ -2867,7 +2817,7 @@ void onDrawMaxAccelY(MenuItemClass* menuitem, int8_t line) { void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(line)); // Z } @@ -2877,7 +2827,7 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { #if HAS_HOTEND void onDrawMaxAccelE(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(line)); // E } @@ -2886,9 +2836,19 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { #endif #if HAS_CLASSIC_JERK + + void onDrawJerk(MenuItemClass* menuitem, int8_t line) { + if (HMI_IsChinese()) { + menuitem->SetFrame(1, 173, 133, 200, 147); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line) + 1); // ... + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(line)); // ...Jerk + } + onDrawSubMenu(menuitem, line); + } + void onDrawMaxJerkX(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(line)); @@ -2898,7 +2858,7 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { void onDrawMaxJerkY(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(line)); @@ -2908,7 +2868,7 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { void onDrawMaxJerkZ(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(line)); @@ -2919,7 +2879,7 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { #if HAS_HOTEND void onDrawMaxJerkE(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 173, 133, 200, 147); + menuitem->SetFrame(1, 173, 133, 200, 147); DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(line)); DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(line)); DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(line)); @@ -2927,11 +2887,12 @@ void onDrawMaxAccelZ(MenuItemClass* menuitem, int8_t line) { onDrawPFloatMenu(menuitem, line); } #endif + #endif // HAS_CLASSIC_JERK void onDrawStepsX(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 153, 148, 194, 161); + menuitem->SetFrame(1, 153, 148, 194, 161); DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(line)); // X } onDrawPFloatMenu(menuitem, line); @@ -2939,7 +2900,7 @@ void onDrawStepsX(MenuItemClass* menuitem, int8_t line) { void onDrawStepsY(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 153, 148, 194, 161); + menuitem->SetFrame(1, 153, 148, 194, 161); DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(line)); // Y } onDrawPFloatMenu(menuitem, line); @@ -2947,7 +2908,7 @@ void onDrawStepsY(MenuItemClass* menuitem, int8_t line) { void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 153, 148, 194, 161); + menuitem->SetFrame(1, 153, 148, 194, 161); DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(line)); // Z } onDrawPFloatMenu(menuitem, line); @@ -2956,7 +2917,7 @@ void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { #if HAS_HOTEND void onDrawStepsE(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) { - menuitem->SetFrame (1, 153, 148, 194, 161); + menuitem->SetFrame(1, 153, 148, 194, 161); DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(line)); // E } onDrawPFloatMenu(menuitem, line); @@ -2986,7 +2947,7 @@ int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; - checkkey = last_checkkey; + checkkey = Menu; return 2; } LIMIT(HMI_value.Value, lo, hi); @@ -3008,7 +2969,7 @@ int8_t HMI_GetInt(const int32_t lo, const int32_t hi) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; DWINUI::Draw_Int(HMI_data.Text_Color, HMI_data.Background_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, HMI_value.Value); - checkkey = last_checkkey; + checkkey = Menu; return 2; } LIMIT(HMI_value.Value, lo, hi); @@ -3048,7 +3009,7 @@ void HMI_SetPInt() { } else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); } -// Get an scaled float value using the encoder +// Get a scaled float value using the encoder // dp: decimal places // lo: scaled low limit // hi: scaled high limit @@ -3062,7 +3023,7 @@ int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); - checkkey = last_checkkey; + checkkey = Menu; return 2; } LIMIT(HMI_value.Value, lo, hi); @@ -3072,38 +3033,34 @@ int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { return 0; } -// Set an scaled float using the encoder +// Set a scaled float using the encoder void HMI_SetFloat() { - int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); + const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); switch (val) { - case 0: return; break; + case 0: return; case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; } } -// Set an scaled float pointer variable using the encoder +// Set a scaled float pointer variable using the encoder void HMI_SetPFloat() { - int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); + const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); if (!val) return; - else if (val == 2) { // Apply + if (val == 2) { // Apply *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); if (HMI_value.Apply != nullptr) HMI_value.Apply(); - } else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); + } + else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); } // Menu Creation and Drawing functions ====================================================== void SetMenuTitle(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { - if (HMI_IsChinese() && (cn.w != 0)) - CurrentMenu->MenuTitle.SetFrame(cn.x, cn.y, cn.w, cn.h); - else { - #ifdef USE_STRING_HEADINGS - CurrentMenu->MenuTitle.SetCaption(text); - #else - if (en.w != 0) CurrentMenu->MenuTitle.SetFrame(en.x, en.y, en.w, en.h); - #endif - } + if (HMI_IsChinese() && (cn.w != 0)) + CurrentMenu->MenuTitle.SetFrame(cn.x, cn.y, cn.w, cn.h); + else + CurrentMenu->MenuTitle.SetCaption(text); } void Draw_Prepare_Menu() { @@ -3301,7 +3258,8 @@ void Draw_Move_Menu() { } CurrentMenu->Draw(); } -#endif +#endif // HAS_FILAMENT_SENSOR + void Draw_SelectColors_Menu() { checkkey = Menu; if (SelectColorMenu == nullptr) SelectColorMenu = new MenuClass(); @@ -3441,6 +3399,7 @@ void Draw_Motion_Menu() { #endif #if HAS_PREHEAT + void Draw_Preheat_Menu(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { checkkey = Menu; if (CurrentMenu != PreheatMenu) { @@ -3485,7 +3444,7 @@ void Draw_Motion_Menu() { } #endif -#endif +#endif // HAS_PREHEAT void Draw_Temperature_Menu() { checkkey = Menu; @@ -3653,5 +3612,4 @@ void Draw_Steps_Menu() { } #endif - #endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index db4cc2121f..ccc47907cf 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -157,15 +157,9 @@ void Popup_Window_Resume(); void HMI_SDCardInit(); void HMI_SDCardUpdate(); -// Main Process -//void Icon_print(); -//void Icon_control(); -//void Icon_leveling(bool value); - // Other void Goto_PrintProcess(); void Goto_Main_Menu(); -void update_variable(); void Draw_Select_Highlight(const bool sel); void Draw_Status_Area(const bool with_update); // Status Area void Draw_Main_Area(); // Redraw main area; @@ -178,19 +172,15 @@ void HMI_ReturnScreen(); // Return to previous screen before popups void ApplyExtMinT(); void HMI_SetLanguageCache(); // Set the languaje image cache -//void HMI_Leveling(); // Level the page -//void HMI_LevBedCorners(); // Tramming menu -//void HMI_Info(); // Information menu - - void HMI_Init(); void HMI_Popup(); void HMI_SaveProcessID(const uint8_t id); void HMI_AudioFeedback(const bool success=true); +void EachMomentUpdate(); +void update_variable(); +void DWIN_HandleScreen(); void DWIN_Startup(); void DWIN_Update(); -void EachMomentUpdate(); -void DWIN_HandleScreen(); void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text); void DWIN_StatusChanged(const char * const text); void DWIN_StatusChanged_P(PGM_P const text); diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index c02aa48b1a..9b63d5331e 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -141,15 +141,24 @@ constexpr float default_steps[] = DEFAULT_AXIS_STEPS_PER_UNIT; constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; #endif -uint8_t active_menu = MainMenu; -uint8_t last_menu = MainMenu; -uint8_t selection = 0; -uint8_t last_selection = 0; +enum SelectItem : uint8_t { + PAGE_PRINT = 0, + PAGE_PREPARE, + PAGE_CONTROL, + PAGE_INFO_LEVELING, + PAGE_COUNT, + + PRINT_SETUP = 0, + PRINT_PAUSE_RESUME, + PRINT_STOP, + PRINT_COUNT +}; + +uint8_t active_menu = MainMenu, last_menu = MainMenu; +uint8_t selection = 0, last_selection = 0; uint8_t scrollpos = 0; -uint8_t process = Main; -uint8_t last_process = Main; -PopupID popup; -PopupID last_popup; +uint8_t process = Main, last_process = Main; +PopupID popup, last_popup; void (*funcpointer)() = nullptr; void *valuepointer = nullptr; @@ -4208,7 +4217,7 @@ void CrealityDWINClass::Confirm_Handler(PopupID popupid) { void CrealityDWINClass::Main_Menu_Control() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < 3) { + if (encoder_diffState == ENCODER_DIFF_CW && selection < PAGE_COUNT - 1) { selection++; // Select Down Main_Menu_Icons(); } @@ -4218,10 +4227,10 @@ void CrealityDWINClass::Main_Menu_Control() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) switch (selection) { - case 0: card.mount(); Draw_SD_List(); break; - case 1: Draw_Menu(Prepare); break; - case 2: Draw_Menu(Control); break; - case 3: Draw_Menu(TERN(HAS_MESH, Leveling, InfoMain)); break; + case PAGE_PRINT: card.mount(); Draw_SD_List(); break; + case PAGE_PREPARE: Draw_Menu(Prepare); break; + case PAGE_CONTROL: Draw_Menu(Control); break; + case PAGE_INFO_LEVELING: Draw_Menu(TERN(HAS_MESH, Leveling, InfoMain)); break; } DWIN_UpdateLCD(); } @@ -4449,7 +4458,7 @@ void CrealityDWINClass::File_Control() { void CrealityDWINClass::Print_Screen_Control() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW && selection < 2) { + if (encoder_diffState == ENCODER_DIFF_CW && selection < PRINT_COUNT - 1) { selection++; // Select Down Print_Screen_Icons(); } @@ -4459,11 +4468,11 @@ void CrealityDWINClass::Print_Screen_Control() { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (selection) { - case 0: + case PRINT_SETUP: Draw_Menu(Tune); Update_Status_Bar(true); break; - case 1: + case PRINT_PAUSE_RESUME: if (paused) { if (sdprint) { wait_for_user = false; @@ -4493,9 +4502,7 @@ void CrealityDWINClass::Print_Screen_Control() { else Popup_Handler(Pause); break; - case 2: - Popup_Handler(Stop); - break; + case PRINT_STOP: Popup_Handler(Stop); break; } } DWIN_UpdateLCD(); From a1e1555ea1e4a5bb0dabc027b56ffb9fc05739e3 Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Wed, 15 Sep 2021 14:47:23 -0500 Subject: [PATCH 0683/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20Monster8?= =?UTF-8?q?=20EEPROM=20issue=20(serial=20timer)=20(#22777)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f4.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index c8f8676b68..7ff0443df6 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -422,7 +422,7 @@ board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 board_build.rename = mks_monster8.bin build_flags = ${stm32_variant.build_flags} ${stm32f4_I2C1_CAN.build_flags} - -DHAL_PCD_MODULE_ENABLED + -DHAL_PCD_MODULE_ENABLED -DTIMER_SERIAL=TIM4 debug_tool = jlink upload_protocol = jlink From cca3250c3ff8e8ed4277f4918f507ab13913d3b5 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 15 Sep 2021 13:51:52 -0700 Subject: [PATCH 0684/2168] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Fix=20TFT=20fiel?= =?UTF-8?q?d=20names=20(#22776)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 0549dbf108..66cfd65995 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -183,7 +183,7 @@ void LTDC_Config() { hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1); hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1); - hltdc_F.Init.TotalHeight = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1); + hltdc_F.Init.TotalHeigh = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1); hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1); /* Configure R,G,B component values for LCD background color : all black background */ @@ -205,7 +205,7 @@ void LTDC_Config() { pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565; /* Start Address configuration : frame buffer is located at SDRAM memory */ - pLayerCfg.FBStartAddress = (uint32_t)(FRAME_BUFFER_ADDRESS); + pLayerCfg.FBStartAdress = (uint32_t)(FRAME_BUFFER_ADDRESS); /* Alpha constant (255 == totally opaque) */ pLayerCfg.Alpha = 255; From 5b5a8798f8fe202e86c008088f847a3edb51cc71 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 15 Sep 2021 19:48:29 -0500 Subject: [PATCH 0685/2168] =?UTF-8?q?=F0=9F=8E=A8=20Consolidate=20Ender-3?= =?UTF-8?q?=20V2=20DWIN=20common=20code=20(#22778)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 18 +- Marlin/src/inc/Conditionals_post.h | 3 +- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 429 ++++++++++++++++ Marlin/src/lcd/e3v2/common/dwin_api.h | 265 ++++++++++ Marlin/src/lcd/e3v2/common/dwin_color.h | 44 ++ Marlin/src/lcd/e3v2/common/dwin_font.h | 38 ++ Marlin/src/lcd/e3v2/common/dwin_set.h | 138 +++++ .../rotary_encoder.cpp => common/encoder.cpp} | 34 +- .../rotary_encoder.h => common/encoder.h} | 6 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 117 +++-- Marlin/src/lcd/e3v2/creality/dwin.h | 23 +- Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp | 398 +------------- Marlin/src/lcd/e3v2/creality/dwin_lcd.h | 323 +----------- .../src/lcd/e3v2/creality/rotary_encoder.cpp | 263 ---------- Marlin/src/lcd/e3v2/creality/rotary_encoder.h | 94 ---- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 134 ++--- Marlin/src/lcd/e3v2/enhanced/dwin.h | 74 ++- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp | 484 ++---------------- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 260 ++-------- Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 76 +-- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 206 ++------ Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp | 56 +- Marlin/src/lcd/e3v2/enhanced/lockscreen.h | 40 +- .../src/lcd/e3v2/enhanced/rotary_encoder.cpp | 263 ---------- Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h | 93 ---- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 271 +++++----- Marlin/src/lcd/e3v2/jyersui/dwin.h | 141 +---- Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp | 420 +-------------- Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 189 +------ Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp | 412 +-------------- Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h | 246 +-------- Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 5 +- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 6 +- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/lcd/marlinui.h | 5 +- Marlin/src/sd/SdFile.h | 1 - buildroot/tests/STM32F103RET6_creality | 8 +- ini/features.ini | 3 +- platformio.ini | 2 +- 39 files changed, 1512 insertions(+), 4078 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/common/dwin_api.cpp create mode 100644 Marlin/src/lcd/e3v2/common/dwin_api.h create mode 100644 Marlin/src/lcd/e3v2/common/dwin_color.h create mode 100644 Marlin/src/lcd/e3v2/common/dwin_font.h create mode 100644 Marlin/src/lcd/e3v2/common/dwin_set.h rename Marlin/src/lcd/e3v2/{jyersui/rotary_encoder.cpp => common/encoder.cpp} (91%) rename Marlin/src/lcd/e3v2/{jyersui/rotary_encoder.h => common/encoder.h} (95%) delete mode 100644 Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp delete mode 100644 Marlin/src/lcd/e3v2/creality/rotary_encoder.h delete mode 100644 Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp delete mode 100644 Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 07a9d0186f..96f6a66b0b 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -74,15 +74,15 @@ #include #endif -#if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/e3v2/creality/dwin.h" - #include "lcd/e3v2/creality/rotary_encoder.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) - #include "lcd/e3v2/enhanced/dwin.h" - #include "lcd/e3v2/enhanced/rotary_encoder.h" -#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "lcd/e3v2/jyersui/dwin.h" - #include "lcd/e3v2/jyersui/rotary_encoder.h" +#if HAS_DWIN_E3V2 + #include "lcd/e3v2/common/encoder.h" + #if ENABLED(DWIN_CREALITY_LCD) + #include "lcd/e3v2/creality/dwin.h" + #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "lcd/e3v2/enhanced/dwin.h" + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "lcd/e3v2/jyersui/dwin.h" + #endif #endif #if ENABLED(EXTENSIBLE_UI) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 5b7526b74b..5c1aa5321f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -421,8 +421,9 @@ #endif #endif -#if EITHER(DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) #define HAS_LCD_BRIGHTNESS 1 + #define MAX_LCD_BRIGHTNESS 31 #endif /** diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp new file mode 100644 index 0000000000..480b98d3fd --- /dev/null +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -0,0 +1,429 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#include "../../../inc/MarlinConfigPre.h" + +#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) + +#include "dwin_api.h" +#include "dwin_set.h" + +#include "../../../inc/MarlinConfig.h" + +#include // for memset + +uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; +uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; +uint8_t databuf[26] = { 0 }; + +// Send the data in the buffer plus the packet tail +void DWIN_Send(size_t &i) { + ++i; + LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } +} + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake() { + static int recnum = 0; + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + const millis_t serial_connect_timeout = millis() + 1000UL; + while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + + size_t i = 0; + DWIN_Byte(i, 0x00); + DWIN_Send(i); + + while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { + databuf[recnum] = LCD_SERIAL.read(); + // ignore the invalid data + if (databuf[0] != FHONE) { // prevent the program from running. + if (recnum > 0) { + recnum = 0; + ZERO(databuf); + } + continue; + } + delay(10); + recnum++; + } + + return ( recnum >= 3 + && databuf[0] == FHONE + && databuf[1] == '\0' + && databuf[2] == 'O' + && databuf[3] == 'K' ); +} + +// Set the backlight brightness +// brightness: (0x00-0x1F) +void DWIN_LCD_Brightness(const uint8_t brightness) { + size_t i = 0; + DWIN_Byte(i, 0x30); + DWIN_Byte(i, _MAX(brightness, 0x1F)); + DWIN_Send(i); +} + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir) { + size_t i = 0; + DWIN_Byte(i, 0x34); + DWIN_Byte(i, 0x5A); + DWIN_Byte(i, 0xA5); + DWIN_Byte(i, dir); + DWIN_Send(i); +} + +// Update display +void DWIN_UpdateLCD() { + size_t i = 0; + DWIN_Byte(i, 0x3D); + DWIN_Send(i); +} + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color) { + size_t i = 0; + DWIN_Byte(i, 0x01); + DWIN_Word(i, color); + DWIN_Send(i); +} + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + DWIN_Word(i, color); + DWIN_Byte(i, width); + DWIN_Byte(i, height); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x03); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x05); + DWIN_Byte(i, mode); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { + size_t i = 0; + DWIN_Byte(i, 0x09); + DWIN_Byte(i, (mode << 7) | dir); + DWIN_Word(i, dis); + DWIN_Word(i, color); + DWIN_Word(i, xStart); + DWIN_Word(i, yStart); + DWIN_Word(i, xEnd); + DWIN_Word(i, yEnd); + DWIN_Send(i); +} + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +// rlimit: To limit the drawn string length +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit/*=0xFFFF*/) { + constexpr uint8_t widthAdjust = 0; + size_t i = 0; + DWIN_Byte(i, 0x11); + // Bit 7: widthAdjust + // Bit 6: bShow + // Bit 5-4: Unused (0) + // Bit 3-0: size + DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Text(i, string, rlimit); + DWIN_Send(i); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint32_t value) { + size_t i = 0; + DWIN_Byte(i, 0x14); + // Bit 7: bshow + // Bit 6: 1 = signed; 0 = unsigned number; + // Bit 5: zeroFill + // Bit 4: zeroMode + // Bit 3-0: size + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, 0); // fNum + DWIN_Word(i, x); + DWIN_Word(i, y); + #if 0 + for (char count = 0; count < 8; count++) { + DWIN_Byte(i, value); + value >>= 8; + if (!(value & 0xFF)) break; + } + #else + // Write a big-endian 64 bit integer + const size_t p = i + 1; + for (char count = 8; count--;) { // 7..0 + ++i; + DWIN_SendBuf[p + count] = value; + value >>= 8; + } + #endif + + DWIN_Send(i); +} + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { + //uint8_t *fvalue = (uint8_t*)&value; + size_t i = 0; + DWIN_Byte(i, 0x14); + DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, iNum); + DWIN_Byte(i, fNum); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Long(i, value); + /* + DWIN_Byte(i, fvalue[3]); + DWIN_Byte(i, fvalue[2]); + DWIN_Byte(i, fvalue[1]); + DWIN_Byte(i, fvalue[0]); + */ + DWIN_Send(i); +} + +// Draw a floating point number +// value: positive unscaled float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + const int32_t val = round(value * POW(10, fNum)); + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); +} + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id) { + size_t i = 0; + DWIN_Word(i, 0x2200); + DWIN_Byte(i, id); + DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C +} + +// Draw an Icon +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(bool IBD, bool BIR, bool BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x23); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, (IBD << 7) | (BIR << 6) | (BFI << 5) | libID); + DWIN_Byte(i, picID); + DWIN_Send(i); +} + +// Draw an Icon from SRAM +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// x/y: Upper-left point +// addr: SRAM address +void DWIN_ICON_Show(bool IBD, bool BIR, bool BFI, uint16_t x, uint16_t y, uint16_t addr) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x24); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Byte(i, (IBD << 7) | (BIR << 6) | (BFI << 5) | 0x00); + DWIN_Word(i, addr); + DWIN_Send(i); +} + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { + size_t i = 0; + DWIN_Byte(i, 0x25); + DWIN_Byte(i, n); + DWIN_Byte(i, id); + DWIN_Send(i); +} + +// Animate a series of icons +// animID: Animation ID; 0x00-0x0F +// animate: true on; false off; +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Bit 7: animation on or off + // Bit 6: start from begin or end + // Bit 5-4: unused (0) + // Bit 3-0: animID + DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); + DWIN_Byte(i, libID); + DWIN_Byte(i, picIDs); + DWIN_Byte(i, picIDe); + DWIN_Byte(i, interval); + DWIN_Send(i); +} + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state) { + size_t i = 0; + DWIN_Byte(i, 0x29); + DWIN_Word(i, state); + DWIN_Send(i); +} + +/*---------------------------------------- Memory functions ----------------------------------------*/ +// The LCD has an additional 32KB SRAM and 16KB Flash +// Data can be written to the SRAM and saved to one of the jpeg page files + +// Write Data Memory +// command 0x31 +// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Data: data +// +// Flash writing returns 0xA5 0x4F 0x4B + +// Read Data Memory +// command 0x32 +// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Length: leangth of data to read; 0x01-0xF0 +// +// Response: +// Type, Address, Length, Data + +// Write Picture Memory +// Write the contents of the 32KB SRAM data memory into the designated image memory space +// Issued: 0x5A, 0xA5, PIC_ID +// Response: 0xA5 0x4F 0x4B +// +// command 0x33 +// 0x5A, 0xA5 +// PicId: Picture Memory location, 0x00-0x0F +// +// Flash writing returns 0xA5 0x4F 0x4B + +#endif // HAS_DWIN_E3V2 || IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h new file mode 100644 index 0000000000..dd9560a60f --- /dev/null +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -0,0 +1,265 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include +#include + +#include "../../../HAL/shared/Marduino.h" + +#ifndef DWIN_WIDTH + #define DWIN_WIDTH 272 +#endif +#ifndef DWIN_HEIGHT + #define DWIN_HEIGHT 480 +#endif + +#define RECEIVED_NO_DATA 0x00 +#define RECEIVED_SHAKE_HAND_ACK 0x01 + +#define FHONE 0xAA + +#define DWIN_SCROLL_UP 2 +#define DWIN_SCROLL_DOWN 3 + +// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. +// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. +extern uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2]; +extern uint8_t DWIN_BufTail[4]; +extern uint8_t databuf[26]; + +inline void DWIN_Byte(size_t &i, const uint16_t bval) { + DWIN_SendBuf[++i] = bval; +} + +inline void DWIN_Word(size_t &i, const uint16_t wval) { + DWIN_SendBuf[++i] = wval >> 8; + DWIN_SendBuf[++i] = wval & 0xFF; +} + +inline void DWIN_Long(size_t &i, const uint32_t lval) { + DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; + DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; + DWIN_SendBuf[++i] = lval & 0xFF; +} + +// Send the data in the buffer plus the packet tail +void DWIN_Send(size_t &i); + +inline void DWIN_Text(size_t &i, const char * const string, uint16_t rlimit=0xFFFF) { + if (!string) return; + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(strlen(string), rlimit)); + if (len == 0) return; + memcpy(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +inline void DWIN_Text(size_t &i, const __FlashStringHelper * string, uint16_t rlimit=0xFFFF) { + if (!string) return; + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P((PGM_P)string))); // cast to PGM_P (const char*) measure with strlen_P. + if (len == 0) return; + memcpy_P(&DWIN_SendBuf[i+1], string, len); + i += len; +} + +/*-------------------------------------- System variable function --------------------------------------*/ + +// Handshake (1: Success, 0: Fail) +bool DWIN_Handshake(); + +// DWIN startup +void DWIN_Startup(); + +// Set the backlight brightness +// brightness: (0x00-0xFF) +void DWIN_LCD_Brightness(const uint8_t brightness); + +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° +void DWIN_Frame_SetDir(uint8_t dir); + +// Update display +void DWIN_UpdateLCD(); + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color +void DWIN_Frame_Clear(const uint16_t color); + +// Draw a point +// color: point color +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point +void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point +void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point +void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, + uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); + + +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string +// rlimit: For draw less chars than string length use rlimit +void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF); + +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + // Note that this won't work on AVR, only 32-bit systems! + DWIN_Draw_String(bShow, size, color, bColor, x, y, reinterpret_cast(title)); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint32_t value); + +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value); + +// Draw a floating point number +// value: positive unscaled float value +void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID +void DWIN_JPG_ShowAndCache(const uint8_t id); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Draw an Icon +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(bool IBD, bool BIR, bool BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + +// Draw an Icon from SRAM +// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black +// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration +// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// x/y: Upper-left point +// addr: SRAM address +void DWIN_ICON_Show(bool IBD, bool BIR, bool BFI, uint16_t x, uint16_t y, uint16_t addr); + +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID +void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); + +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID +inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/e3v2/common/dwin_color.h new file mode 100644 index 0000000000..d327f21a93 --- /dev/null +++ b/Marlin/src/lcd/e3v2/common/dwin_color.h @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +// Extended and default UI Colors +#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 +#define GetRColor(color) ((color >> 11) & 0x1F) +#define GetGColor(color) ((color >> 5) & 0x3F) +#define GetBColor(color) ((color >> 0) & 0x1F) + +#define Color_White 0xFFFF +#define Color_Yellow RGB(0x1F,0x3F,0x00) +#define Color_Red RGB(0x1F,0x00,0x00) +#define Color_Error_Red 0xB000 // Error! +#define Color_Bg_Red 0xF00F // Red background color +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents +#define Popup_Text_Color 0xD6BA // Popup font background color +#define Line_Color 0x3A6A // Split line color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color diff --git a/Marlin/src/lcd/e3v2/common/dwin_font.h b/Marlin/src/lcd/e3v2/common/dwin_font.h new file mode 100644 index 0000000000..5a4b1a61cf --- /dev/null +++ b/Marlin/src/lcd/e3v2/common/dwin_font.h @@ -0,0 +1,38 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: + * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 + * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 + */ +#define font6x12 0x00 +#define font8x16 0x01 +#define font10x20 0x02 +#define font12x24 0x03 +#define font14x28 0x04 +#define font16x32 0x05 +#define font20x40 0x06 +#define font24x48 0x07 +#define font28x56 0x08 +#define font32x64 0x09 diff --git a/Marlin/src/lcd/e3v2/common/dwin_set.h b/Marlin/src/lcd/e3v2/common/dwin_set.h new file mode 100644 index 0000000000..4fedd7a584 --- /dev/null +++ b/Marlin/src/lcd/e3v2/common/dwin_set.h @@ -0,0 +1,138 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +// Picture ID +#define Language_English 1 +#define Language_Chinese 2 + +#define ICON 7 // Icon set file 7.ICO + +#define ICON_LOGO 0 +#define ICON_Print_0 1 +#define ICON_Print_1 2 +#define ICON_Prepare_0 3 +#define ICON_Prepare_1 4 +#define ICON_Control_0 5 +#define ICON_Control_1 6 +#define ICON_Leveling_0 7 +#define ICON_Leveling_1 8 +#define ICON_HotendTemp 9 +#define ICON_BedTemp 10 +#define ICON_Speed 11 +#define ICON_Zoffset 12 +#define ICON_Back 13 +#define ICON_File 14 +#define ICON_PrintTime 15 +#define ICON_RemainTime 16 +#define ICON_Setup_0 17 +#define ICON_Setup_1 18 +#define ICON_Pause_0 19 +#define ICON_Pause_1 20 +#define ICON_Continue_0 21 +#define ICON_Continue_1 22 +#define ICON_Stop_0 23 +#define ICON_Stop_1 24 +#define ICON_Bar 25 +#define ICON_More 26 + +#define ICON_Axis 27 +#define ICON_CloseMotor 28 +#define ICON_Homing 29 +#define ICON_SetHome 30 +#define ICON_PLAPreheat 31 +#define ICON_ABSPreheat 32 +#define ICON_Cool 33 +#define ICON_Language 34 + +#define ICON_MoveX 35 +#define ICON_MoveY 36 +#define ICON_MoveZ 37 +#define ICON_Extruder 38 + +#define ICON_Temperature 40 +#define ICON_Motion 41 +#define ICON_WriteEEPROM 42 +#define ICON_ReadEEPROM 43 +#define ICON_ResumeEEPROM 44 +#define ICON_Info 45 + +#define ICON_SetEndTemp 46 +#define ICON_SetBedTemp 47 +#define ICON_FanSpeed 48 +#define ICON_SetPLAPreheat 49 +#define ICON_SetABSPreheat 50 + +#define ICON_MaxSpeed 51 +#define ICON_MaxAccelerated 52 +#define ICON_MaxJerk 53 +#define ICON_Step 54 +#define ICON_PrintSize 55 +#define ICON_Version 56 +#define ICON_Contact 57 +#define ICON_StockConfiguration 58 +#define ICON_MaxSpeedX 59 +#define ICON_MaxSpeedY 60 +#define ICON_MaxSpeedZ 61 +#define ICON_MaxSpeedE 62 +#define ICON_MaxAccX 63 +#define ICON_MaxAccY 64 +#define ICON_MaxAccZ 65 +#define ICON_MaxAccE 66 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 +#define ICON_StepX 71 +#define ICON_StepY 72 +#define ICON_StepZ 73 +#define ICON_StepE 74 +#define ICON_Setspeed 75 +#define ICON_SetZOffset 76 +#define ICON_Rectangle 77 +#define ICON_BLTouch 78 +#define ICON_TempTooLow 79 +#define ICON_AutoLeveling 80 +#define ICON_TempTooHigh 81 +#define ICON_NoTips_C 82 +#define ICON_NoTips_E 83 +#define ICON_Continue_C 84 +#define ICON_Continue_E 85 +#define ICON_Cancel_C 86 +#define ICON_Cancel_E 87 +#define ICON_Confirm_C 88 +#define ICON_Confirm_E 89 +#define ICON_Info_0 90 +#define ICON_Info_1 91 + +#define ICON_Folder ICON_More +#define ICON_AdvSet ICON_Language +#define ICON_HomeOffset ICON_AdvSet +#define ICON_HomeOffsetX ICON_StepX +#define ICON_HomeOffsetY ICON_StepY +#define ICON_HomeOffsetZ ICON_StepZ +#define ICON_ProbeOffset ICON_AdvSet +#define ICON_ProbeOffsetX ICON_StepX +#define ICON_ProbeOffsetY ICON_StepY +#define ICON_ProbeOffsetZ ICON_StepZ +#define ICON_PIDNozzle ICON_SetEndTemp +#define ICON_PIDbed ICON_SetBedTemp diff --git a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp similarity index 91% rename from Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp rename to Marlin/src/lcd/e3v2/common/encoder.cpp index 23494aa693..edfaf60aae 100644 --- a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -21,15 +21,15 @@ */ /***************************************************************************** - * @file lcd/e3v2/jyersui/rotary_encoder.cpp + * @file lcd/e3v2/common/encoder.cpp * @brief Rotary encoder functions *****************************************************************************/ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) +#if HAS_DWIN_E3V2 -#include "rotary_encoder.h" +#include "encoder.h" #include "../../buttons.h" #include "../../../MarlinCore.h" @@ -38,7 +38,6 @@ #if HAS_BUZZER #include "../../../libs/buzzer.h" - #include "dwin.h" #endif #include @@ -49,10 +48,10 @@ ENCODER_Rate EncoderRate; -// Buzzer +// TODO: Replace with ui.quick_feedback void Encoder_tick() { #if PIN_EXISTS(BEEPER) - if (CrealityDWIN.eeprom_settings.beeperenable) { + if (ui.buzzer_enabled) { WRITE(BEEPER_PIN, HIGH); delay(10); WRITE(BEEPER_PIN, LOW); @@ -72,18 +71,18 @@ void Encoder_Configuration() { SET_INPUT_PULLUP(BTN_ENC); #endif #if PIN_EXISTS(BEEPER) - SET_OUTPUT(BEEPER_PIN); + SET_OUTPUT(BEEPER_PIN); // TODO: Use buzzer.h which already inits this #endif } // Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze() { +EncoderState Encoder_ReceiveAnalyze() { const millis_t now = millis(); static uint8_t lastEncoderBits; uint8_t newbutton = 0; static signed char temp_diff = 0; - ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; + EncoderState temp_diffState = ENCODER_DIFF_NO; if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; if (BUTTON_PRESSED(ENC)) { @@ -94,8 +93,10 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { #if PIN_EXISTS(LCD_LED) //LED_Action(); #endif - if (ui.backlight) return ENCODER_DIFF_ENTER; - ui.refresh_brightness(); + if (!ui.backlight) ui.refresh_brightness(); + const bool was_waiting = wait_for_user; + wait_for_user = false; + return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; } else return ENCODER_DIFF_NO; } @@ -122,13 +123,8 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { } if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { - #if ENABLED(REVERSE_ENCODER_DIRECTION) - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CCW; - else temp_diffState = ENCODER_DIFF_CW; - #else - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; - else temp_diffState = ENCODER_DIFF_CCW; - #endif + if (temp_diff > 0) temp_diffState = TERN(REVERSE_ENCODER_DIRECTION, ENCODER_DIFF_CCW, ENCODER_DIFF_CW); + else temp_diffState = TERN(REVERSE_ENCODER_DIRECTION, ENCODER_DIFF_CW, ENCODER_DIFF_CCW); #if ENABLED(ENCODER_RATE_MULTIPLIER) @@ -260,4 +256,4 @@ ENCODER_DiffState Encoder_ReceiveAnalyze() { #endif // LCD_LED -#endif // DWIN_CREALITY_LCD_JYERSUI +#endif // HAS_DWIN_E3V2 diff --git a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h b/Marlin/src/lcd/e3v2/common/encoder.h similarity index 95% rename from Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h rename to Marlin/src/lcd/e3v2/common/encoder.h index 0febe6bd35..e5d9645ed4 100644 --- a/Marlin/src/lcd/e3v2/jyersui/rotary_encoder.h +++ b/Marlin/src/lcd/e3v2/common/encoder.h @@ -22,7 +22,7 @@ #pragma once /***************************************************************************** - * @file lcd/e3v2/jyersui/rotary_encoder.h + * @file lcd/e3v2/common/encoder.h * @brief Rotary encoder functions ****************************************************************************/ @@ -43,13 +43,13 @@ typedef enum { ENCODER_DIFF_CW = 1, // clockwise rotation ENCODER_DIFF_CCW = 2, // counterclockwise rotation ENCODER_DIFF_ENTER = 3 // click -} ENCODER_DiffState; +} EncoderState; // Encoder initialization void Encoder_Configuration(); // Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze(); +EncoderState Encoder_ReceiveAnalyze(); /*********************** Encoder LED ***********************/ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 5593147b7a..05aa9f0ec3 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -138,7 +138,7 @@ constexpr uint16_t MROWS = TROWS - 1, // Last Row Index // Value Init HMI_value_t HMI_ValueStruct; -HMI_Flag_t HMI_flag{0}; +HMI_flag_t HMI_flag{0}; millis_t dwin_heat_time = 0; @@ -470,7 +470,7 @@ void Draw_Back_First(const bool is_sel=true) { } template -inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) { +inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { if (encoder_diffState == ENCODER_DIFF_CW) valref += EncoderRate.encoderMoveValue; else if (encoder_diffState == ENCODER_DIFF_CCW) @@ -593,7 +593,7 @@ void DWIN_Draw_Label(const uint8_t row, const __FlashStringHelper *title) { DWIN_Draw_Label(row, (char*)title); } -void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { DWIN_Draw_String(true, size, Color_White, bColor, x - 8, y, value < 0 ? F("-") : F(" ")); DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value < 0 ? -value : value); } @@ -607,7 +607,7 @@ void Draw_Edit_Integer4(const uint8_t row, const uint16_t value, const bool acti } void Draw_Edit_Float3(const uint8_t row, const uint16_t value, const bool active=false) { - DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, UNITFDIGITS, 220 - UNITFDIGITS * 8, EBASE(row), value); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, active ? Select_Color : Color_Bg_Black, 3, UNITFDIGITS, 220 - UNITFDIGITS * 8, EBASE(row), (int32_t)value); } void Draw_Edit_Signed_Float2(const uint8_t row, const float value, const bool active=false) { @@ -1292,11 +1292,11 @@ void Goto_MainMenu() { TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); } -inline ENCODER_DiffState get_encoder_state() { +inline EncoderState get_encoder_state() { static millis_t Encoder_ms = 0; const millis_t ms = millis(); if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); + const EncoderState state = Encoder_ReceiveAnalyze(); if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; return state; } @@ -1317,7 +1317,7 @@ void HMI_Move_Done(const AxisEnum axis) { } void HMI_Move_X() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scaled)) { Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled); @@ -1331,7 +1331,7 @@ void HMI_Move_X() { } void HMI_Move_Y() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scaled)) { Draw_Edit_Float3(2, HMI_ValueStruct.Move_Y_scaled); @@ -1345,7 +1345,7 @@ void HMI_Move_Y() { } void HMI_Move_Z() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scaled)) { Draw_Edit_Float3(3, HMI_ValueStruct.Move_Z_scaled); @@ -1362,7 +1362,7 @@ void HMI_Move_Z() { void HMI_Move_E() { static float last_E_scaled = 0; - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scaled)) { last_E_scaled = HMI_ValueStruct.Move_E_scaled; @@ -1383,7 +1383,7 @@ void HMI_Move_Z() { bool printer_busy() { return planner.movesplanned() || printingIsActive(); } void HMI_Zoffset() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; uint8_t zoff_line; switch (HMI_ValueStruct.show_mode) { @@ -1416,7 +1416,7 @@ void HMI_Move_Z() { #if HAS_HOTEND void HMI_ETemp() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; uint8_t temp_line; switch (HMI_ValueStruct.show_mode) { @@ -1458,7 +1458,7 @@ void HMI_Move_Z() { #if HAS_HEATED_BED void HMI_BedTemp() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; uint8_t bed_line; switch (HMI_ValueStruct.show_mode) { @@ -1500,7 +1500,7 @@ void HMI_Move_Z() { #if HAS_PREHEAT && HAS_FAN void HMI_FanSpeed() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; uint8_t fan_line; switch (HMI_ValueStruct.show_mode) { @@ -1541,7 +1541,7 @@ void HMI_Move_Z() { #endif // HAS_PREHEAT && HAS_FAN void HMI_PrintSpeed() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { checkkey = Tune; @@ -1559,7 +1559,7 @@ void HMI_PrintSpeed() { #define LAST_AXIS TERN(HAS_HOTEND, E_AXIS, Z_AXIS) void HMI_MaxFeedspeedXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { checkkey = MaxSpeed; @@ -1578,7 +1578,7 @@ void HMI_MaxFeedspeedXYZE() { } void HMI_MaxAccelerationXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { checkkey = MaxAcceleration; @@ -1599,7 +1599,7 @@ void HMI_MaxAccelerationXYZE() { #if HAS_CLASSIC_JERK void HMI_MaxJerkXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk_scaled)) { checkkey = MaxJerk; @@ -1620,7 +1620,7 @@ void HMI_MaxAccelerationXYZE() { #endif // HAS_CLASSIC_JERK void HMI_StepXYZE() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step_scaled)) { checkkey = Step; @@ -1816,8 +1816,6 @@ void HMI_SDCardInit() { card.cdroot(); } void MarlinUI::refresh() { /* Nothing to see here */ } -#define ICON_Folder ICON_More - #if ENABLED(SCROLL_LONG_FILENAMES) char shift_name[LONG_FILENAME_LENGTH + 1]; @@ -2077,7 +2075,7 @@ void Draw_Print_File_Menu() { // Main Process void HMI_MainMenu() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) { @@ -2137,7 +2135,7 @@ void HMI_MainMenu() { // Select (and Print) File void HMI_SelectFile() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); const uint16_t hasUpDir = !card.flag.workDirIsRoot; @@ -2257,7 +2255,7 @@ void HMI_SelectFile() { // Printing void HMI_Printing() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (HMI_flag.done_confirm_flag) { @@ -2335,7 +2333,7 @@ void HMI_Printing() { // Pause and Stop window void HMI_PauseOrStop() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) @@ -2417,7 +2415,7 @@ void Item_Adv_HomeOffsets(const uint8_t row) { Item_AreaCopy(1, 76, 102, 87, row); // "Set Home Offsets" #endif } - Draw_Menu_Line(row, ICON_HomeOff); + Draw_Menu_Line(row, ICON_HomeOffset); Draw_More_Icon(row); } @@ -2434,7 +2432,7 @@ void Item_Adv_HomeOffsets(const uint8_t row) { say_probe_offs_en(row); #endif } - Draw_Menu_Line(row, ICON_ProbeOff); + Draw_Menu_Line(row, ICON_ProbeOffset); Draw_More_Icon(row); } @@ -2529,12 +2527,12 @@ void Item_HomeOffs_X(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffX, GET_TEXT_F(MSG_HOME_OFFSET_X)); + Draw_Menu_LineF(row, ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X)); #else say_home_offs_en(row); say_x_en(75, row); // "Home Offset X" #endif } - Draw_Menu_Line(row, ICON_HomeOff); + Draw_Menu_Line(row, ICON_HomeOffset); Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffX_scaled); } @@ -2544,12 +2542,12 @@ void Item_HomeOffs_Y(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); + Draw_Menu_LineF(row, ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); #else say_home_offs_en(row); say_y_en(75, row); // "Home Offset X" #endif } - Draw_Menu_Line(row, ICON_HomeOff); + Draw_Menu_Line(row, ICON_HomeOffset); Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffY_scaled); } @@ -2559,12 +2557,12 @@ void Item_HomeOffs_Z(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); + Draw_Menu_LineF(row, ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); #else say_home_offs_en(row); say_z_en(75, row); // "Home Offset Z" #endif } - Draw_Menu_Line(row, ICON_HomeOff); + Draw_Menu_Line(row, ICON_HomeOffset); Draw_Edit_Signed_Float3(row, HMI_ValueStruct.Home_OffZ_scaled); } @@ -2602,8 +2600,8 @@ void Draw_HomeOff_Menu() { DWIN_Frame_TitleCopy(124, 431, 91, 12); // "Probe Offsets" #endif #ifdef USE_STRING_TITLES - Draw_Menu_LineF(1, ICON_ProbeOffX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset - Draw_Menu_LineF(2, ICON_ProbeOffY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset + Draw_Menu_LineF(1, ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset + Draw_Menu_LineF(2, ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset #else say_probe_offs_en(1); say_x_en(75, 1); // "Probe Offset X" say_probe_offs_en(2); say_y_en(75, 2); // "Probe Offset Y" @@ -2615,6 +2613,7 @@ void Draw_HomeOff_Menu() { if (select_item.now != CASE_BACK) Draw_Menu_Cursor(select_item.now); } + #endif #include "../../../libs/buzzer.h" @@ -2633,7 +2632,7 @@ void HMI_AudioFeedback(const bool success=true) { // Prepare void HMI_Prepare() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -2847,7 +2846,7 @@ void Draw_Temperature_Menu() { // Control void HMI_Control() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -2932,28 +2931,25 @@ void HMI_Control() { DWIN_UpdateLCD(); } - #if HAS_ONESTEP_LEVELING - // Leveling void HMI_Leveling() { Popup_Window_Leveling(); DWIN_UpdateLCD(); queue.inject_P(PSTR("G28O\nG29")); } - #endif // Axis Move void HMI_AxisMove() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; #if ENABLED(PREVENT_COLD_EXTRUSION) // popup window resume - if (HMI_flag.ETempTooLow_flag) { + if (HMI_flag.cold_flag) { if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.ETempTooLow_flag = false; + HMI_flag.cold_flag = false; HMI_ValueStruct.Move_E_scaled = current_position.e * MINUNITMULT; Draw_Move_Menu(); Draw_Edit_Float3(1, HMI_ValueStruct.Move_X_scaled); @@ -3003,7 +2999,7 @@ void HMI_AxisMove() { case 4: // Extruder #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(0)) { - HMI_flag.ETempTooLow_flag = true; + HMI_flag.cold_flag = true; Popup_Window_ETempTooLow(); DWIN_UpdateLCD(); return; @@ -3022,7 +3018,7 @@ void HMI_AxisMove() { // TemperatureID void HMI_Temperature() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3449,7 +3445,7 @@ void Draw_Steps_Menu() { // Motion void HMI_Motion() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3497,7 +3493,7 @@ void HMI_Motion() { // Advanced Settings void HMI_AdvSet() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3594,7 +3590,7 @@ void HMI_AdvSet() { // Home Offset void HMI_HomeOff() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3633,7 +3629,7 @@ void HMI_AdvSet() { } void HMI_HomeOffN(const AxisEnum axis, float &posScaled, const_float_t lo, const_float_t hi) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, posScaled)) { @@ -3654,9 +3650,10 @@ void HMI_AdvSet() { #endif // HAS_HOME_OFFSET #if HAS_ONESTEP_LEVELING + // Probe Offset void HMI_ProbeOff() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3689,7 +3686,7 @@ void HMI_AdvSet() { } void HMI_ProbeOffN(float &posScaled, float &offset_ref) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (Apply_Encoder(encoder_diffState, posScaled)) { @@ -3710,7 +3707,7 @@ void HMI_AdvSet() { // Info void HMI_Info() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { #if HAS_ONESTEP_LEVELING @@ -3727,7 +3724,7 @@ void HMI_Info() { // Tune void HMI_Tune() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3813,7 +3810,7 @@ void HMI_Tune() { // PLA Preheat void HMI_PLAPreheatSetting() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3869,7 +3866,7 @@ void HMI_Tune() { // ABS Preheat void HMI_ABSPreheatSetting() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3927,7 +3924,7 @@ void HMI_Tune() { // Max Speed void HMI_MaxSpeed() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3956,7 +3953,7 @@ void HMI_MaxSpeed() { // Max Acceleration void HMI_MaxAcceleration() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -3986,7 +3983,7 @@ void HMI_MaxAcceleration() { #if HAS_CLASSIC_JERK // Max Jerk void HMI_MaxJerk() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -4016,7 +4013,7 @@ void HMI_MaxAcceleration() { // Step void HMI_Step() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu @@ -4172,7 +4169,7 @@ void EachMomentUpdate() { DWIN_UpdateLCD(); while (recovery_flag) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_ENTER) { recovery_flag = false; diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index 69fe0d6bd6..d4afe46a7d 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -26,7 +26,7 @@ */ #include "dwin_lcd.h" -#include "rotary_encoder.h" +#include "../common/encoder.h" #include "../../../libs/BL24CXX.h" #include "../../../inc/MarlinConfigPre.h" @@ -144,24 +144,21 @@ typedef struct { typedef struct { uint8_t language; - bool pause_flag:1; - bool pause_action:1; - bool print_finish:1; + bool pause_flag:1; // printing is paused + bool pause_action:1; // flag a pause action + bool print_finish:1; // print was finished + bool select_flag:1; // Popup button selected + bool home_flag:1; // homing in course + bool heat_flag:1; // 0: heating done 1: during heating bool done_confirm_flag:1; - bool select_flag:1; - bool home_flag:1; - bool heat_flag:1; // 0: heating done 1: during heating #if ENABLED(PREVENT_COLD_EXTRUSION) - bool ETempTooLow_flag:1; - #endif - #if HAS_LEVELING - bool leveling_offset_flag:1; + bool cold_flag:1; #endif AxisEnum feedspeed_axis, acc_axis, jerk_axis, step_axis; -} HMI_Flag_t; +} HMI_flag_t; extern HMI_value_t HMI_ValueStruct; -extern HMI_Flag_t HMI_flag; +extern HMI_flag_t HMI_flag; #if HAS_HOTEND || HAS_HEATED_BED // Popup message window diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp index 1ce95bd729..fee22932d2 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp @@ -35,94 +35,13 @@ #include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" -#include // for memset //#define DEBUG_OUT 1 #include "../../../core/debug_out.h" -// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. -// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. -uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; -uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; -uint8_t databuf[26] = { 0 }; -uint8_t receivedType; - -int recnum = 0; - -inline void DWIN_Byte(size_t &i, const uint16_t bval) { - DWIN_SendBuf[++i] = bval; -} - -inline void DWIN_Word(size_t &i, const uint16_t wval) { - DWIN_SendBuf[++i] = wval >> 8; - DWIN_SendBuf[++i] = wval & 0xFF; -} - -inline void DWIN_Long(size_t &i, const uint32_t lval) { - DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; - DWIN_SendBuf[++i] = lval & 0xFF; -} - -inline void DWIN_String(size_t &i, char * const string) { - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { - if (!string) return; - const size_t len = strlen_P((PGM_P)string); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. - if (len == 0) return; - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -// Send the data in the buffer and the packet end -inline void DWIN_Send(size_t &i) { - ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } -} - /*-------------------------------------- System variable function --------------------------------------*/ -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void) { - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 115200 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - const millis_t serial_connect_timeout = millis() + 1000UL; - while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - - size_t i = 0; - DWIN_Byte(i, 0x00); - DWIN_Send(i); - - while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { - databuf[recnum] = LCD_SERIAL.read(); - // ignore the invalid data - if (databuf[0] != FHONE) { // prevent the program from running. - if (recnum > 0) { - recnum = 0; - ZERO(databuf); - } - continue; - } - delay(10); - recnum++; - } - - return ( recnum >= 3 - && databuf[0] == FHONE - && databuf[1] == '\0' - && databuf[2] == 'O' - && databuf[3] == 'K' ); -} - -void DWIN_Startup(void) { +void DWIN_Startup() { DEBUG_ECHOPGM("\r\nDWIN handshake "); delay(750); // Delay here or init later in the boot process if (DWIN_Handshake()) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); @@ -133,255 +52,14 @@ void DWIN_Startup(void) { DWIN_UpdateLCD(); } -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance) { - size_t i = 0; - DWIN_Byte(i, 0x30); - DWIN_Byte(i, _MAX(luminance, 0x1F)); - DWIN_Send(i); -} - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir) { - size_t i = 0; - DWIN_Byte(i, 0x34); - DWIN_Byte(i, 0x5A); - DWIN_Byte(i, 0xA5); - DWIN_Byte(i, dir); - DWIN_Send(i); -} - -// Update display -void DWIN_UpdateLCD(void) { - size_t i = 0; - DWIN_Byte(i, 0x3D); - DWIN_Send(i); -} - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color) { - size_t i = 0; - DWIN_Byte(i, 0x01); - DWIN_Word(i, color); - DWIN_Send(i); -} - -// Draw a point -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x02); - DWIN_Word(i, color); - DWIN_Byte(i, width); - DWIN_Byte(i, height); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x03); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x05); - DWIN_Byte(i, mode); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x09); - DWIN_Byte(i, (mode << 7) | dir); - DWIN_Word(i, dis); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { - uint8_t widthAdjust = 0; - size_t i = 0; - DWIN_Byte(i, 0x11); - // Bit 7: widthAdjust - // Bit 6: bShow - // Bit 5-4: Unused (0) - // Bit 3-0: size - DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_String(i, string); - DWIN_Send(i); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - // Bit 7: bshow - // Bit 6: 1 = signed; 0 = unsigned number; - // Bit 5: zeroFill - // Bit 4: zeroMode - // Bit 3-0: size - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, 0); // fNum - DWIN_Word(i, x); - DWIN_Word(i, y); - #if 0 - for (char count = 0; count < 8; count++) { - DWIN_Byte(i, value); - value >>= 8; - if (!(value & 0xFF)) break; - } - #else - // Write a big-endian 64 bit integer - const size_t p = i + 1; - for (char count = 8; count--;) { // 7..0 - ++i; - DWIN_SendBuf[p + count] = value; - value >>= 8; - } - #endif - - DWIN_Send(i); -} - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - //uint8_t *fvalue = (uint8_t*)&value; - size_t i = 0; - DWIN_Byte(i, 0x14); - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, fNum); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Long(i, value); - /* - DWIN_Byte(i, fvalue[3]); - DWIN_Byte(i, fvalue[2]); - DWIN_Byte(i, fvalue[1]); - DWIN_Byte(i, fvalue[0]); - */ - DWIN_Send(i); -} - /*---------------------------------------- Picture related functions ----------------------------------------*/ -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id) { - size_t i = 0; - DWIN_Word(i, 0x2200); - DWIN_Byte(i, id); - DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C -} - // Draw an Icon // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x23); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Byte(i, 0x80 | libID); - //DWIN_Byte(i, libID); - DWIN_Byte(i, picID); - DWIN_Send(i); -} - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { - size_t i = 0; - DWIN_Byte(i, 0x25); - DWIN_Byte(i, n); - DWIN_Byte(i, id); - DWIN_Send(i); + DWIN_ICON_Show(true, false, false, libID, picID, x, y); } // Copy area from virtual display area to current screen @@ -389,8 +67,7 @@ void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { size_t i = 0; DWIN_Byte(i, 0x27); DWIN_Byte(i, 0x80 | cacheID); @@ -403,73 +80,4 @@ void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, DWIN_Send(i); } -// Animate a series of icons -// animID: Animation ID; 0x00-0x0F -// animate: true on; false off; -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x28); - DWIN_Word(i, x); - DWIN_Word(i, y); - // Bit 7: animation on or off - // Bit 6: start from begin or end - // Bit 5-4: unused (0) - // Bit 3-0: animID - DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); - DWIN_Byte(i, libID); - DWIN_Byte(i, picIDs); - DWIN_Byte(i, picIDe); - DWIN_Byte(i, interval); - DWIN_Send(i); -} - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state) { - size_t i = 0; - DWIN_Byte(i, 0x29); - DWIN_Word(i, state); - DWIN_Send(i); -} - -/*---------------------------------------- Memory functions ----------------------------------------*/ -// The LCD has an additional 32KB SRAM and 16KB Flash - -// Data can be written to the sram and save to one of the jpeg page files - -// Write Data Memory -// command 0x31 -// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Data: data -// -// Flash writing returns 0xA5 0x4F 0x4B - -// Read Data Memory -// command 0x32 -// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Length: leangth of data to read; 0x01-0xF0 -// -// Response: -// Type, Address, Length, Data - -// Write Picture Memory -// Write the contents of the 32KB SRAM data memory into the designated image memory space -// Issued: 0x5A, 0xA5, PIC_ID -// Response: 0xA5 0x4F 0x4B -// -// command 0x33 -// 0x5A, 0xA5 -// PicId: Picture Memory location, 0x00-0x0F -// -// Flash writing returns 0xA5 0x4F 0x4B - #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h index dab3806de6..115781f094 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -29,335 +29,22 @@ * @brief 迪文屏控制操作函数 ********************************************************************************/ -#include - -#define RECEIVED_NO_DATA 0x00 -#define RECEIVED_SHAKE_HAND_ACK 0x01 - -#define FHONE 0xAA - -#define DWIN_SCROLL_UP 2 -#define DWIN_SCROLL_DOWN 3 - #define DWIN_WIDTH 272 #define DWIN_HEIGHT 480 -// Picture ID -#define Language_English 1 -#define Language_Chinese 2 - -// ICON ID -#define ICON 7 // Icon set file 7.ICO - -#define ICON_LOGO 0 -#define ICON_Print_0 1 -#define ICON_Print_1 2 -#define ICON_Prepare_0 3 -#define ICON_Prepare_1 4 -#define ICON_Control_0 5 -#define ICON_Control_1 6 -#define ICON_Leveling_0 7 -#define ICON_Leveling_1 8 -#define ICON_HotendTemp 9 -#define ICON_BedTemp 10 -#define ICON_Speed 11 -#define ICON_Zoffset 12 -#define ICON_Back 13 -#define ICON_File 14 -#define ICON_PrintTime 15 -#define ICON_RemainTime 16 -#define ICON_Setup_0 17 -#define ICON_Setup_1 18 -#define ICON_Pause_0 19 -#define ICON_Pause_1 20 -#define ICON_Continue_0 21 -#define ICON_Continue_1 22 -#define ICON_Stop_0 23 -#define ICON_Stop_1 24 -#define ICON_Bar 25 -#define ICON_More 26 - -#define ICON_Axis 27 -#define ICON_CloseMotor 28 -#define ICON_Homing 29 -#define ICON_SetHome 30 -#define ICON_PLAPreheat 31 -#define ICON_ABSPreheat 32 -#define ICON_Cool 33 -#define ICON_Language 34 - -#define ICON_MoveX 35 -#define ICON_MoveY 36 -#define ICON_MoveZ 37 -#define ICON_Extruder 38 - -#define ICON_Temperature 40 -#define ICON_Motion 41 -#define ICON_WriteEEPROM 42 -#define ICON_ReadEEPROM 43 -#define ICON_ResumeEEPROM 44 -#define ICON_Info 45 - -#define ICON_SetEndTemp 46 -#define ICON_SetBedTemp 47 -#define ICON_FanSpeed 48 -#define ICON_SetPLAPreheat 49 -#define ICON_SetABSPreheat 50 - -#define ICON_MaxSpeed 51 -#define ICON_MaxAccelerated 52 -#define ICON_MaxJerk 53 -#define ICON_Step 54 -#define ICON_PrintSize 55 -#define ICON_Version 56 -#define ICON_Contact 57 -#define ICON_StockConfiguraton 58 -#define ICON_MaxSpeedX 59 -#define ICON_MaxSpeedY 60 -#define ICON_MaxSpeedZ 61 -#define ICON_MaxSpeedE 62 -#define ICON_MaxAccX 63 -#define ICON_MaxAccY 64 -#define ICON_MaxAccZ 65 -#define ICON_MaxAccE 66 -#define ICON_MaxSpeedJerkX 67 -#define ICON_MaxSpeedJerkY 68 -#define ICON_MaxSpeedJerkZ 69 -#define ICON_MaxSpeedJerkE 70 -#define ICON_StepX 71 -#define ICON_StepY 72 -#define ICON_StepZ 73 -#define ICON_StepE 74 -#define ICON_Setspeed 75 -#define ICON_SetZOffset 76 -#define ICON_Rectangle 77 -#define ICON_BLTouch 78 -#define ICON_TempTooLow 79 -#define ICON_AutoLeveling 80 -#define ICON_TempTooHigh 81 -#define ICON_NoTips_C 82 -#define ICON_NoTips_E 83 -#define ICON_Continue_C 84 -#define ICON_Continue_E 85 -#define ICON_Cancel_C 86 -#define ICON_Cancel_E 87 -#define ICON_Confirm_C 88 -#define ICON_Confirm_E 89 -#define ICON_Info_0 90 -#define ICON_Info_1 91 - -#define ICON_AdvSet ICON_Language -#define ICON_HomeOff ICON_AdvSet -#define ICON_HomeOffX ICON_StepX -#define ICON_HomeOffY ICON_StepY -#define ICON_HomeOffZ ICON_StepZ -#define ICON_ProbeOff ICON_AdvSet -#define ICON_ProbeOffX ICON_StepX -#define ICON_ProbeOffY ICON_StepY -#define ICON_PIDNozzle ICON_SetEndTemp -#define ICON_PIDbed ICON_SetBedTemp - -/** - * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: - * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 - * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 - */ -#define font6x12 0x00 -#define font8x16 0x01 -#define font10x20 0x02 -#define font12x24 0x03 -#define font14x28 0x04 -#define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 +#include "../common/dwin_api.h" +#include "../common/dwin_set.h" +#include "../common/dwin_font.h" +#include "../common/dwin_color.h" #define DWIN_FONT_MENU font10x20 #define DWIN_FONT_STAT font10x20 #define DWIN_FONT_HEAD font10x20 #define DWIN_FONT_ALERT font14x28 -// Color -#define Color_White 0xFFFF -#define Color_Yellow 0xFF0F -#define Color_Error_Red 0xB000 // Error! -#define Color_Bg_Red 0xF00F // Red background color -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color - -/*-------------------------------------- System variable function --------------------------------------*/ - -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void); - -// Common DWIN startup -void DWIN_Startup(void); - -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance); - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir); - -// Update display -void DWIN_UpdateLCD(void); - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color); - -// Draw a point -// color: point color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a Horizontal line -// color: Line segment color -// xStart/yStart: Start point -// xLength: Line Length -inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); -} - -// Draw a Vertical line -// color: Line segment color -// xStart/yStart: Start point -// yLength: Line Length -inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a box -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xSize/ySize: box size -inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { - DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); - -class __FlashStringHelper; - -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(bShow, size, color, bColor, x, y, (char *)title); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - -/*---------------------------------------- Picture related functions ----------------------------------------*/ - -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id); - -// Draw an Icon -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); - -// Unzip the JPG picture to virtual display area #1 -// id: Picture ID -inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } - // Copy area from virtual display area to current screen // cacheID: virtual area number // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - -// Animate a series of icons -// animID: Animation ID up to 16 -// animate: animation on or off -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, - uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state); +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp deleted file mode 100644 index 6bb8d79be8..0000000000 --- a/Marlin/src/lcd/e3v2/creality/rotary_encoder.cpp +++ /dev/null @@ -1,263 +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 . - * - */ - -/***************************************************************************** - * @file lcd/e3v2/creality/rotary_encoder.cpp - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - *****************************************************************************/ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD) - -#include "rotary_encoder.h" -#include "../../buttons.h" - -#include "../../../MarlinCore.h" -#include "../../../HAL/shared/Delay.h" - -#if HAS_BUZZER - #include "../../../libs/buzzer.h" -#endif - -#include - -#ifndef ENCODER_PULSES_PER_STEP - #define ENCODER_PULSES_PER_STEP 4 -#endif - -ENCODER_Rate EncoderRate; - -// Buzzer -void Encoder_tick() { - #if PIN_EXISTS(BEEPER) - WRITE(BEEPER_PIN, HIGH); - delay(10); - WRITE(BEEPER_PIN, LOW); - #endif -} - -// Encoder initialization -void Encoder_Configuration() { - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - #if PIN_EXISTS(BEEPER) - SET_OUTPUT(BEEPER_PIN); - #endif -} - -// Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze() { - const millis_t now = millis(); - static uint8_t lastEncoderBits; - uint8_t newbutton = 0; - static signed char temp_diff = 0; - - ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - if (BUTTON_PRESSED(ENC)) { - static millis_t next_click_update_ms; - if (ELAPSED(now, next_click_update_ms)) { - next_click_update_ms = millis() + 300; - Encoder_tick(); - #if PIN_EXISTS(LCD_LED) - //LED_Action(); - #endif - const bool was_waiting = wait_for_user; - wait_for_user = false; - return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; - } - else return ENCODER_DIFF_NO; - } - if (newbutton != lastEncoderBits) { - switch (newbutton) { - case ENCODER_PHASE_0: - if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; - break; - case ENCODER_PHASE_1: - if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; - break; - case ENCODER_PHASE_2: - if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; - break; - case ENCODER_PHASE_3: - if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; - break; - } - lastEncoderBits = newbutton; - } - - if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { - #if ENABLED(REVERSE_ENCODER_DIRECTION) - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CCW; - else temp_diffState = ENCODER_DIFF_CW; - #else - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; - else temp_diffState = ENCODER_DIFF_CCW; - #endif - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - - millis_t ms = millis(); - int32_t encoderMultiplier = 1; - - // if must encoder rati multiplier - if (EncoderRate.enabled) { - const float abs_diff = ABS(temp_diff), - encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.lastEncoderTime) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the temp_diff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - #if ENCODER_5X_STEPS_PER_SEC - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; - #endif - } - EncoderRate.lastEncoderTime = ms; - } - - #else - - constexpr int32_t encoderMultiplier = 1; - - #endif - - // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; - - temp_diff = 0; - } - return temp_diffState; -} - -#if PIN_EXISTS(LCD_LED) - - // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 - uint16_t LED_DataArray[LED_NUM]; - - // LED light operation - void LED_Action() { - LED_Control(RGB_SCALE_WARM_WHITE,0x0F); - delay(30); - LED_Control(RGB_SCALE_WARM_WHITE,0x00); - } - - // LED initialization - void LED_Configuration() { - SET_OUTPUT(LCD_LED_PIN); - } - - // LED write data - void LED_WriteData() { - uint8_t tempCounter_LED, tempCounter_Bit; - for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { - for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { - if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { - LED_DATA_HIGH; - DELAY_NS(300); - LED_DATA_LOW; - DELAY_NS(200); - } - else { - LED_DATA_HIGH; - LED_DATA_LOW; - DELAY_NS(200); - } - } - } - } - - // LED control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance) { - for (uint8_t i = 0; i < LED_NUM; i++) { - LED_DataArray[i] = 0; - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 5/10; break; - case RGB_SCALE_R10_G7_B4: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 4/10; break; - case RGB_SCALE_R10_G8_B7: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 8/10) << 16 | luminance * 7/10; break; - } - } - LED_WriteData(); - } - - // LED gradient control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - // change_Time: gradient time (ms) - void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval) { - struct { uint8_t g, r, b; } led_data[LED_NUM]; - for (uint8_t i = 0; i < LED_NUM; i++) { - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: - led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 5/10 }; - break; - case RGB_SCALE_R10_G7_B4: - led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 4/10 }; - break; - case RGB_SCALE_R10_G8_B7: - led_data[i] = { luminance * 8/10, luminance * 10/10, luminance * 7/10 }; - break; - } - } - - struct { bool g, r, b; } led_flag = { false, false, false }; - for (uint8_t i = 0; i < LED_NUM; i++) { - while (1) { - const uint8_t g = uint8_t(LED_DataArray[i] >> 16), - r = uint8_t(LED_DataArray[i] >> 8), - b = uint8_t(LED_DataArray[i]); - if (g == led_data[i].g) led_flag.g = true; - else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; - if (r == led_data[i].r) led_flag.r = true; - else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; - if (b == led_data[i].b) led_flag.b = true; - else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; - LED_WriteData(); - if (led_flag.r && led_flag.g && led_flag.b) break; - delay(change_Interval); - } - } - } - -#endif // LCD_LED - -#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/e3v2/creality/rotary_encoder.h b/Marlin/src/lcd/e3v2/creality/rotary_encoder.h deleted file mode 100644 index 48e13b7ece..0000000000 --- a/Marlin/src/lcd/e3v2/creality/rotary_encoder.h +++ /dev/null @@ -1,94 +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 - -/***************************************************************************** - * @file lcd/e3v2/creality/rotary_encoder.h - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - ****************************************************************************/ - -#include "../../../inc/MarlinConfig.h" - -/*********************** Encoder Set ***********************/ - -typedef struct { - bool enabled = false; - int encoderMoveValue = 0; - millis_t lastEncoderTime = 0; -} ENCODER_Rate; - -extern ENCODER_Rate EncoderRate; - -typedef enum { - ENCODER_DIFF_NO = 0, // no state - ENCODER_DIFF_CW = 1, // clockwise rotation - ENCODER_DIFF_CCW = 2, // counterclockwise rotation - ENCODER_DIFF_ENTER = 3 // click -} ENCODER_DiffState; - -// Encoder initialization -void Encoder_Configuration(); - -// Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze(); - -/*********************** Encoder LED ***********************/ - -#if PIN_EXISTS(LCD_LED) - - #define LED_NUM 4 - #define LED_DATA_HIGH WRITE(LCD_LED_PIN, 1) - #define LED_DATA_LOW WRITE(LCD_LED_PIN, 0) - - #define RGB_SCALE_R10_G7_B5 1 - #define RGB_SCALE_R10_G7_B4 2 - #define RGB_SCALE_R10_G8_B7 3 - #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 - #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 - #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 - - extern unsigned int LED_DataArray[LED_NUM]; - - // LED light operation - void LED_Action(); - - // LED initialization - void LED_Configuration(); - - // LED write data - void LED_WriteData(); - - // LED control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance); - - // LED gradient control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - // change_Time: gradient time (ms) - void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval); - -#endif // LCD_LED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index dd4f07cb3a..80348e4418 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,11 +15,18 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/10 + */ + #include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) @@ -261,7 +269,7 @@ typedef struct { uint16_t x, y[2], w, h; } text_info_t; void ICON_Button(const bool here, const int iconid, const frame_rect_t &ico, const text_info_t (&txt)[2]) { const bool cn = HMI_IsChinese(); - DWIN_ICON_Show(1, 0, 0, ICON, iconid + here, ico.x, ico.y); + DWIN_ICON_Show(true, false, false, ICON, iconid + here, ico.x, ico.y); if (here) DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ico.x, ico.y, ico.x + ico.w - 1, ico.y + ico.h - 1); DWIN_Frame_AreaCopy(1, txt[cn].x, txt[cn].y[here], txt[cn].x + txt[cn].w - 1, txt[cn].y[here] + txt[cn].h - 1, ico.x + (ico.w - txt[cn].w) / 2, (ico.y + ico.h - 28) - txt[cn].h/2); } @@ -438,17 +446,17 @@ void Draw_Back_First(const bool is_sel=true) { if (is_sel) Draw_Menu_Cursor(0); } -inline ENCODER_DiffState get_encoder_state() { +inline EncoderState get_encoder_state() { static millis_t Encoder_ms = 0; const millis_t ms = millis(); if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); + const EncoderState state = Encoder_ReceiveAnalyze(); if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; return state; } template -inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, T &valref) { +inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { if (encoder_diffState == ENCODER_DIFF_CW) valref += EncoderRate.encoderMoveValue; else if (encoder_diffState == ENCODER_DIFF_CCW) @@ -762,15 +770,15 @@ void update_variable() { // Tune page temperature update #if HAS_HOTEND if (_new_hotend_target) - HotendTargetItem->Draw(CurrentMenu->line(HotendTargetItem->pos)); + HotendTargetItem->draw(CurrentMenu->line(HotendTargetItem->pos)); #endif #if HAS_HEATED_BED if (_new_bed_target) - BedTargetItem->Draw(CurrentMenu->line(BedTargetItem->pos)); + BedTargetItem->draw(CurrentMenu->line(BedTargetItem->pos)); #endif #if HAS_FAN if (_new_fanspeed) - FanSpeedItem->Draw(CurrentMenu->line(FanSpeedItem->pos)); + FanSpeedItem->draw(CurrentMenu->line(FanSpeedItem->pos)); #endif } @@ -1098,7 +1106,7 @@ void Draw_Print_File_Menu() { // Main Process void HMI_MainMenu() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1147,7 +1155,7 @@ void HMI_MainMenu() { // Select (and Print) File void HMI_SelectFile() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); const uint16_t hasUpDir = !card.flag.workDirIsRoot; @@ -1267,7 +1275,7 @@ void HMI_SelectFile() { // Printing void HMI_Printing() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; // Avoid flicker by updating only the previous menu if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1331,7 +1339,7 @@ void HMI_Printing() { // Print done void HMI_PrintDone() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { dwin_abort_flag = true; // Reset feedrate, return to Home @@ -1341,7 +1349,7 @@ void HMI_PrintDone() { // Pause or Stop popup void HMI_PauseOrStop() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) @@ -1404,13 +1412,13 @@ void Draw_Main_Area() { #if ENABLED(ADVANCED_PAUSE_FEATURE) case FilamentPurge: Draw_Popup_FilamentPurge(); break; #endif - case Locked: LockScreen.Draw(); break; + case Locked: lockScreen.draw(); break; case Menu: case SetInt: case SetPInt: case SetIntNoDraw: case SetFloat: - case SetPFloat: CurrentMenu->Draw(); break; + case SetPFloat: CurrentMenu->draw(); break; default: break; } } @@ -1423,7 +1431,7 @@ void HMI_ReturnScreen() { } void HMI_Popup() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { wait_for_user = false; @@ -1560,7 +1568,7 @@ void EachMomentUpdate() { DWIN_UpdateLCD(); while (recovery_flag) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_ENTER) { recovery_flag = false; @@ -1714,7 +1722,7 @@ void Draw_Title(TitleClass* title) { if (title->frameid) DWIN_Frame_AreaCopy(title->frameid, title->frame.left, title->frame.top, title->frame.right, title->frame.bottom, 14, (TITLE_HEIGHT - (title->frame.bottom - title->frame.top)) / 2 - 1); else - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, HMI_data.TitleTxt_color, HMI_data.TitleBg_color, 14, (TITLE_HEIGHT - DWINUI::Get_font_height(DWIN_FONT_HEAD)) / 2 - 1, title->caption); + DWIN_Draw_String(false, DWIN_FONT_HEAD, HMI_data.TitleTxt_color, HMI_data.TitleBg_color, 14, (TITLE_HEIGHT - DWINUI::fontHeight(DWIN_FONT_HEAD)) / 2 - 1, title->caption); } void Draw_Menu(MenuClass* menu) { @@ -1725,7 +1733,7 @@ void Draw_Menu(MenuClass* menu) { // Startup routines void DWIN_Startup() { - DWINUI::Init(); + DWINUI::init(); DWINUI::onCursorDraw = Draw_Menu_Cursor; DWINUI::onCursorErase = Erase_Menu_Cursor; DWINUI::onTitleDraw = Draw_Title; @@ -1890,7 +1898,7 @@ void DWIN_Redraw_screen() { } void HMI_FilamentPurge() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) Draw_Select_Highlight(false); @@ -1910,10 +1918,10 @@ void DWIN_Redraw_screen() { #endif // ADVANCED_PAUSE_FEATURE void HMI_LockScreen() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; - LockScreen.onEncoderState(encoder_diffState); - if (LockScreen.isUnlocked()) { + lockScreen.onEncoder(encoder_diffState); + if (lockScreen.isUnlocked()) { if (CurrentMenu == AdvancedSettings) Draw_AdvancedSettings_Menu(); else @@ -1924,7 +1932,7 @@ void HMI_LockScreen() { void DWIN_LockScreen(const bool flag) { HMI_flag.lock_flag = flag; checkkey = Locked; - LockScreen.Init(); + lockScreen.init(); } // @@ -1974,7 +1982,7 @@ void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { const int32_t value = round(val * POW(10, dp)); SetOnClick(process, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), val); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), val); } // Generic onclick event for integer values @@ -2379,7 +2387,7 @@ void LevBedC () { LevBed(4); } planner.synchronize(); #ifdef MANUAL_PROBE_START_Z const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, 2, VALX - 2 * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, 2, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); #endif } @@ -2395,7 +2403,7 @@ void LevBedC () { LevBed(4); } void ManualMeshContinue(){ gcode.process_subcommands_now_P(PSTR("G29S2")); planner.synchronize(); - MMeshMoveZItem->Draw(CurrentMenu->line(MMeshMoveZItem->pos)); + MMeshMoveZItem->draw(CurrentMenu->line(MMeshMoveZItem->pos)); } void ManualMeshSave(){ @@ -2515,7 +2523,7 @@ void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line) { void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value) { onDrawMenuItem(menuitem, line); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(line), value); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), value); } void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { @@ -2928,7 +2936,7 @@ void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { // Generic menu control using the encoder void HMI_Menu() { - ENCODER_DiffState encoder_diffState = get_encoder_state(); + EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { if (CurrentMenu != nullptr) CurrentMenu->onClick(); @@ -2943,7 +2951,7 @@ void HMI_Menu() { // 1 : live change // 2 : apply change int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; @@ -2964,7 +2972,7 @@ int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { // 1 : live change // 2 : apply change int8_t HMI_GetInt(const int32_t lo, const int32_t hi) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; @@ -3018,16 +3026,16 @@ void HMI_SetPInt() { // 1 : live change // 2 : apply change int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { EncoderRate.enabled = false; - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); checkkey = Menu; return 2; } LIMIT(HMI_value.Value, lo, hi); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::Get_font_width(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); return 1; } return 0; @@ -3098,7 +3106,7 @@ void Draw_Prepare_Menu() { #endif ADDMENUITEM(ICON_Language, PSTR("UI Language"), onDrawLanguage, SetLanguage); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_LevBedCorners_Menu() { @@ -3116,7 +3124,7 @@ void Draw_LevBedCorners_Menu() { ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_BL), onDrawMenuItem, LevBedBL); ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_C ), onDrawMenuItem, LevBedC ); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_Control_Menu() { @@ -3138,7 +3146,7 @@ void Draw_Control_Menu() { ADDMENUITEM(ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_Info, GET_TEXT(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_InfoMenu); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_AdvancedSettings_Menu() { @@ -3176,7 +3184,7 @@ void Draw_AdvancedSettings_Menu() { #endif ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_Move_Menu() { @@ -3194,7 +3202,7 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_Extruder, GET_TEXT(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); if (!all_axes_trusted()) ui.set_status_P(PSTR("WARNING: position is unknow")); } @@ -3211,7 +3219,7 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_HomeOffsetY, GET_TEXT(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); ADDMENUITEM_P(ICON_HomeOffsetZ, GET_TEXT(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3229,7 +3237,7 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); ADDMENUITEM(ICON_ProbeTest, GET_TEXT(MSG_M48_TEST), onDrawMenuItem, ProbeTest); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3256,7 +3264,7 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif // HAS_FILAMENT_SENSOR @@ -3288,7 +3296,7 @@ void Draw_SelectColors_Menu() { ADDMENUITEM_P(0, "Indicator value", onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); ADDMENUITEM_P(0, "Coordinate value", onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_GetColor_Menu() { @@ -3304,7 +3312,7 @@ void Draw_GetColor_Menu() { ADDMENUITEM(1, "Green", onDrawGetColorItem, SetRGBColor); ADDMENUITEM(2, "Blue", onDrawGetColorItem, SetRGBColor); } - CurrentMenu->Draw(); + CurrentMenu->draw(); DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); } @@ -3338,7 +3346,7 @@ void Draw_Tune_Menu() { ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_Motion_Menu() { @@ -3357,7 +3365,7 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_Step, GET_TEXT(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -3376,7 +3384,7 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_FilLoad, GET_TEXT(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3394,7 +3402,7 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); ADDMENUITEM(ICON_MeshSave, GET_TEXT(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3420,7 +3428,7 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_Preheat1_Menu() { @@ -3471,7 +3479,7 @@ void Draw_Temperature_Menu() { #endif #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_MaxSpeed_Menu() { @@ -3489,7 +3497,7 @@ void Draw_MaxSpeed_Menu() { ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } void Draw_MaxAccel_Menu() { @@ -3507,7 +3515,7 @@ void Draw_MaxAccel_Menu() { ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #if HAS_CLASSIC_JERK @@ -3526,7 +3534,7 @@ void Draw_MaxAccel_Menu() { ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3545,7 +3553,7 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_StepE, GET_TEXT(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #if HAS_HOTEND @@ -3567,7 +3575,7 @@ void Draw_Steps_Menu() { ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3590,7 +3598,7 @@ void Draw_Steps_Menu() { ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } - CurrentMenu->Draw(); + CurrentMenu->draw(); } #endif @@ -3607,7 +3615,7 @@ void Draw_Steps_Menu() { ADDMENUITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } - CurrentMenu->Draw(); + CurrentMenu->draw(); if (!axis_is_trusted(Z_AXIS)) ui.set_status_P(PSTR("WARNING: Z position is unknow, move Z to home")); } #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index ccc47907cf..8d138df7f7 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,15 +15,22 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ #pragma once +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ + #include "../../../inc/MarlinConfigPre.h" #include "dwinui.h" -#include "rotary_encoder.h" +#include "../common/encoder.h" #include "../../../libs/BL24CXX.h" #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT @@ -79,11 +87,6 @@ enum pidresult_t : uint8_t { PID_DONE }; -// Picture ID -#define Start_Process 0 -#define Language_English 1 -#define Language_Chinese 2 - #define DWIN_CHINESE 123 #define DWIN_ENGLISH 0 @@ -120,12 +123,16 @@ typedef struct { uint16_t Barfill_Color = Def_Barfill_Color; uint16_t Indicator_Color = Def_Indicator_Color; uint16_t Coordinate_Color = Def_Coordinate_Color; - TERN_(HAS_HOTEND, int16_t HotendPidT = PREHEAT_1_TEMP_HOTEND); - TERN_(HAS_HOTEND, int16_t PidCycles = 10); + #if HAS_HOTEND + int16_t HotendPidT = PREHEAT_1_TEMP_HOTEND; + int16_t PidCycles = 10; + #endif #ifdef PREHEAT_1_TEMP_BED int16_t BedPidT = PREHEAT_1_TEMP_BED; #endif - TERN_(PREVENT_COLD_EXTRUSION, int16_t ExtMinT = EXTRUDE_MINTEMP); + #if ENABLED(PREVENT_COLD_EXTRUSION) + int16_t ExtMinT = EXTRUDE_MINTEMP; + #endif } HMI_data_t; typedef struct { @@ -150,7 +157,9 @@ void DWIN_Popup_Confirm(uint8_t icon, const char * const msg1, const char * cons #if HAS_HOTEND || HAS_HEATED_BED void DWIN_Popup_Temperature(const bool toohigh); #endif -TERN_(HAS_HOTEND, void Popup_Window_ETempTooLow()); +#if HAS_HOTEND + void Popup_Window_ETempTooLow(); +#endif void Popup_Window_Resume(); // SD Card @@ -179,7 +188,6 @@ void HMI_AudioFeedback(const bool success=true); void EachMomentUpdate(); void update_variable(); void DWIN_HandleScreen(); -void DWIN_Startup(); void DWIN_Update(); void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text); void DWIN_StatusChanged(const char * const text); @@ -229,27 +237,41 @@ void Draw_AdvancedSettings_Menu(); void Draw_Prepare_Menu(); void Draw_Move_Menu(); void Draw_LevBedCorners_Menu(); -TERN_(HAS_HOME_OFFSET, void Draw_HomeOffset_Menu()); -TERN_(HAS_BED_PROBE, void Draw_ProbeSet_Menu()); -TERN_(HAS_FILAMENT_SENSOR, void Draw_FilSet_Menu()); +#if HAS_HOME_OFFSET + void Draw_HomeOffset_Menu(); +#endif +#if HAS_BED_PROBE + void Draw_ProbeSet_Menu(); +#endif +#if HAS_FILAMENT_SENSOR + void Draw_FilSet_Menu(); +#endif void Draw_SelectColors_Menu(); void Draw_GetColor_Menu(); void Draw_Tune_Menu(); void Draw_Motion_Menu(); -TERN_(ADVANCED_PAUSE_FEATURE, void Draw_FilamentMan_Menu()); -TERN_(MESH_BED_LEVELING, void Draw_ManualMesh_Menu()); +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void Draw_FilamentMan_Menu(); +#endif +#if ENABLED(MESH_BED_LEVELING) + void Draw_ManualMesh_Menu(); +#endif #if HAS_HOTEND void Draw_Preheat1_Menu(); void Draw_Preheat2_Menu(); void Draw_Preheat3_Menu(); + void Draw_HotendPID_Menu(); #endif void Draw_Temperature_Menu(); void Draw_MaxSpeed_Menu(); void Draw_MaxAccel_Menu(); -TERN_(HAS_CLASSIC_JERK, void Draw_MaxJerk_Menu()); +#if HAS_CLASSIC_JERK + void Draw_MaxJerk_Menu(); +#endif void Draw_Steps_Menu(); -TERN_(HAS_HOTEND, void Draw_HotendPID_Menu()); -TERN_(HAS_HEATED_BED, void Draw_BedPID_Menu()); +#if HAS_HEATED_BED + void Draw_BedPID_Menu(); +#endif #if EITHER(HAS_BED_PROBE, BABYSTEPPING) void Draw_ZOffsetWiz_Menu(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp index b9246523ce..93477be0b8 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,18 +15,17 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ -/******************************************************************************** - * @file lcd/e3v2/enhanced/dwin_lcd.cpp - * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo - * @date 2021/09/08 - * @version 2.2.1 - * @brief DWIN screen control functions - ********************************************************************************/ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ #include "../../../inc/MarlinConfigPre.h" @@ -34,297 +34,6 @@ #include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" -#include // for memset - -//#define DEBUG_OUT 1 -#include "../../../core/debug_out.h" - -// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. -// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. -uint8_t DWIN_SendBuf[11 + DWIN_DataLength] = { 0xAA }; -uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; -uint8_t databuf[26] = { 0 }; -uint8_t receivedType; - -int recnum = 0; - -inline void DWIN_Byte(size_t &i, const uint16_t bval) { - DWIN_SendBuf[++i] = bval; -} - -inline void DWIN_Word(size_t &i, const uint16_t wval) { - DWIN_SendBuf[++i] = wval >> 8; - DWIN_SendBuf[++i] = wval & 0xFF; -} - -inline void DWIN_Long(size_t &i, const uint32_t lval) { - DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; - DWIN_SendBuf[++i] = lval & 0xFF; -} - -inline void DWIN_String(size_t &i, const char * const string, uint16_t rlimit = 0xFFFF) { - if (!string) return; - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(strlen(string), rlimit)); - if (len == 0) return; - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -inline void DWIN_String(size_t &i, const __FlashStringHelper * string, uint16_t rlimit = 0xFFFF) { - if (!string) return; - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P((PGM_P)string))); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. - if (len == 0) return; - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -// Send the data in the buffer and the packet end -inline void DWIN_Send(size_t &i) { - ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } -} - -/*-------------------------------------- System variable function --------------------------------------*/ - -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void) { - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 115200 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - const millis_t serial_connect_timeout = millis() + 1000UL; - while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - - size_t i = 0; - DWIN_Byte(i, 0x00); - DWIN_Send(i); - - while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { - databuf[recnum] = LCD_SERIAL.read(); - // ignore the invalid data - if (databuf[0] != FHONE) { // prevent the program from running. - if (recnum > 0) { - recnum = 0; - ZERO(databuf); - } - continue; - } - delay(10); - recnum++; - } - - return ( recnum >= 3 - && databuf[0] == FHONE - && databuf[1] == '\0' - && databuf[2] == 'O' - && databuf[3] == 'K' ); -} - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir) { - size_t i = 0; - DWIN_Byte(i, 0x34); - DWIN_Byte(i, 0x5A); - DWIN_Byte(i, 0xA5); - DWIN_Byte(i, dir); - DWIN_Send(i); -} - -// Update display -void DWIN_UpdateLCD(void) { - size_t i = 0; - DWIN_Byte(i, 0x3D); - DWIN_Send(i); -} - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color) { - size_t i = 0; - DWIN_Byte(i, 0x01); - DWIN_Word(i, color); - DWIN_Send(i); -} - -// Draw a point -// color: point color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x02); - DWIN_Word(i, color); - DWIN_Byte(i, width); - DWIN_Byte(i, height); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x03); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x05); - DWIN_Byte(i, mode); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x09); - DWIN_Byte(i, (mode << 7) | dir); - DWIN_Word(i, dis); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -// rlimit: For draw less chars than string length use rlimit -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit) { - size_t i = 0; - DWIN_Byte(i, 0x11); - // Bit 7: widthAdjust - // Bit 6: bShow - // Bit 5-4: Unused (0) - // Bit 3-0: size - DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_String(i, string, rlimit); - DWIN_Send(i); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - // Bit 7: bshow - // Bit 6: 1 = signed; 0 = unsigned number; - // Bit 5: zeroFill - // Bit 4: zeroMode - // Bit 3-0: size - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, 0); // fNum - DWIN_Word(i, x); - DWIN_Word(i, y); - #if 0 - for (char count = 0; count < 8; count++) { - DWIN_Byte(i, value); - value >>= 8; - if (!(value & 0xFF)) break; - } - #else - // Write a big-endian 64 bit integer - const size_t p = i + 1; - for (char count = 8; count--;) { // 7..0 - ++i; - DWIN_SendBuf[p + count] = value; - value >>= 8; - } - #endif - - DWIN_Send(i); -} - -// Draw a positive floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Scaled positive float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, fNum); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Long(i, value); - DWIN_Send(i); -} -// value: positive float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - const long val = round(value * POW(10, fNum)); - DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); -} /*---------------------------------------- Picture related functions ----------------------------------------*/ @@ -339,73 +48,23 @@ void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, char *string) { DWIN_Word(i, x); DWIN_Word(i, y); DWIN_Byte(i, QR_Pixel); - DWIN_String(i, string); + DWIN_Text(i, string); DWIN_Send(i); } -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id) { - size_t i = 0; - DWIN_Word(i, 0x2200); - DWIN_Byte(i, id); - DWIN_Send(i); -} - -// Draw an Icon -// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black -// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration -// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) +// Draw an Icon with transparent background // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point -void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x23); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | libID); - DWIN_Byte(i, picID); - DWIN_Send(i); -} - -// Draw an Icon from SRAM -// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black -// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration -// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) -// x/y: Upper-left point -// addr: SRAM address -void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint16_t x, uint16_t y, uint16_t addr) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x24); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | 0x00); - DWIN_Word(i, addr); - DWIN_Send(i); -} - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { - size_t i = 0; - DWIN_Byte(i, 0x25); - DWIN_Byte(i, n); - DWIN_Byte(i, id); - DWIN_Send(i); +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + DWIN_ICON_Show(false, false, true, libID, picID, x, y); } // Copy area from current virtual display area to current screen // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { +void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { size_t i = 0; DWIN_Byte(i, 0x26); DWIN_Word(i, xStart); @@ -425,11 +84,10 @@ void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { +void DWIN_Frame_AreaCopy(bool IBD, bool BIR, bool BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { size_t i = 0; DWIN_Byte(i, 0x27); - DWIN_Byte(i, IBD%2<<7 | BIR%2<<6 | BFI%2<<5 | cacheID); + DWIN_Byte(i, (IBD & 1) << 7 | (BIR & 1) << 6 | (BFI & 1) << 5 | cacheID); DWIN_Word(i, xStart); DWIN_Word(i, yStart); DWIN_Word(i, xEnd); @@ -439,48 +97,13 @@ void DWIN_Frame_AreaCopy(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t cacheID, DWIN_Send(i); } -// Animate a series of icons -// animID: Animation ID; 0x00-0x0F -// animate: true on; false off; -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x28); - DWIN_Word(i, x); - DWIN_Word(i, y); - // Bit 7: animation on or off - // Bit 6: start from begin or end - // Bit 5-4: unused (0) - // Bit 3-0: animID - DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); - DWIN_Byte(i, libID); - DWIN_Byte(i, picIDs); - DWIN_Byte(i, picIDe); - DWIN_Byte(i, interval); - DWIN_Send(i); -} - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state) { - size_t i = 0; - DWIN_Byte(i, 0x29); - DWIN_Word(i, state); - DWIN_Send(i); -} - -// Set LCD Brightness 0x00-0xFF -void DWIN_LCD_Brightness(const uint8_t brightness) { - size_t i = 0; - DWIN_Byte(i, 0x30); - DWIN_Byte(i, brightness); - DWIN_Send(i); +// Copy area from virtual display area to current screen with transparent background +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { + DWIN_Frame_AreaCopy(false, false, true, cacheID, xStart, yStart, xEnd, yEnd, x, y); } // Write buffer data to the SRAM or Flash @@ -524,47 +147,14 @@ void DWIN_SRAMToPic(uint8_t picID) { //--------------------------Test area ------------------------- -// void DWIN_ReadSRAM(uint16_t addr, uint8_t length, const char * const data) { -// size_t i = 0; -// DWIN_Byte(i, 0x32); -// DWIN_Byte(i, 0x5A); // 0x5A Read from SRAM - 0xA5 Read from Flash -// DWIN_Word(i, addr); // 0x0000 to 0x7FFF -// const size_t len = _MIN(0xF0, length); -// DWIN_Byte(i, len); -// DWIN_Send(i); -// } - -/*---------------------------------------- Memory functions ----------------------------------------*/ -// The LCD has an additional 32KB SRAM and 16KB Flash - -// Data can be written to the sram and save to one of the jpeg page files - -// Write Data Memory -// command 0x31 -// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Data: data -// -// Flash writing returns 0xA5 0x4F 0x4B - -// Read Data Memory -// command 0x32 -// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Length: leangth of data to read; 0x01-0xF0 -// -// Response: -// Type, Address, Length, Data - -// Write Picture Memory -// Write the contents of the 32KB SRAM data memory into the designated image memory space -// Issued: 0x5A, 0xA5, PIC_ID -// Response: 0xA5 0x4F 0x4B -// -// command 0x33 -// 0x5A, 0xA5 -// PicId: Picture Memory location, 0x00-0x0F -// -// Flash writing returns 0xA5 0x4F 0x4B +//void DWIN_ReadSRAM(uint16_t addr, uint8_t length, const char * const data) { +// size_t i = 0; +// DWIN_Byte(i, 0x32); +// DWIN_Byte(i, 0x5A); // 0x5A Read from SRAM - 0xA5 Read from Flash +// DWIN_Word(i, addr); // 0x0000 to 0x7FFF +// const size_t len = _MIN(0xF0, length); +// DWIN_Byte(i, len); +// DWIN_Send(i); +//} #endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h index c66416a7ed..f33879bb7e 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,169 +15,20 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ - -/******************************************************************************** - * @file lcd/e3v2/enhanced/dwin_lcd.h - * @author LEO / Creality3D - Enhanced by Miguel A. Risco-Castillo - * @date 2021/08/09 - * @version 2.2.1 - * @brief DWIN screen control functions - ********************************************************************************/ - #pragma once -#include +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ -#define RECEIVED_NO_DATA 0x00 -#define RECEIVED_SHAKE_HAND_ACK 0x01 - -#define FHONE 0xAA - -#define DWIN_SCROLL_UP 2 -#define DWIN_SCROLL_DOWN 3 - -#define DWIN_WIDTH 272 -#define DWIN_HEIGHT 480 - -#define DWIN_DataLength (DWIN_WIDTH / 6 * 2) - -/*-------------------------------------- System variable function --------------------------------------*/ - -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void); - -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance); - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir); - -// Update display -void DWIN_UpdateLCD(void); - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color); - -// Draw a point -// color: point color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a Horizontal line -// color: Line segment color -// xStart/yStart: Start point -// xLength: Line Length -inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); -} - -// Draw a Vertical line -// color: Line segment color -// xStart/yStart: Start point -// yLength: Line Length -inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a box -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xSize/ySize: box size -inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { - DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -// rlimit: For draw less chars than string length use rlimit -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit = 0xFFFF); -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit = 0xFFFF) { - DWIN_Draw_String(0, bShow, size, color, bColor, x, y, string, rlimit); -} - -class __FlashStringHelper; - -inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, (char *)title); -} -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(0, bShow, size, color, bColor, x, y, (char *)title); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value); - -// Draw a positive floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Scaled positive float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); -// value: positive float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); - -/*---------------------------------------- Picture related functions ----------------------------------------*/ +#include "../common/dwin_api.h" // Display QR code // The size of the QR code is (46*QR_Pixel)*(46*QR_Pixel) dot matrix @@ -189,50 +41,25 @@ inline void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, const __Flash DWIN_Draw_QR(QR_Pixel, x, y, (char *)title); } -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id); +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); -// Draw an Icon -// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black -// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration -// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - -// Draw an Icon with transparent background -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -inline void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - DWIN_ICON_Show(0, 0, 1, libID, picID, x, y); -} - -// Draw an Icon from SRAM -// IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black -// BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration -// BFI: Background filtering strength: 0=normal, 1=enhanced, (only valid when the icon background display=0) -// x/y: Upper-left point -// addr: SRAM address -void DWIN_ICON_Show(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint16_t x, uint16_t y, uint16_t addr); - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); - -// Unzip the JPG picture to virtual display area #1 -// id: Picture ID -inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point +void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); // Copy area from current virtual display area to current screen // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); +void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); // Copy area from virtual display area to current screen // IBD: background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black @@ -242,36 +69,7 @@ void DWIN_Frame_AreaCopy(uint16_t xStart, uint16_t yStart, // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t IBD, uint8_t BIR, uint8_t BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - -// Copy area from virtual display area to current screen with transparent background -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -inline void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { - DWIN_Frame_AreaCopy(0, 0, 1, cacheID, xStart, yStart, xEnd, yEnd, x, y); -} - -// Animate a series of icons -// animID: Animation ID up to 16 -// animate: animation on or off -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, - uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state); - -// Set LCD Brightness 0x00-0x0F -void DWIN_LCD_Brightness(const uint8_t brightness); +void DWIN_Frame_AreaCopy(bool IBD, bool BIR, bool BFI, uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); // Write buffer data to the SRAM or Flash // mem: 0x5A=32KB SRAM, 0xA5=16KB Flash diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index 85353bed28..5c2cb3d1c1 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/08/09 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,11 +15,18 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ + #include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) @@ -48,7 +56,7 @@ void (*DWINUI::onCursorDraw)(uint8_t line)=nullptr; void (*DWINUI::onTitleDraw)(TitleClass* title)=nullptr; void (*DWINUI::onMenuDraw)(MenuClass* menu)=nullptr; -void DWINUI::Init(void) { +void DWINUI::init() { DEBUG_ECHOPGM("\r\nDWIN handshake "); delay(750); // Delay here or init later in the boot process const bool success = DWIN_Handshake(); @@ -65,12 +73,12 @@ void DWINUI::Init(void) { } // Set text/number font -void DWINUI::SetFont(uint8_t cfont) { +void DWINUI::setFont(uint8_t cfont) { font = cfont; } // Get font character width -uint8_t DWINUI::Get_font_width(uint8_t cfont) { +uint8_t DWINUI::fontWidth(uint8_t cfont) { switch (cfont) { case font6x12 : return 6; case font8x16 : return 8; @@ -87,7 +95,7 @@ uint8_t DWINUI::Get_font_width(uint8_t cfont) { } // Get font character heigh -uint8_t DWINUI::Get_font_height(uint8_t cfont) { +uint8_t DWINUI::fontHeight(uint8_t cfont) { switch (cfont) { case font6x12 : return 12; case font8x16 : return 16; @@ -105,12 +113,12 @@ uint8_t DWINUI::Get_font_height(uint8_t cfont) { // Get screen x coodinates from text column uint16_t DWINUI::ColToX(uint8_t col) { - return col * Get_font_width(font); + return col * fontWidth(font); } // Get screen y coodinates from text row uint16_t DWINUI::RowToY(uint8_t row) { - return row * Get_font_height(font); + return row * fontHeight(font); } // Set text/number color @@ -151,7 +159,7 @@ void DWINUI::MoveBy(xy_int_t point) { // Draw a Centered string using DWIN_WIDTH void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { - const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * Get_font_width(size)) / 2 - 1; + const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * fontWidth(size)) / 2 - 1; DWIN_Draw_String(bShow, size, color, bColor, x, y, string); } @@ -159,7 +167,7 @@ void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint1 void DWINUI::Draw_Char(const char c) { const char string[2] = { c, 0}; DWIN_Draw_String(false, font, textcolor, backcolor, cursor.x, cursor.y, string, 1); - MoveBy(Get_font_width(font), 0); + MoveBy(fontWidth(font), 0); } // Draw a string at cursor position @@ -168,11 +176,11 @@ void DWINUI::Draw_Char(const char c) { // rlimit: For draw less chars than string length use rlimit void DWINUI::Draw_String(const char * const string, uint16_t rlimit) { DWIN_Draw_String(false, font, textcolor, backcolor, cursor.x, cursor.y, string, rlimit); - MoveBy(strlen(string) * Get_font_width(font), 0); + MoveBy(strlen(string) * fontWidth(font), 0); } void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rlimit) { DWIN_Draw_String(false, font, color, backcolor, cursor.x, cursor.y, string, rlimit); - MoveBy(strlen(string) * Get_font_width(font), 0); + MoveBy(strlen(string) * fontWidth(font), 0); } // Draw a signed floating point number @@ -186,14 +194,8 @@ void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rli // x/y: Upper-left point // value: Float value void DWINUI::Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - if (value < 0) { - DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, -value); - DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, F("-")); - } - else { - DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, F(" ")); - DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); - } + DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value < 0 ? -value : value); + DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, value < 0 ? F("-") : F(" ")); } // Draw a circle @@ -239,7 +241,7 @@ void DWINUI::Draw_FillCircle(uint16_t bcolor, uint16_t x,uint16_t y,uint8_t r) { // Color Interpolator // val : Interpolator minv..maxv // minv : Minimum value -// maxv : Maximun value +// maxv : Maximum value // color1 : Start color // color2 : End color uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2) { @@ -255,7 +257,7 @@ uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t colo // Color Interpolator through Red->Yellow->Green->Blue // val : Interpolator minv..maxv // minv : Minimum value -// maxv : Maximun value +// maxv : Maximum value uint16_t DWINUI::RainbowInt(int16_t val, int16_t minv, int16_t maxv) { uint8_t B,G,R; const uint8_t maxB = 28; @@ -292,7 +294,7 @@ uint16_t DWINUI::RainbowInt(int16_t val, int16_t minv, int16_t maxv) { // x/y: Upper-left point // mode : 0 : unchecked, 1 : checked void DWINUI::Draw_Checkbox(uint16_t color, uint16_t bcolor, uint16_t x, uint16_t y, bool checked=false) { - DWIN_Draw_String(false, true, font8x16, color, bcolor, x + 4, y, checked ? F("x") : F(" ")); + DWIN_Draw_String(true, font8x16, color, bcolor, x + 4, y, checked ? F("x") : F(" ")); DWIN_Draw_Rectangle(0, color, x + 2, y + 2, x + 17, y + 17); } @@ -332,7 +334,7 @@ MenuItemClass* DWINUI::MenuItemsAdd(MenuItemClass* menuitem) { TitleClass Title; -void TitleClass::Draw() { +void TitleClass::draw() { if (DWINUI::onTitleDraw != nullptr) (*DWINUI::onTitleDraw)(this); } @@ -346,7 +348,7 @@ void TitleClass::SetCaption(const char * const title) { void TitleClass::ShowCaption(const char * const title) { SetCaption(title); - Draw(); + draw(); } void TitleClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { @@ -361,7 +363,7 @@ void TitleClass::SetFrame(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { void TitleClass::FrameCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { SetFrame(id, x1, y1, x2, y2); - Draw(); + draw(); } void TitleClass::FrameCopy(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { @@ -375,11 +377,11 @@ MenuClass::MenuClass() { topline = 0; } -void MenuClass::Draw() { - MenuTitle.Draw(); +void MenuClass::draw() { + MenuTitle.draw(); if (DWINUI::onMenuDraw != nullptr) (*DWINUI::onMenuDraw)(this); for (uint8_t i = 0; i < MenuItemCount; i++) - MenuItems[i]->Draw(i - topline); + MenuItems[i]->draw(i - topline); if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); DWIN_UpdateLCD(); } @@ -393,12 +395,12 @@ void MenuClass::onScroll(bool dir) { if ((sel - topline) == TROWS) { DWIN_Frame_AreaMove(1, DWIN_SCROLL_UP, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); topline++; - MenuItems[sel]->Draw(TROWS - 1); + MenuItems[sel]->draw(TROWS - 1); } if ((sel < topline)) { DWIN_Frame_AreaMove(1, DWIN_SCROLL_DOWN, MLINE, DWINUI::backcolor, 0, TITLE_HEIGHT + 1, DWIN_WIDTH, STATUS_Y - 1); topline--; - MenuItems[sel]->Draw(0); + MenuItems[sel]->draw(0); } selected = sel; if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); @@ -440,7 +442,7 @@ void MenuItemClass::SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, frame = { x1, y1, x2, y2 }; } -void MenuItemClass::Draw(int8_t line) { +void MenuItemClass::draw(int8_t line) { if (line < 0 || line >= TROWS) return; if (onDraw != nullptr) (*onDraw)(this, line); }; diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index 1ec51bec22..dd2fc74291 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/08/09 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,117 +15,26 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ #pragma once +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ + #include "../../../core/types.h" #include "dwin_lcd.h" - -// ICON ID -#define ICON 7 // Icon set file 7.ICO - -#define ICON_LOGO 0 -#define ICON_Print_0 1 -#define ICON_Print_1 2 -#define ICON_Prepare_0 3 -#define ICON_Prepare_1 4 -#define ICON_Control_0 5 -#define ICON_Control_1 6 -#define ICON_Leveling_0 7 -#define ICON_Leveling_1 8 -#define ICON_HotendTemp 9 -#define ICON_BedTemp 10 -#define ICON_Speed 11 -#define ICON_Zoffset 12 -#define ICON_Back 13 -#define ICON_File 14 -#define ICON_PrintTime 15 -#define ICON_RemainTime 16 -#define ICON_Setup_0 17 -#define ICON_Setup_1 18 -#define ICON_Pause_0 19 -#define ICON_Pause_1 20 -#define ICON_Continue_0 21 -#define ICON_Continue_1 22 -#define ICON_Stop_0 23 -#define ICON_Stop_1 24 -#define ICON_Bar 25 -#define ICON_More 26 - -#define ICON_Axis 27 -#define ICON_CloseMotor 28 -#define ICON_Homing 29 -#define ICON_SetHome 30 -#define ICON_PLAPreheat 31 -#define ICON_ABSPreheat 32 -#define ICON_Cool 33 -#define ICON_Language 34 - -#define ICON_MoveX 35 -#define ICON_MoveY 36 -#define ICON_MoveZ 37 -#define ICON_Extruder 38 - -#define ICON_Temperature 40 -#define ICON_Motion 41 -#define ICON_WriteEEPROM 42 -#define ICON_ReadEEPROM 43 -#define ICON_ResumeEEPROM 44 -#define ICON_Info 45 - -#define ICON_SetEndTemp 46 -#define ICON_SetBedTemp 47 -#define ICON_FanSpeed 48 -#define ICON_SetPLAPreheat 49 -#define ICON_SetABSPreheat 50 - -#define ICON_MaxSpeed 51 -#define ICON_MaxAccelerated 52 -#define ICON_MaxJerk 53 -#define ICON_Step 54 -#define ICON_PrintSize 55 -#define ICON_Version 56 -#define ICON_Contact 57 -#define ICON_StockConfiguration 58 -#define ICON_MaxSpeedX 59 -#define ICON_MaxSpeedY 60 -#define ICON_MaxSpeedZ 61 -#define ICON_MaxSpeedE 62 -#define ICON_MaxAccX 63 -#define ICON_MaxAccY 64 -#define ICON_MaxAccZ 65 -#define ICON_MaxAccE 66 -#define ICON_MaxSpeedJerkX 67 -#define ICON_MaxSpeedJerkY 68 -#define ICON_MaxSpeedJerkZ 69 -#define ICON_MaxSpeedJerkE 70 -#define ICON_StepX 71 -#define ICON_StepY 72 -#define ICON_StepZ 73 -#define ICON_StepE 74 -#define ICON_Setspeed 75 -#define ICON_SetZOffset 76 -#define ICON_Rectangle 77 -#define ICON_BLTouch 78 -#define ICON_TempTooLow 79 -#define ICON_AutoLeveling 80 -#define ICON_TempTooHigh 81 -#define ICON_NoTips_C 82 -#define ICON_NoTips_E 83 -#define ICON_Continue_C 84 -#define ICON_Continue_E 85 -#define ICON_Cancel_C 86 -#define ICON_Cancel_E 87 -#define ICON_Confirm_C 88 -#define ICON_Confirm_E 89 -#define ICON_Info_0 90 -#define ICON_Info_1 91 +#include "../common/dwin_set.h" +#include "../common/dwin_font.h" +#include "../common/dwin_color.h" // Extra Icons -#define ICON_AdvSet ICON_Language #define ICON_Brightness ICON_Motion #define ICON_Cancel ICON_StockConfiguration #define ICON_CustomPreheat ICON_SetEndTemp @@ -135,10 +45,6 @@ #define ICON_FilSet ICON_ResumeEEPROM #define ICON_FilUnload ICON_ReadEEPROM #define ICON_Flow ICON_StepE -#define ICON_HomeOffset ICON_AdvSet -#define ICON_HomeOffsetX ICON_StepX -#define ICON_HomeOffsetY ICON_StepY -#define ICON_HomeOffsetZ ICON_StepZ #define ICON_LevBed ICON_SetEndTemp #define ICON_Lock ICON_Cool #define ICON_ManualMesh ICON_HotendTemp @@ -146,13 +52,8 @@ #define ICON_MeshSave ICON_WriteEEPROM #define ICON_MoveZ0 ICON_HotendTemp #define ICON_Park ICON_Motion -#define ICON_PIDbed ICON_SetBedTemp #define ICON_PIDcycles ICON_ResumeEEPROM -#define ICON_PIDNozzle ICON_SetEndTemp #define ICON_PIDValue ICON_Contact -#define ICON_ProbeOffsetX ICON_StepX -#define ICON_ProbeOffsetY ICON_StepY -#define ICON_ProbeOffsetZ ICON_StepZ #define ICON_ProbeSet ICON_SetEndTemp #define ICON_ProbeTest ICON_SetEndTemp #define ICON_Pwrlossr ICON_Motion @@ -162,47 +63,6 @@ #define ICON_SetCustomPreheat ICON_SetEndTemp #define ICON_Sound ICON_Cool -/** - * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: - * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 - * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 - */ -#define font6x12 0x00 -#define font8x16 0x01 -#define font10x20 0x02 -#define font12x24 0x03 -#define font14x28 0x04 -#define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 - -// Extended and default UI Colors -#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 -#define GetRColor(color) ((color >> 11) & 0x1F) -#define GetGColor(color) ((color >> 5) & 0x3F) -#define GetBColor(color) ((color >> 0) & 0x1F) - -#define Color_White 0xFFFF -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_Bg_Red 0xF00F // Red background color -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color - -#define Color_Black 0 -#define Color_Red RGB(31,0,0) -#define Color_Yellow RGB(31,63,0) -#define Color_Green RGB(0,63,0) -#define Color_Aqua RGB(0,63,31) -#define Color_Blue RGB(0,0,31) - // Default UI Colors #define Def_Background_Color Color_Bg_Black #define Def_Cursor_color Rectangle_Color @@ -223,7 +83,7 @@ #define Def_Indicator_Color Color_White #define Def_Coordinate_Color Color_White -//UI elements defines and constants +// UI element defines and constants #define DWIN_FONT_MENU font8x16 #define DWIN_FONT_STAT font10x20 #define DWIN_FONT_HEAD font10x20 @@ -262,7 +122,7 @@ public: char caption[32] = ""; uint8_t frameid = 0; rect_t frame = {0}; - void Draw(); + void draw(); void SetCaption(const char * const title); inline void SetCaption(const __FlashStringHelper * title) { SetCaption((char *)title); } void ShowCaption(const char * const title); @@ -290,7 +150,7 @@ public: MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); virtual ~MenuItemClass(){}; - virtual void Draw(int8_t line); + virtual void draw(int8_t line); }; class MenuItemPtrClass: public MenuItemClass { @@ -310,7 +170,7 @@ public: virtual ~MenuClass(){}; inline int8_t line() { return selected - topline; }; inline int8_t line(uint8_t pos) {return pos - topline; }; - void Draw(); + void draw(); void onScroll(bool dir); void onClick(); MenuItemClass* SelectedItem(); @@ -330,16 +190,16 @@ namespace DWINUI { extern void (*onMenuDraw)(MenuClass* menu); // DWIN LCD Initialization - void Init(void); + void init(); // Set text/number font - void SetFont(uint8_t cfont); + void setFont(uint8_t cfont); // Get font character width - uint8_t Get_font_width(uint8_t cfont); + uint8_t fontWidth(uint8_t cfont); // Get font character heigh - uint8_t Get_font_height(uint8_t cfont); + uint8_t fontHeight(uint8_t cfont); // Get screen x coodinates from text column uint16_t ColToX(uint8_t col); @@ -398,7 +258,7 @@ namespace DWINUI { } inline void Draw_Int(uint8_t iNum, long value) { DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); - MoveBy(iNum * Get_font_width(font), 0); + MoveBy(iNum * fontWidth(font), 0); } inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, x, y, value); @@ -429,7 +289,7 @@ namespace DWINUI { } inline void Draw_Float(uint8_t iNum, uint8_t fNum, float value) { DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); - MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); + MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); @@ -457,7 +317,7 @@ namespace DWINUI { void Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, float value) { Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); - MoveBy((iNum + fNum + 1) * Get_font_width(font), 0); + MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); @@ -548,7 +408,7 @@ namespace DWINUI { // Draw a circle // Color: circle color - // x: the abscissa of the center of the circle + // x: abscissa of the center of the circle // y: ordinate of the center of the circle // r: circle radius void Draw_Circle(uint16_t color, uint16_t x,uint16_t y,uint8_t r); @@ -569,7 +429,7 @@ namespace DWINUI { // Color Interpolator // val : Interpolator minv..maxv // minv : Minimum value - // maxv : Maximun value + // maxv : Maximum value // color1 : Start color // color2 : End color uint16_t ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2); @@ -578,7 +438,7 @@ namespace DWINUI { // Draw a circle filled with color // bcolor: fill color - // x: the abscissa of the center of the circle + // x: abscissa of the center of the circle // y: ordinate of the center of the circle // r: circle radius void Draw_FillCircle(uint16_t bcolor, uint16_t x,uint16_t y,uint8_t r); @@ -589,7 +449,7 @@ namespace DWINUI { // Color Interpolator through Red->Yellow->Green->Blue // val : Interpolator minv..maxv // minv : Minimum value - // maxv : Maximun value + // maxv : Maximum value uint16_t RainbowInt(int16_t val, int16_t minv, int16_t maxv); // Write buffer data to the SRAM diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp index 2615a05881..ca772184f1 100644 --- a/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,11 +15,18 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ + #include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) @@ -29,15 +37,18 @@ #include "dwin.h" #include "lockscreen.h" -LockScreenClass LockScreen; +LockScreenClass lockScreen; -void LockScreenClass::Init() { - Lock_Pos = 0; +uint8_t LockScreenClass::lock_pos = 0; +bool LockScreenClass::unlocked = false; + +void LockScreenClass::init() { + lock_pos = 0; unlocked = false; - Draw(); + draw(); } -void LockScreenClass::Draw() { +void LockScreenClass::draw() { Title.SetCaption(PSTR("Lock Screen")); DWINUI::ClearMenuArea(); DWINUI::Draw_Icon(ICON_LOGO, 71, 120); // CREALITY logo @@ -45,25 +56,20 @@ void LockScreenClass::Draw() { DWINUI::Draw_CenteredString(Color_White, 200, F("Scroll to unlock.")); DWINUI::Draw_CenteredString(Color_White, 240, F("-> | <-")); DWIN_Draw_Box(1, HMI_data.Barfill_Color, 0, 260, DWIN_WIDTH, 20); - DWIN_Draw_VLine(Color_Yellow, Lock_Pos * DWIN_WIDTH / 255, 260, 20); + DWIN_Draw_VLine(Color_Yellow, lock_pos * DWIN_WIDTH / 255, 260, 20); DWIN_UpdateLCD(); } -void LockScreenClass::onEncoderState(ENCODER_DiffState encoder_diffState) { - if (encoder_diffState == ENCODER_DIFF_CW) { - Lock_Pos += 8; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - Lock_Pos -= 8; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - unlocked = (Lock_Pos == 128); +void LockScreenClass::onEncoder(EncoderState encoder_diffState) { + switch (encoder_diffState) { + case ENCODER_DIFF_CW: lock_pos += 8; break; + case ENCODER_DIFF_CCW: lock_pos -= 8; break; + case ENCODER_DIFF_ENTER: unlocked = (lock_pos == 128); break; + default: break; } DWIN_Draw_Box(1, HMI_data.Barfill_Color, 0, 260, DWIN_WIDTH, 20); - DWIN_Draw_VLine(Color_Yellow, Lock_Pos * DWIN_WIDTH / 255, 260, 20); + DWIN_Draw_VLine(Color_Yellow, lock_pos * DWIN_WIDTH / 255, 260, 20); DWIN_UpdateLCD(); } -bool LockScreenClass::isUnlocked() { return unlocked; } - #endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h index 32a0cc3e5a..f0c4c1fde8 100644 --- a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h @@ -1,12 +1,13 @@ /** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,22 +15,31 @@ * 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 Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ #pragma once -#include "../../../core/types.h" +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.6.3 + * Date: 2021/09/08 + */ + +#include "../common/encoder.h" +#include class LockScreenClass { private: - uint8_t Lock_Pos = 0; - bool unlocked = false; + static bool unlocked; + static uint8_t lock_pos; public: - void Init(); - void onEncoderState(ENCODER_DiffState encoder_diffState); - void Draw(); - bool isUnlocked(); + static void init(); + static void onEncoder(EncoderState encoder_diffState); + static void draw(); + static inline bool isUnlocked() { return unlocked; } }; -extern LockScreenClass LockScreen; + +extern LockScreenClass lockScreen; diff --git a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp deleted file mode 100644 index de478f79f4..0000000000 --- a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.cpp +++ /dev/null @@ -1,263 +0,0 @@ -/** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser 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 Lesser General Public License - * along with this program. If not, see . - * - */ - -/***************************************************************************** - * @file lcd/e3v2/enhanced/rotary_encoder.cpp - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - *****************************************************************************/ - -#include "../../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) - -#include "rotary_encoder.h" -#include "../../buttons.h" - -#include "../../../MarlinCore.h" -#include "../../../HAL/shared/Delay.h" - -#if HAS_BUZZER - #include "../../../libs/buzzer.h" -#endif - -#include - -#ifndef ENCODER_PULSES_PER_STEP - #define ENCODER_PULSES_PER_STEP 4 -#endif - -#if ENABLED(SOUND_MENU_ITEM) - #include "../../marlinui.h" -#endif - -ENCODER_Rate EncoderRate; - -// Buzzer -void Encoder_tick() { - #if PIN_EXISTS(BEEPER) - if (TERN1(SOUND_MENU_ITEM, ui.buzzer_enabled)) { - WRITE(BEEPER_PIN, HIGH); - delay(10); - WRITE(BEEPER_PIN, LOW); - } - #endif -} - -// Encoder initialization -void Encoder_Configuration() { - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - #if PIN_EXISTS(BEEPER) - SET_OUTPUT(BEEPER_PIN); - #endif -} - -// Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze() { - const millis_t now = millis(); - static uint8_t lastEncoderBits; - uint8_t newbutton = 0; - static signed char temp_diff = 0; - - ENCODER_DiffState temp_diffState = ENCODER_DIFF_NO; - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - if (BUTTON_PRESSED(ENC)) { - static millis_t next_click_update_ms; - if (ELAPSED(now, next_click_update_ms)) { - next_click_update_ms = millis() + 300; - Encoder_tick(); - #if PIN_EXISTS(LCD_LED) - //LED_Action(); - #endif - const bool was_waiting = wait_for_user; - wait_for_user = false; - return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; - } - else return ENCODER_DIFF_NO; - } - if (newbutton != lastEncoderBits) { - switch (newbutton) { - case ENCODER_PHASE_0: - if (lastEncoderBits == ENCODER_PHASE_3) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_1) temp_diff--; - break; - case ENCODER_PHASE_1: - if (lastEncoderBits == ENCODER_PHASE_0) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_2) temp_diff--; - break; - case ENCODER_PHASE_2: - if (lastEncoderBits == ENCODER_PHASE_1) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_3) temp_diff--; - break; - case ENCODER_PHASE_3: - if (lastEncoderBits == ENCODER_PHASE_2) temp_diff++; - else if (lastEncoderBits == ENCODER_PHASE_0) temp_diff--; - break; - } - lastEncoderBits = newbutton; - } - - if (ABS(temp_diff) >= ENCODER_PULSES_PER_STEP) { - if (temp_diff > 0) temp_diffState = ENCODER_DIFF_CW; - else temp_diffState = ENCODER_DIFF_CCW; - - #if ENABLED(ENCODER_RATE_MULTIPLIER) - - millis_t ms = millis(); - int32_t encoderMultiplier = 1; - - // if must encoder rati multiplier - if (EncoderRate.enabled) { - const float abs_diff = ABS(temp_diff), - encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.lastEncoderTime) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the temp_diff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - #if ENCODER_5X_STEPS_PER_SEC - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; - #endif - } - EncoderRate.lastEncoderTime = ms; - } - - #else - - constexpr int32_t encoderMultiplier = 1; - - #endif - - // EncoderRate.encoderMoveValue += (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - EncoderRate.encoderMoveValue = (temp_diff * encoderMultiplier) / (ENCODER_PULSES_PER_STEP); - if (EncoderRate.encoderMoveValue < 0) EncoderRate.encoderMoveValue = -EncoderRate.encoderMoveValue; - - temp_diff = 0; - } - return temp_diffState; -} - -#if PIN_EXISTS(LCD_LED) - - // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 - uint16_t LED_DataArray[LED_NUM]; - - // LED light operation - void LED_Action() { - LED_Control(RGB_SCALE_WARM_WHITE,0x0F); - delay(30); - LED_Control(RGB_SCALE_WARM_WHITE,0x00); - } - - // LED initialization - void LED_Configuration() { - SET_OUTPUT(LCD_LED_PIN); - } - - // LED write data - void LED_WriteData() { - uint8_t tempCounter_LED, tempCounter_Bit; - for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { - for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { - if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { - LED_DATA_HIGH; - DELAY_NS(300); - LED_DATA_LOW; - DELAY_NS(200); - } - else { - LED_DATA_HIGH; - LED_DATA_LOW; - DELAY_NS(200); - } - } - } - } - - // LED control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance) { - for (uint8_t i = 0; i < LED_NUM; i++) { - LED_DataArray[i] = 0; - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 5/10; break; - case RGB_SCALE_R10_G7_B4: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 7/10) << 16 | luminance * 4/10; break; - case RGB_SCALE_R10_G8_B7: LED_DataArray[i] = (luminance * 10/10) << 8 | (luminance * 8/10) << 16 | luminance * 7/10; break; - } - } - LED_WriteData(); - } - - // LED gradient control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - // change_Time: gradient time (ms) - void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval) { - struct { uint8_t g, r, b; } led_data[LED_NUM]; - for (uint8_t i = 0; i < LED_NUM; i++) { - switch (RGB_Scale) { - case RGB_SCALE_R10_G7_B5: - led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 5/10 }; - break; - case RGB_SCALE_R10_G7_B4: - led_data[i] = { luminance * 7/10, luminance * 10/10, luminance * 4/10 }; - break; - case RGB_SCALE_R10_G8_B7: - led_data[i] = { luminance * 8/10, luminance * 10/10, luminance * 7/10 }; - break; - } - } - - struct { bool g, r, b; } led_flag = { false, false, false }; - for (uint8_t i = 0; i < LED_NUM; i++) { - while (1) { - const uint8_t g = uint8_t(LED_DataArray[i] >> 16), - r = uint8_t(LED_DataArray[i] >> 8), - b = uint8_t(LED_DataArray[i]); - if (g == led_data[i].g) led_flag.g = true; - else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; - if (r == led_data[i].r) led_flag.r = true; - else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; - if (b == led_data[i].b) led_flag.b = true; - else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; - LED_WriteData(); - if (led_flag.r && led_flag.g && led_flag.b) break; - delay(change_Interval); - } - } - } - -#endif // LCD_LED - -#endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h b/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h deleted file mode 100644 index c500cfe5bb..0000000000 --- a/Marlin/src/lcd/e3v2/enhanced/rotary_encoder.h +++ /dev/null @@ -1,93 +0,0 @@ -/** - * DWIN UI Enhanced implementation - * Author: Miguel A. Risco-Castillo - * Version: 3.6.1 - * Date: 2021/08/29 - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser 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 Lesser General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/***************************************************************************** - * @file lcd/e3v2/enhanced/rotary_encoder.h - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief Rotary encoder functions - ****************************************************************************/ - -#include "../../../inc/MarlinConfig.h" - -/*********************** Encoder Set ***********************/ - -typedef struct { - bool enabled = false; - int encoderMoveValue = 0; - millis_t lastEncoderTime = 0; -} ENCODER_Rate; - -extern ENCODER_Rate EncoderRate; - -typedef enum { - ENCODER_DIFF_NO = 0, // no state - ENCODER_DIFF_CW = 1, // clockwise rotation - ENCODER_DIFF_CCW = 2, // counterclockwise rotation - ENCODER_DIFF_ENTER = 3 // click -} ENCODER_DiffState; - -// Encoder initialization -void Encoder_Configuration(); - -// Analyze encoder value and return state -ENCODER_DiffState Encoder_ReceiveAnalyze(); - -/*********************** Encoder LED ***********************/ - -#if PIN_EXISTS(LCD_LED) - - #define LED_NUM 4 - #define LED_DATA_HIGH WRITE(LCD_LED_PIN, 1) - #define LED_DATA_LOW WRITE(LCD_LED_PIN, 0) - - #define RGB_SCALE_R10_G7_B5 1 - #define RGB_SCALE_R10_G7_B4 2 - #define RGB_SCALE_R10_G8_B7 3 - #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 - #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 - #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 - - extern unsigned int LED_DataArray[LED_NUM]; - - // LED light operation - void LED_Action(); - - // LED initialization - void LED_Configuration(); - - // LED write data - void LED_WriteData(); - - // LED control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - void LED_Control(const uint8_t RGB_Scale, const uint8_t luminance); - - // LED gradient control - // RGB_Scale: RGB color ratio - // luminance: brightness (0~0xFF) - // change_Time: gradient time (ms) - void LED_GraduallyControl(const uint8_t RGB_Scale, const uint8_t luminance, const uint16_t change_Interval); - -#endif // LCD_LED diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 9b63d5331e..55aee49f82 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -40,6 +40,9 @@ #include "../../../libs/buzzer.h" #include "../../../inc/Conditionals_post.h" +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + #if ENABLED(ADVANCED_PAUSE_FEATURE) #include "../../../feature/pause.h" #endif @@ -200,7 +203,6 @@ CrealityDWINClass CrealityDWIN; uint8_t mesh_y = 0; #if ENABLED(AUTO_BED_LEVELING_UBL) - bed_mesh_t &mesh_z_values = ubl.z_values; uint8_t tilt_grid = 1; void manual_value_update(bool undefined=false) { @@ -213,11 +215,11 @@ CrealityDWINClass CrealityDWIN; struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); GRID_LOOP(x, y) { - if (!isnan(mesh_z_values[x][y])) { + if (!isnan(Z_VALUES_ARR[x][y])) { xy_pos_t rpos; rpos.x = ubl.mesh_index_to_xpos(x); rpos.y = ubl.mesh_index_to_ypos(y); - incremental_LSF(&lsf_results, rpos, mesh_z_values[x][y]); + incremental_LSF(&lsf_results, rpos, Z_VALUES_ARR[x][y]); } } @@ -232,7 +234,7 @@ CrealityDWINClass CrealityDWIN; GRID_LOOP(i, j) { float mx = ubl.mesh_index_to_xpos(i), my = ubl.mesh_index_to_ypos(j), - mz = mesh_z_values[i][j]; + mz = Z_VALUES_ARR[i][j]; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); @@ -256,13 +258,12 @@ CrealityDWINClass CrealityDWIN; DEBUG_DELAY(20); } - mesh_z_values[i][j] = mz - lsf_results.D; + Z_VALUES_ARR[i][j] = mz - lsf_results.D; } return false; } #else - bed_mesh_t &mesh_z_values = z_values; void manual_value_update() { sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); @@ -275,7 +276,7 @@ CrealityDWINClass CrealityDWIN; void manual_move(bool zmove=false) { if (zmove) { planner.synchronize(); - current_position.z = goto_mesh_value ? mesh_z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + current_position.z = goto_mesh_value ? Z_VALUES_ARR[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); planner.synchronize(); } @@ -286,7 +287,7 @@ CrealityDWINClass CrealityDWIN; sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); gcode.process_subcommands_now_P(cmd); planner.synchronize(); - current_position.z = goto_mesh_value ? mesh_z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + current_position.z = goto_mesh_value ? Z_VALUES_ARR[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); planner.synchronize(); CrealityDWIN.Redraw_Menu(); @@ -296,8 +297,8 @@ CrealityDWINClass CrealityDWIN; float get_max_value() { float max = __FLT_MIN__; GRID_LOOP(x, y) { - if (!isnan(mesh_z_values[x][y]) && mesh_z_values[x][y] > max) - max = mesh_z_values[x][y]; + if (!isnan(Z_VALUES_ARR[x][y]) && Z_VALUES_ARR[x][y] > max) + max = Z_VALUES_ARR[x][y]; } return max; } @@ -305,8 +306,8 @@ CrealityDWINClass CrealityDWIN; float get_min_value() { float min = __FLT_MAX__; GRID_LOOP(x, y) { - if (!isnan(mesh_z_values[x][y]) && mesh_z_values[x][y] < min) - min = mesh_z_values[x][y]; + if (!isnan(Z_VALUES_ARR[x][y]) && Z_VALUES_ARR[x][y] < min) + min = Z_VALUES_ARR[x][y]; } return min; } @@ -335,12 +336,12 @@ CrealityDWINClass CrealityDWIN; const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px; const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; - DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ - isnan(mesh_z_values[x][y]) ? Color_Grey : ( // gray if undefined - (mesh_z_values[x][y] < 0 ? - (uint16_t)round(0x1F * -mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative - (uint16_t)round(0x3F * mesh_z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive - _MIN(0x1F, (((uint8_t)abs(mesh_z_values[x][y]) / 10) * 4))), // + blue stepping for every mm + DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ + isnan(Z_VALUES_ARR[x][y]) ? Color_Grey : ( // gray if undefined + (Z_VALUES_ARR[x][y] < 0 ? + (uint16_t)round(0x1F * -Z_VALUES_ARR[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)round(0x3F * Z_VALUES_ARR[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive + _MIN(0x1F, (((uint8_t)abs(Z_VALUES_ARR[x][y]) / 10) * 4))), // + blue stepping for every mm start_x_px, start_y_px, end_x_px, end_y_px ); @@ -350,18 +351,18 @@ CrealityDWINClass CrealityDWIN; // Draw value text on if (viewer_print_value) { int8_t offset_x, offset_y = cell_height_px / 2 - 6; - if (isnan(mesh_z_values[x][y])) { // undefined - DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); + if (isnan(Z_VALUES_ARR[x][y])) { // undefined + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); } else { // has value if (GRID_MAX_POINTS_X < 10) - sprintf_P(buf, PSTR("%s"), dtostrf(abs(mesh_z_values[x][y]), 1, 2, str_1)); + sprintf_P(buf, PSTR("%s"), dtostrf(abs(Z_VALUES_ARR[x][y]), 1, 2, str_1)); else - sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(mesh_z_values[x][y] - (int16_t)mesh_z_values[x][y]) * 100)); + sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(Z_VALUES_ARR[x][y] - (int16_t)Z_VALUES_ARR[x][y]) * 100)); offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; if (!(GRID_MAX_POINTS_X < 10)) - DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); - DWIN_Draw_String(false, false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); } safe_delay(10); LCD_SERIAL.flushTX(); @@ -415,16 +416,11 @@ void CrealityDWINClass::Draw_Float(float value, uint8_t row, bool selected/*=fal const uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; const uint16_t xpos = 240 - (digits * 8); DWIN_Draw_Rectangle(1, Color_Bg_Black, 194, MBASE(row), 234 - (digits * 8), MBASE(row) + 16); - if (isnan(value)) { - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" NaN")); - } - else if (value < 0) { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), -value * minunit); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F("-")); - } + if (isnan(value)) + DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" NaN")); else { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), value * minunit); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" ")); + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), (value < 0 ? -value : value) * minunit); + DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), value < 0 ? F("-") : F(" ")); } } @@ -432,7 +428,7 @@ void CrealityDWINClass::Draw_Option(uint8_t value, const char * const * options, uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; uint16_t tColor = (color) ? GetColor(value, Color_White, false) : Color_White; DWIN_Draw_Rectangle(1, bColor, 202, MBASE(row) + 14, 258, MBASE(row) - 2); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, tColor, bColor, 202, MBASE(row) - 1, options[value]); + DWIN_Draw_String(false, DWIN_FONT_MENU, tColor, bColor, 202, MBASE(row) - 1, options[value]); } uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool light/*=false*/) { @@ -475,15 +471,15 @@ uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool ligh } void CrealityDWINClass::Draw_Title(const char * title) { - DWIN_Draw_String(false, false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(title) * STAT_CHR_W) / 2, 5, title); + DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(title) * STAT_CHR_W) / 2, 5, title); } void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { const uint8_t label_offset_y = !(label1 && label2) ? 0 : MENU_CHR_H * 3 / 5; const uint8_t label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2); const uint8_t label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); - if (label1) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label - if (label2) DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label + if (label1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label + if (label2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow DWIN_Draw_Line(GetColor(eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line @@ -547,50 +543,49 @@ void CrealityDWINClass::Main_Menu_Icons() { if (selection == 0) { DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 130, 126, 229); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); } else { DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); } if (selection == 1) { DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 130, 254, 229); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); } else { DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); } if (selection == 2) { DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 246, 126, 345); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); } else { DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); } #if HAS_ABL_OR_UBL if (selection == 3) { DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); } else { DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); } #else if (selection == 3) { DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); } else { DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); - //DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); } #endif } @@ -610,41 +605,41 @@ void CrealityDWINClass::Print_Screen_Icons() { if (selection == 0) { DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 8, 252, 87, 351); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); } else { DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); } if (selection == 2) { DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 184, 252, 263, 351); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); } else { DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); } if (paused) { if (selection == 1) { DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); } else { DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); } } else { if (selection == 1) { DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); } else { DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); } } } @@ -658,8 +653,8 @@ void CrealityDWINClass::Draw_Print_Screen() { Print_Screen_Icons(); DWIN_ICON_Show(ICON, ICON_PrintTime, 14, 171); DWIN_ICON_Show(ICON, ICON_RemainTime, 147, 169); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 41, 163, "Elapsed"); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 176, 163, "Remaining"); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 41, 163, F("Elapsed")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 176, 163, F("Remaining")); Update_Status_Bar(true); Draw_Print_ProgressBar(); Draw_Print_ProgressElapsed(); @@ -687,14 +682,14 @@ void CrealityDWINClass::Draw_Print_Filename(const bool reset/*=false*/) { dispname[len] = '\0'; DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, dispname); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, dispname); if (-pos >= 30) namescrl = 0; namescrl++; } else { DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); const int8_t npos = (DWIN_WIDTH - strlen(filename) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, filename); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, filename); } } } @@ -704,7 +699,7 @@ void CrealityDWINClass::Draw_Print_ProgressBar() { DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); DWIN_Draw_Rectangle(1, BarFill_Color, 16 + printpercent * 240 / 100, 93, 256, 113); DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 3, 109, 133, printpercent); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 133, 133, "%"); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 133, 133, F("%")); } #if ENABLED(USE_M73_REMAINING_TIME) @@ -714,11 +709,11 @@ void CrealityDWINClass::Draw_Print_ProgressBar() { DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 176, 187, remainingtime / 3600); DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 200, 187, (remainingtime % 3600) / 60); if (eeprom_settings.time_format_textual) { - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, "h"); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 216, 187, "m"); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F("h")); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 216, 187, F("m")); } else - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, ":"); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F(":")); } #endif @@ -728,11 +723,11 @@ void CrealityDWINClass::Draw_Print_ProgressElapsed() { DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 42, 187, elapsed.value / 3600); DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 66, 187, (elapsed.value % 3600) / 60); if (eeprom_settings.time_format_textual) { - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, "h"); - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 82, 187, "m"); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F("h")); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 82, 187, F("m")); } else - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, ":"); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F(":")); } void CrealityDWINClass::Draw_Print_confirm() { @@ -779,7 +774,7 @@ void CrealityDWINClass::Draw_SD_List(bool removed/*=false*/) { else { Draw_Menu_Item(0, ICON_Back, "Back"); DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - DWIN_Draw_String(false, false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), "No Media"); + DWIN_Draw_String(false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); } DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(0) - 18, 14, MBASE(0) + 33); } @@ -795,7 +790,7 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { hotend = -1; hotendtarget = -1; DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); } if (thermalManager.temp_hotend[0].celsius != hotend) { hotend = thermalManager.temp_hotend[0].celsius; @@ -810,7 +805,7 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { if (icons) { flow = -1; DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); } if (planner.flow_percentage[0] != flow) { flow = planner.flow_percentage[0]; @@ -825,7 +820,7 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { bed = -1; bedtarget = -1; DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); } if (thermalManager.temp_bed.celsius != bed) { bed = thermalManager.temp_bed.celsius; @@ -860,14 +855,8 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { } if (zoffsetvalue != offset) { offset = zoffsetvalue; - if (zoffsetvalue < 0) { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, -zoffsetvalue * 100); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, "-"); - } - else { - DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, zoffsetvalue* 100); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, " "); - } + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, (zoffsetvalue < 0 ? -zoffsetvalue : zoffsetvalue) * 100); + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, zoffsetvalue < 0 ? F("-") : F(" ")); } #endif @@ -875,7 +864,7 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { if (icons) { feedrate = -1; DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); } if (feedrate_percentage != feedrate) { feedrate = feedrate_percentage; @@ -897,21 +886,21 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { if (update_x) { x = current_position.x; if ((update_x = axis_should_home(X_AXIS) && ui.get_blink())) - DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 35, 459, " -?- "); + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 35, 459, F(" -?- ")); else DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 35, 459, current_position.x * 10); } if (update_y) { y = current_position.y; if ((update_y = axis_should_home(Y_AXIS) && ui.get_blink())) - DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 120, 459, " -?- "); + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 120, 459, F(" -?- ")); else DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 120, 459, current_position.y * 10); } if (update_z) { z = current_position.z; if ((update_z = axis_should_home(Z_AXIS) && ui.get_blink())) - DWIN_Draw_String(false, true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 205, 459, " -?- "); + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 205, 459, F(" -?- ")); else DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 2, 205, 459, (current_position.z>=0) ? current_position.z * 100 : 0); } @@ -927,20 +916,20 @@ void CrealityDWINClass::Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P c DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 350); const uint8_t ypos = (mode == Popup || mode == Confirm) ? 150 : 230; if (icon > 0) DWIN_ICON_Show(ICON, icon, 101, 105); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line1)) / 2, ypos, line1); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line2)) / 2, ypos + 30, line2); - DWIN_Draw_String(false, true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line3)) / 2, ypos + 60, line3); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line1)) / 2, ypos, line1); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line2)) / 2, ypos + 30, line2); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line3)) / 2, ypos + 60, line3); if (mode == Popup) { selection = 0; DWIN_Draw_Rectangle(1, Confirm_Color, 26, 280, 125, 317); DWIN_Draw_Rectangle(1, Cancel_Color, 146, 280, 245, 317); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 39, 290, "Confirm"); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 165, 290, "Cancel"); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 39, 290, F("Confirm")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 165, 290, F("Cancel")); Popup_Select(); } else if (mode == Confirm) { DWIN_Draw_Rectangle(1, Confirm_Color, 87, 280, 186, 317); - DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 96, 290, "Continue"); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 96, 290, F("Continue")); } } @@ -985,12 +974,12 @@ void CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { if (process == Print) { DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, dispmsg); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, dispmsg); } else { DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, dispmsg); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, dispmsg); } if (-pos >= 30) msgscrl = 0; msgscrl++; @@ -1001,12 +990,12 @@ void CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { if (process == Print) { DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, statusmsg); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, statusmsg); } else { DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, statusmsg); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, statusmsg); } } } @@ -1280,7 +1269,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_BED_PROBE case MOVE_P: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguraton, "Probe"); + Draw_Menu_Item(row, ICON_StockConfiguration, "Probe"); Draw_Checkbox(row, probe_deployed); } else { @@ -2866,7 +2855,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case Advanced: #define ADVANCED_BACK 0 - #define ADVANCED_BEEPER (ADVANCED_BACK + 1) + #define ADVANCED_BEEPER (ADVANCED_BACK + ENABLED(SOUND_MENU_ITEM)) #define ADVANCED_PROBE (ADVANCED_BEEPER + ENABLED(HAS_BED_PROBE)) #define ADVANCED_CORNER (ADVANCED_PROBE + 1) #define ADVANCED_LA (ADVANCED_CORNER + ENABLED(LIN_ADVANCE)) @@ -2886,16 +2875,18 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu(Control, CONTROL_ADVANCED); break; - case ADVANCED_BEEPER: - if (draw) { - Draw_Menu_Item(row, ICON_Version, "LCD Beeper"); - Draw_Checkbox(row, eeprom_settings.beeperenable); - } - else { - eeprom_settings.beeperenable = !eeprom_settings.beeperenable; - Draw_Checkbox(row, eeprom_settings.beeperenable); - } - break; + #if ENABLED(SOUND_MENU_ITEM) + case ADVANCED_BEEPER: + if (draw) { + Draw_Menu_Item(row, ICON_Version, "LCD Beeper"); + Draw_Checkbox(row, ui.buzzer_enabled); + } + else { + ui.buzzer_enabled = !ui.buzzer_enabled; + Draw_Checkbox(row, ui.buzzer_enabled); + } + break; + #endif #if HAS_BED_PROBE case ADVANCED_PROBE: @@ -3122,7 +3113,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_ACTIVE: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguraton, "Leveling Active"); + Draw_Menu_Item(row, ICON_StockConfiguration, "Leveling Active"); Draw_Checkbox(row, planner.leveling_active); } else { @@ -3407,7 +3398,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_Mesh, "Zero Current Mesh"); else - ZERO(mesh_conf.mesh_z_values); + ZERO(Z_VALUES_ARR); break; case LEVELING_SETTINGS_UNDEF: if (draw) @@ -3493,41 +3484,41 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case LEVELING_M_OFFSET: if (draw) { Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); } else { - if (isnan(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; - Modify_Value(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + if (isnan(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y])) + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); } break; case LEVELING_M_UP: if (draw) Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); - else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); } break; case LEVELING_M_DOWN: if (draw) Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); - else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); } break; case LEVELING_M_GOTO_VALUE: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguraton, "Go to Mesh Z Value"); + Draw_Menu_Item(row, ICON_StockConfiguration, "Go to Mesh Z Value"); Draw_Checkbox(row, mesh_conf.goto_mesh_value); } else { @@ -3614,36 +3605,36 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case UBL_M_OFFSET: if (draw) { Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); } else { - if (isnan(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; - Modify_Value(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + if (isnan(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y])) + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); } break; case UBL_M_UP: if (draw) Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); - else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); } break; case UBL_M_DOWN: if (draw) Draw_Menu_Item(row, ICON_Axis, "Microstep Down"); - else if (mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { - mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); - Draw_Float(mesh_conf.mesh_z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); } break; } @@ -3733,7 +3724,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (mesh_y % 2 == 1) mesh_x = GRID_MAX_POINTS_X - mesh_x - 1; - const float currval = mesh_conf.mesh_z_values[mesh_x][mesh_y]; + const float currval = Z_VALUES_ARR[mesh_x][mesh_y]; if (draw) { Draw_Menu_Item(row, ICON_Zoffset, "Goto Mesh Value"); @@ -4215,7 +4206,7 @@ void CrealityDWINClass::Confirm_Handler(PopupID popupid) { /* Navigation and Control */ void CrealityDWINClass::Main_Menu_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW && selection < PAGE_COUNT - 1) { selection++; // Select Down @@ -4236,7 +4227,7 @@ void CrealityDWINClass::Main_Menu_Control() { } void CrealityDWINClass::Menu_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); @@ -4264,7 +4255,7 @@ void CrealityDWINClass::Menu_Control() { } void CrealityDWINClass::Value_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) tempvalue += EncoderRate.encoderMoveValue; @@ -4329,7 +4320,7 @@ void CrealityDWINClass::Value_Control() { } void CrealityDWINClass::Option_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW) tempvalue += EncoderRate.encoderMoveValue; @@ -4368,7 +4359,7 @@ void CrealityDWINClass::Option_Control() { } void CrealityDWINClass::File_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); static uint8_t filescrl = 0; if (encoder_diffState == ENCODER_DIFF_NO) { if (selection > 0) { @@ -4456,7 +4447,7 @@ void CrealityDWINClass::File_Control() { } void CrealityDWINClass::Print_Screen_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW && selection < PRINT_COUNT - 1) { selection++; // Select Down @@ -4509,7 +4500,7 @@ void CrealityDWINClass::Print_Screen_Control() { } void CrealityDWINClass::Popup_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_CW && selection < 1) { selection++; @@ -4659,7 +4650,7 @@ void CrealityDWINClass::Popup_Control() { } void CrealityDWINClass::Confirm_Control() { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (popup) { @@ -4967,14 +4958,14 @@ void CrealityDWINClass::Screen_Update() { void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { if (success) { - if (eeprom_settings.beeperenable) { + if (ui.buzzer_enabled) { BUZZ(100, 659); BUZZ( 10, 0); BUZZ(100, 698); } else Update_Status("Success"); } - else if (eeprom_settings.beeperenable) + else if (ui.buzzer_enabled) BUZZ(40, 440); else Update_Status("Failed"); @@ -5003,7 +4994,6 @@ void CrealityDWINClass::Load_Settings(const char *buff) { void CrealityDWINClass::Reset_Settings() { eeprom_settings.time_format_textual = false; - eeprom_settings.beeperenable = true; TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = 0); eeprom_settings.corner_pos = 325; eeprom_settings.cursor_color = 0; @@ -5019,6 +5009,7 @@ void CrealityDWINClass::Reset_Settings() { eeprom_settings.coordinates_split_line = 0; TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); corner_pos = eeprom_settings.corner_pos / 10.0f; + TERN_(SOUND_MENU_ITEM, ui.buzzer_enabled = true); Redraw_Screen(); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index d6c8539cc6..92470c2f0e 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -26,10 +26,16 @@ */ #include "dwin_lcd.h" -#include "rotary_encoder.h" +#include "../common/dwin_set.h" +#include "../common/dwin_font.h" +#include "../common/dwin_color.h" +#include "../common/encoder.h" #include "../../../libs/BL24CXX.h" + #include "../../../inc/MarlinConfigPre.h" +//#define DWIN_CREALITY_LCD_CUSTOM_ICONS + enum processID : uint8_t { Main, Print, Menu, Value, Option, File, Popup, Confirm, Wait }; @@ -82,109 +88,6 @@ enum menuID : uint8_t { PreheatHotend }; -#define Start_Process 0 -#define Language_English 1 -#define Language_Chinese 2 - -#define ICON 7 // Icon set file 7.ICO - -#define ICON_LOGO 0 -#define ICON_Print_0 1 -#define ICON_Print_1 2 -#define ICON_Prepare_0 3 -#define ICON_Prepare_1 4 -#define ICON_Control_0 5 -#define ICON_Control_1 6 -#define ICON_Leveling_0 7 -#define ICON_Leveling_1 8 -#define ICON_HotendTemp 9 -#define ICON_BedTemp 10 -#define ICON_Speed 11 -#define ICON_Zoffset 12 -#define ICON_Back 13 -#define ICON_File 14 -#define ICON_PrintTime 15 -#define ICON_RemainTime 16 -#define ICON_Setup_0 17 -#define ICON_Setup_1 18 -#define ICON_Pause_0 19 -#define ICON_Pause_1 20 -#define ICON_Continue_0 21 -#define ICON_Continue_1 22 -#define ICON_Stop_0 23 -#define ICON_Stop_1 24 -#define ICON_Bar 25 -#define ICON_More 26 - -#define ICON_Axis 27 -#define ICON_CloseMotor 28 -#define ICON_Homing 29 -#define ICON_SetHome 30 -#define ICON_PLAPreheat 31 -#define ICON_ABSPreheat 32 -#define ICON_Cool 33 -#define ICON_Language 34 - -#define ICON_MoveX 35 -#define ICON_MoveY 36 -#define ICON_MoveZ 37 -#define ICON_Extruder 38 - -#define ICON_Temperature 40 -#define ICON_Motion 41 -#define ICON_WriteEEPROM 42 -#define ICON_ReadEEPROM 43 -#define ICON_ResumeEEPROM 44 -#define ICON_Info 45 - -#define ICON_SetEndTemp 46 -#define ICON_SetBedTemp 47 -#define ICON_FanSpeed 48 -#define ICON_SetPLAPreheat 49 -#define ICON_SetABSPreheat 50 - -#define ICON_MaxSpeed 51 -#define ICON_MaxAccelerated 52 -#define ICON_MaxJerk 53 -#define ICON_Step 54 -#define ICON_PrintSize 55 -#define ICON_Version 56 -#define ICON_Contact 57 -#define ICON_StockConfiguraton 58 -#define ICON_MaxSpeedX 59 -#define ICON_MaxSpeedY 60 -#define ICON_MaxSpeedZ 61 -#define ICON_MaxSpeedE 62 -#define ICON_MaxAccX 63 -#define ICON_MaxAccY 64 -#define ICON_MaxAccZ 65 -#define ICON_MaxAccE 66 -#define ICON_MaxSpeedJerkX 67 -#define ICON_MaxSpeedJerkY 68 -#define ICON_MaxSpeedJerkZ 69 -#define ICON_MaxSpeedJerkE 70 -#define ICON_StepX 71 -#define ICON_StepY 72 -#define ICON_StepZ 73 -#define ICON_StepE 74 -#define ICON_Setspeed 75 -#define ICON_SetZOffset 76 -#define ICON_Rectangle 77 -#define ICON_BLTouch 78 -#define ICON_TempTooLow 79 -#define ICON_AutoLeveling 80 -#define ICON_TempTooHigh 81 -#define ICON_NoTips_C 82 -#define ICON_NoTips_E 83 -#define ICON_Continue_C 84 -#define ICON_Continue_E 85 -#define ICON_Cancel_C 86 -#define ICON_Cancel_E 87 -#define ICON_Confirm_C 88 -#define ICON_Confirm_E 89 -#define ICON_Info_0 90 -#define ICON_Info_1 91 - // Custom icons #if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) // index of every custom icon should be >= CUSTOM_ICON_START @@ -214,25 +117,14 @@ enum menuID : uint8_t { #define ICON_AxisC ICON_Axis #endif -#define font6x12 0x00 -#define font8x16 0x01 -#define font10x20 0x02 -#define font12x24 0x03 -#define font14x28 0x04 -#define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 - enum colorID : uint8_t { Default, White, Green, Cyan, Blue, Magenta, Red, Orange, Yellow, Brown, Black }; #define Custom_Colors 10 -#define Color_White 0xFFFF +#define Color_Aqua RGB(0x00,0x3F,0x1F) #define Color_Light_White 0xBDD7 -#define Color_Green 0x07E0 +#define Color_Green RGB(0x00,0x3F,0x00) #define Color_Light_Green 0x3460 #define Color_Cyan 0x07FF #define Color_Light_Cyan 0x04F3 @@ -240,28 +132,16 @@ enum colorID : uint8_t { #define Color_Light_Blue 0x3A6A #define Color_Magenta 0xF81F #define Color_Light_Magenta 0x9813 -#define Color_Red 0xF800 #define Color_Light_Red 0x8800 #define Color_Orange 0xFA20 #define Color_Light_Orange 0xFBC0 -#define Color_Yellow 0xFF0F #define Color_Light_Yellow 0x8BE0 #define Color_Brown 0xCC27 #define Color_Light_Brown 0x6204 #define Color_Black 0x0000 #define Color_Grey 0x18E3 -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_Bg_Red 0xF00F // Red background color -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color #define Check_Color 0x4E5C // Check-box check color -#define Confirm_Color 0x34B9 +#define Confirm_Color 0x34B9 #define Cancel_Color 0x3186 class CrealityDWINClass { @@ -269,7 +149,6 @@ public: static constexpr size_t eeprom_data_size = 48; static struct EEPROM_Settings { // use bit fields to save space, max 48 bytes bool time_format_textual : 1; - bool beeperenable : 1; #if ENABLED(AUTO_BED_LEVELING_UBL) uint8_t tilt_grid_size : 3; #endif diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp index 92f4be4548..04889e92b0 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp @@ -29,185 +29,17 @@ #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) -#include "../../../inc/MarlinConfig.h" - #include "dwin_lcd.h" -#include // for memset - -//#define DEBUG_OUT 1 -#include "../../../core/debug_out.h" - -// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. -// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. -uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; -uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; -uint8_t databuf[26] = { 0 }; -uint8_t receivedType; - -int recnum = 0; - -inline void DWIN_Byte(size_t &i, const uint16_t bval) { - DWIN_SendBuf[++i] = bval; -} - -inline void DWIN_Word(size_t &i, const uint16_t wval) { - DWIN_SendBuf[++i] = wval >> 8; - DWIN_SendBuf[++i] = wval & 0xFF; -} - -inline void DWIN_Long(size_t &i, const uint32_t lval) { - DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; - DWIN_SendBuf[++i] = lval & 0xFF; -} - -inline void DWIN_String(size_t &i, const char * const string) { - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); - memcpy(&DWIN_SendBuf[i + 1], string, len); - i += len; -} - -inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { - if (!string) return; - const size_t len = strlen_P((PGM_P)string); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. - if (len == 0) return; - memcpy(&DWIN_SendBuf[i + 1], string, len); - i += len; -} - -// Send the data in the buffer and the packet end -inline void DWIN_Send(size_t &i) { - ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } -} /*-------------------------------------- System variable function --------------------------------------*/ -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void) { - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 115200 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - const millis_t serial_connect_timeout = millis() + 1000UL; - while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - - size_t i = 0; - DWIN_Byte(i, 0x00); - DWIN_Send(i); - - while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { - databuf[recnum] = LCD_SERIAL.read(); - // ignore the invalid data - if (databuf[0] != FHONE) { // prevent the program from running. - if (recnum > 0) { - recnum = 0; - ZERO(databuf); - } - continue; - } - delay(10); - recnum++; - } - - return ( recnum >= 3 - && databuf[0] == FHONE - && databuf[1] == '\0' - && databuf[2] == 'O' - && databuf[3] == 'K' ); -} - -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance) { - size_t i = 0; - DWIN_Byte(i, 0x30); - DWIN_Byte(i, luminance); - DWIN_Send(i); -} - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir) { - size_t i = 0; - DWIN_Byte(i, 0x34); - DWIN_Byte(i, 0x5A); - DWIN_Byte(i, 0xA5); - DWIN_Byte(i, dir); - DWIN_Send(i); -} - -// Update display -void DWIN_UpdateLCD(void) { - size_t i = 0; - DWIN_Byte(i, 0x3D); - DWIN_Send(i); -} +void DWIN_Startup() {} /*---------------------------------------- Drawing functions ----------------------------------------*/ -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color) { - size_t i = 0; - DWIN_Byte(i, 0x01); - DWIN_Word(i, color); - DWIN_Send(i); -} - -// Draw a point -// color: Pixel segment color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x02); - DWIN_Word(i, color); - DWIN_Byte(i, width); - DWIN_Byte(i, height); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x03); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x05); - DWIN_Byte(i, mode); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -//Color: color -//x/y: Upper-left coordinate of the first pixel +// Draw the degree (°) symbol +// Color: color +// x/y: Upper-left coordinate of the first pixel void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y) { DWIN_Draw_Point(Color, 1, 1, x + 1, y); DWIN_Draw_Point(Color, 1, 1, x + 2, y); @@ -219,256 +51,14 @@ void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y) { DWIN_Draw_Point(Color, 1, 1, x + 2, y + 3); } -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x09); - DWIN_Byte(i, (mode << 7) | dir); - DWIN_Word(i, dis); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * string) { - size_t i = 0; - DWIN_Byte(i, 0x11); - // Bit 7: widthAdjust - // Bit 6: bShow - // Bit 5-4: Unused (0) - // Bit 3-0: size - DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_String(i, string); - DWIN_Send(i); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - // Bit 7: bshow - // Bit 6: 1 = signed; 0 = unsigned number; - // Bit 5: zeroFill - // Bit 4: zeroMode - // Bit 3-0: size - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, 0); // fNum - DWIN_Word(i, x); - DWIN_Word(i, y); - #if 0 - for (char count = 0; count < 8; count++) { - DWIN_Byte(i, value); - value >>= 8; - if (!(value & 0xFF)) break; - } - #else - // Write a big-endian 64 bit integer - const size_t p = i + 1; - for (char count = 8; count--;) { // 7..0 - ++i; - DWIN_SendBuf[p + count] = value; - value >>= 8; - } - #endif - - DWIN_Send(i); -} - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - //uint8_t *fvalue = (uint8_t*)&value; - size_t i = 0; - DWIN_Byte(i, 0x14); - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, fNum); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Long(i, value); - /* - DWIN_Byte(i, fvalue[3]); - DWIN_Byte(i, fvalue[2]); - DWIN_Byte(i, fvalue[1]); - DWIN_Byte(i, fvalue[0]); - */ - DWIN_Send(i); -} - /*---------------------------------------- Picture related functions ----------------------------------------*/ -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id) { - size_t i = 0; - DWIN_Word(i, 0x2200); - DWIN_Byte(i, id); - DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C -} - // Draw an Icon // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x23); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Byte(i, 0x80 | libID); - DWIN_Byte(i, picID); - DWIN_Send(i); + DWIN_ICON_Show(true, false, false, libID, picID, x, y); } -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { - size_t i = 0; - DWIN_Byte(i, 0x25); - DWIN_Byte(i, n); - DWIN_Byte(i, id); - DWIN_Send(i); -} - -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x27); - DWIN_Byte(i, 0x80 | cacheID); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Animate a series of icons -// animID: Animation ID; 0x00-0x0F -// animate: true on; false off; -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x28); - DWIN_Word(i, x); - DWIN_Word(i, y); - // Bit 7: animation on or off - // Bit 6: start from begin or end - // Bit 5-4: unused (0) - // Bit 3-0: animID - DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); - DWIN_Byte(i, libID); - DWIN_Byte(i, picIDs); - DWIN_Byte(i, picIDe); - DWIN_Byte(i, interval); - DWIN_Send(i); -} - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state) { - size_t i = 0; - DWIN_Byte(i, 0x28); - DWIN_Word(i, state); - DWIN_Send(i); -} - -/*---------------------------------------- Memory functions ----------------------------------------*/ -// The LCD has an additional 32KB SRAM and 16KB Flash - -// Data can be written to the sram and save to one of the jpeg page files - -// Write Data Memory -// command 0x31 -// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Data: data -// -// Flash writing returns 0xA5 0x4F 0x4B - -// Read Data Memory -// command 0x32 -// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Length: leangth of data to read; 0x01-0xF0 -// -// Response: -// Type, Address, Length, Data - -// Write Picture Memory -// Write the contents of the 32KB SRAM data memory into the designated image memory space -// Issued: 0x5A, 0xA5, PIC_ID -// Response: 0xA5 0x4F 0x4B -// -// command 0x33 -// 0x5A, 0xA5 -// PicId: Picture Memory location, 0x00-0x0F -// -// Flash writing returns 0xA5 0x4F 0x4B - #endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h index 9f8bd25295..f76cfb5d3e 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -26,190 +26,9 @@ * @brief DWIN screen control functions ********************************************************************************/ -#include +#include "../common/dwin_api.h" -#define RECEIVED_NO_DATA 0x00 -#define RECEIVED_SHAKE_HAND_ACK 0x01 - -#define FHONE 0xAA - -#define DWIN_SCROLL_UP 2 -#define DWIN_SCROLL_DOWN 3 - -#define DWIN_WIDTH 272 -#define DWIN_HEIGHT 480 - -/*-------------------------------------- System variable function --------------------------------------*/ - -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void); - -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance); - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir); - -// Update display -void DWIN_UpdateLCD(void); - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color); - -// Draw a point -// color: Line segment color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a Horizontal line -// color: Line segment color -// xStart/yStart: Start point -// xLength: Line Length -inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); -} - -// Draw a Vertical line -// color: Line segment color -// xStart/yStart: Start point -// yLength: Line Length -inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a box -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xSize/ySize: box size -inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { - DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); -} - -//Color: color -//x: upper left point -//y: bottom right point +// Draw the degree (°) symbol +// Color: color +// x/y: Upper-left coordinate of the first pixel void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y); - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// widthAdjust: true=self-adjust character width; false=no adjustment -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * string); - -class __FlashStringHelper; - -inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - // Note that this won't work on AVR. This is for 32-bit systems only! - // Are __FlashStringHelper versions worth keeping? - DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, reinterpret_cast(title)); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - -/*---------------------------------------- Picture related functions ----------------------------------------*/ - -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id); - -// Draw an Icon -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); - -// Unzip the JPG picture to virtual display area #1 -// id: Picture ID -inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } - -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - -// Animate a series of icons -// animID: Animation ID up to 16 -// animate: animation on or off -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, - uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp index 97dc0eec42..ef390ac9dc 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp @@ -37,89 +37,9 @@ //#define DEBUG_OUT 1 #include "../../../core/debug_out.h" -// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. -// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. -uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; -uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; -uint8_t databuf[26] = { 0 }; -uint8_t receivedType; - -int recnum = 0; - -inline void DWIN_Byte(size_t &i, const uint16_t bval) { - DWIN_SendBuf[++i] = bval; -} - -inline void DWIN_Word(size_t &i, const uint16_t wval) { - DWIN_SendBuf[++i] = wval >> 8; - DWIN_SendBuf[++i] = wval & 0xFF; -} - -inline void DWIN_Long(size_t &i, const uint32_t lval) { - DWIN_SendBuf[++i] = (lval >> 24) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 16) & 0xFF; - DWIN_SendBuf[++i] = (lval >> 8) & 0xFF; - DWIN_SendBuf[++i] = lval & 0xFF; -} - -inline void DWIN_String(size_t &i, char * const string) { - const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { - if (!string) return; - const size_t len = strlen_P((PGM_P)string); // cast it to PGM_P, which is basically const char *, and measure it using the _P version of strlen. - if (len == 0) return; - memcpy(&DWIN_SendBuf[i+1], string, len); - i += len; -} - -// Send the data in the buffer and the packet end -inline void DWIN_Send(size_t &i) { - ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } -} - /*-------------------------------------- System variable function --------------------------------------*/ -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void) { - #ifndef LCD_BAUDRATE - #define LCD_BAUDRATE 115200 - #endif - LCD_SERIAL.begin(LCD_BAUDRATE); - const millis_t serial_connect_timeout = millis() + 1000UL; - while (!LCD_SERIAL.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - - size_t i = 0; - DWIN_Byte(i, 0x00); - DWIN_Send(i); - - while (LCD_SERIAL.available() > 0 && recnum < (signed)sizeof(databuf)) { - databuf[recnum] = LCD_SERIAL.read(); - // ignore the invalid data - if (databuf[0] != FHONE) { // prevent the program from running. - if (recnum > 0) { - recnum = 0; - ZERO(databuf); - } - continue; - } - delay(10); - recnum++; - } - - return ( recnum >= 3 - && databuf[0] == FHONE - && databuf[1] == '\0' - && databuf[2] == 'O' - && databuf[3] == 'K' ); -} - -void DWIN_Startup(void) { +void DWIN_Startup() { DEBUG_ECHOPGM("\r\nDWIN handshake "); delay(750); // Delay here or init later in the boot process const bool success = DWIN_Handshake(); @@ -129,342 +49,14 @@ void DWIN_Startup(void) { DWIN_UpdateLCD(); } -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance) { - size_t i = 0; - DWIN_Byte(i, 0x30); - DWIN_Byte(i, _MAX(luminance, 0x1F)); - DWIN_Send(i); -} - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir) { - size_t i = 0; - DWIN_Byte(i, 0x34); - DWIN_Byte(i, 0x5A); - DWIN_Byte(i, 0xA5); - DWIN_Byte(i, dir); - DWIN_Send(i); -} - -// Update display -void DWIN_UpdateLCD(void) { - size_t i = 0; - DWIN_Byte(i, 0x3D); - DWIN_Send(i); -} - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color) { - size_t i = 0; - DWIN_Byte(i, 0x01); - DWIN_Word(i, color); - DWIN_Send(i); -} - -// Draw a point -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x02); - DWIN_Word(i, color); - DWIN_Byte(i, width); - DWIN_Byte(i, height); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x03); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x05); - DWIN_Byte(i, mode); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd) { - size_t i = 0; - DWIN_Byte(i, 0x09); - DWIN_Byte(i, (mode << 7) | dir); - DWIN_Word(i, dis); - DWIN_Word(i, color); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Send(i); -} - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { - uint8_t widthAdjust = 0; - size_t i = 0; - DWIN_Byte(i, 0x11); - // Bit 7: widthAdjust - // Bit 6: bShow - // Bit 5-4: Unused (0) - // Bit 3-0: size - DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_String(i, string); - DWIN_Send(i); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { - size_t i = 0; - DWIN_Byte(i, 0x14); - // Bit 7: bshow - // Bit 6: 1 = signed; 0 = unsigned number; - // Bit 5: zeroFill - // Bit 4: zeroMode - // Bit 3-0: size - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, 0); // fNum - DWIN_Word(i, x); - DWIN_Word(i, y); - #if 0 - for (char count = 0; count < 8; count++) { - DWIN_Byte(i, value); - value >>= 8; - if (!(value & 0xFF)) break; - } - #else - // Write a big-endian 64 bit integer - const size_t p = i + 1; - for (char count = 8; count--;) { // 7..0 - ++i; - DWIN_SendBuf[p + count] = value; - value >>= 8; - } - #endif - - DWIN_Send(i); -} - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - //uint8_t *fvalue = (uint8_t*)&value; - size_t i = 0; - DWIN_Byte(i, 0x14); - DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Byte(i, iNum); - DWIN_Byte(i, fNum); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Long(i, value); - /* - DWIN_Byte(i, fvalue[3]); - DWIN_Byte(i, fvalue[2]); - DWIN_Byte(i, fvalue[1]); - DWIN_Byte(i, fvalue[0]); - */ - DWIN_Send(i); -} - /*---------------------------------------- Picture related functions ----------------------------------------*/ -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id) { - size_t i = 0; - DWIN_Word(i, 0x2200); - DWIN_Byte(i, id); - DWIN_Send(i); // AA 23 00 00 00 00 08 00 01 02 03 CC 33 C3 3C -} - // Draw an Icon // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x23); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Byte(i, 0x80 | libID); - //DWIN_Byte(i, libID); - DWIN_Byte(i, picID); - DWIN_Send(i); + DWIN_ICON_Show(true, false, false, libID, picID, x, y); } -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { - size_t i = 0; - DWIN_Byte(i, 0x25); - DWIN_Byte(i, n); - DWIN_Byte(i, id); - DWIN_Send(i); -} - -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y) { - size_t i = 0; - DWIN_Byte(i, 0x27); - DWIN_Byte(i, 0x80 | cacheID); - DWIN_Word(i, xStart); - DWIN_Word(i, yStart); - DWIN_Word(i, xEnd); - DWIN_Word(i, yEnd); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_Send(i); -} - -// Animate a series of icons -// animID: Animation ID; 0x00-0x0F -// animate: true on; false off; -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { - NOMORE(x, DWIN_WIDTH - 1); - NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl - size_t i = 0; - DWIN_Byte(i, 0x28); - DWIN_Word(i, x); - DWIN_Word(i, y); - // Bit 7: animation on or off - // Bit 6: start from begin or end - // Bit 5-4: unused (0) - // Bit 3-0: animID - DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); - DWIN_Byte(i, libID); - DWIN_Byte(i, picIDs); - DWIN_Byte(i, picIDe); - DWIN_Byte(i, interval); - DWIN_Send(i); -} - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state) { - size_t i = 0; - DWIN_Byte(i, 0x29); - DWIN_Word(i, state); - DWIN_Send(i); -} - -/*---------------------------------------- Memory functions ----------------------------------------*/ -// The LCD has an additional 32KB SRAM and 16KB Flash - -// Data can be written to the sram and save to one of the jpeg page files - -// Write Data Memory -// command 0x31 -// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Data: data -// -// Flash writing returns 0xA5 0x4F 0x4B - -// Read Data Memory -// command 0x32 -// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash -// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash -// Length: leangth of data to read; 0x01-0xF0 -// -// Response: -// Type, Address, Length, Data - -// Write Picture Memory -// Write the contents of the 32KB SRAM data memory into the designated image memory space -// Issued: 0x5A, 0xA5, PIC_ID -// Response: 0xA5 0x4F 0x4B -// -// command 0x33 -// 0x5A, 0xA5 -// PicId: Picture Memory location, 0x00-0x0F -// -// Flash writing returns 0xA5 0x4F 0x4B - #endif // IS_DWIN_MARLINUI diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h index 4d8e670e1c..753dcf47c2 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h @@ -26,82 +26,30 @@ * @brief DWIN screen control functions ********************************************************************************/ -#include - -#define RECEIVED_NO_DATA 0x00 -#define RECEIVED_SHAKE_HAND_ACK 0x01 - -#define FHONE 0xAA - -#define DWIN_SCROLL_UP 2 -#define DWIN_SCROLL_DOWN 3 - -#if DISABLED(DWIN_MARLINUI_LANDSCAPE) - #define DWIN_WIDTH 272 - #define DWIN_HEIGHT 480 -#else +#if ENABLED(DWIN_MARLINUI_LANDSCAPE) #define DWIN_WIDTH 480 #define DWIN_HEIGHT 272 #endif +#include "../common/dwin_api.h" + // Picture ID #define DWIN_Boot_Horiz 0 #define DWIN_Boot_Vert 1 #define DWIN_MarlinUI_Assets 2 -/** - * 3-.0:The font size, 0x00-0x09, corresponds to the font size below: - * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 - * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 - */ -#define font6x12 0x00 -#define font8x16 0x01 -#define font10x20 0x02 -#define font12x24 0x03 -#define font14x28 0x04 -#define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 - -#define DWIN_FONT_MENU font10x20 -#define DWIN_FONT_STAT font14x28 -#define DWIN_FONT_ALERT font14x28 - -// Color -#define Color_White 0xFFFF -#define Color_Yellow 0xFF0F -#define Color_Error_Red 0xB000 // Error! -#define Color_Bg_Red 0xF00F // Red background color -#define Color_Bg_Window 0x31E8 // Popup background color -#define Color_Bg_Heading 0x3344 // Static Heading -#define Color_Bg_Blue 0x1125 // Dark blue background color -#define Color_Bg_Black 0x0841 // Black background color -#define Color_IconBlue 0x45FA // Lighter blue that matches icons/accents -#define Popup_Text_Color 0xD6BA // Popup font background color -#define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // Blue square cursor color -#define Percent_Color 0xFE29 // Percentage color -#define BarFill_Color 0x10E4 // Fill color of progress bar -#define Select_Color 0x33BB // Selected color - -// Character matrix width x height -//#define LCD_WIDTH ((DWIN_WIDTH) / 8) -//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) - // ICON ID #define BOOT_ICON 3 // Icon set file 3.ICO #define ICON 4 // Icon set file 4.ICO -// MarlinUI Boot Icons +// MarlinUI Boot Icons from Set 3 #define ICON_MarlinBoot 0 #define ICON_OpenSource 1 #define ICON_GitHubURL 2 #define ICON_MarlinURL 3 #define ICON_Copyright 4 -// MarlinUI Icons +// MarlinUI Icons from Set 4 #define ICON_LOGO_Marlin 0 #define ICON_HotendOff 1 #define ICON_HotendOn 2 @@ -120,182 +68,16 @@ #define ICON_DownArrow 15 #define ICON_BedLine 16 -#define ICON_AdvSet ICON_Language -#define ICON_HomeOff ICON_AdvSet -#define ICON_HomeOffX ICON_StepX -#define ICON_HomeOffY ICON_StepY -#define ICON_HomeOffZ ICON_StepZ -#define ICON_ProbeOff ICON_AdvSet -#define ICON_ProbeOffX ICON_StepX -#define ICON_ProbeOffY ICON_StepY -#define ICON_PIDNozzle ICON_SetEndTemp -#define ICON_PIDbed ICON_SetBedTemp +#include "../common/dwin_font.h" -/*-------------------------------------- System variable function --------------------------------------*/ +#define DWIN_FONT_MENU font10x20 +#define DWIN_FONT_STAT font14x28 +#define DWIN_FONT_ALERT font14x28 -// Handshake (1: Success, 0: Fail) -bool DWIN_Handshake(void); +#include "../common/dwin_color.h" -// Common DWIN startup -void DWIN_Startup(void); +#define Color_Bg_Heading 0x3344 // Static Heading -// Set the backlight luminance -// luminance: (0x00-0xFF) -void DWIN_Backlight_SetLuminance(const uint8_t luminance); - -// Set screen display direction -// dir: 0=0°, 1=90°, 2=180°, 3=270° -void DWIN_Frame_SetDir(uint8_t dir); - -// Update display -void DWIN_UpdateLCD(void); - -/*---------------------------------------- Drawing functions ----------------------------------------*/ - -// Clear screen -// color: Clear screen color -void DWIN_Frame_Clear(const uint16_t color); - -// Draw a point -// color: point color -// width: point width 0x01-0x0F -// height: point height 0x01-0x0F -// x,y: upper left point -void DWIN_Draw_Point(uint16_t color, uint8_t width, uint8_t height, uint16_t x, uint16_t y); - -// Draw a line -// color: Line segment color -// xStart/yStart: Start point -// xEnd/yEnd: End point -void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a Horizontal line -// color: Line segment color -// xStart/yStart: Start point -// xLength: Line Length -inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); -} - -// Draw a Vertical line -// color: Line segment color -// xStart/yStart: Start point -// yLength: Line Length -inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { - DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); -} - -// Draw a rectangle -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xEnd/yEnd: lower right point -void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, - uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -// Draw a box -// mode: 0=frame, 1=fill, 2=XOR fill -// color: Rectangle color -// xStart/yStart: upper left point -// xSize/ySize: box size -inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { - DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); -} - -// Move a screen area -// mode: 0, circle shift; 1, translation -// dir: 0=left, 1=right, 2=up, 3=down -// dis: Distance -// color: Fill color -// xStart/yStart: upper left point -// xEnd/yEnd: bottom right point -void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, - uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - -/*---------------------------------------- Text related functions ----------------------------------------*/ - -// Draw a string -// bShow: true=display background color; false=don't display background color -// size: Font size -// color: Character color -// bColor: Background color -// x/y: Upper-left coordinate of the string -// *string: The string -void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); - -class __FlashStringHelper; - -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { - DWIN_Draw_String(bShow, size, color, bColor, x, y, (char *)title); -} - -// Draw a positive integer -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of digits -// x/y: Upper-left coordinate -// value: Integer value -void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); - -// Draw a floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// color: Character color -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, - uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); - -/*---------------------------------------- Picture related functions ----------------------------------------*/ - -// Draw JPG and cached in #0 virtual display area -// id: Picture ID -void DWIN_JPG_ShowAndCache(const uint8_t id); - -// Draw an Icon -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - -// Unzip the JPG picture to a virtual display area -// n: Cache index -// id: Picture ID -void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); - -// Unzip the JPG picture to virtual display area #1 -// id: Picture ID -inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } - -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, - uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - -// Animate a series of icons -// animID: Animation ID up to 16 -// animate: animation on or off -// libID: Icon library ID -// picIDs: Icon starting ID -// picIDe: Icon ending ID -// x/y: Upper-left point -// interval: Display time interval, unit 10mS -void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, - uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); - -// Animation Control -// state: 16 bits, each bit is the state of an animation id -void DWIN_ICON_AnimationControl(uint16_t state); +// Character matrix width x height +//#define LCD_WIDTH ((DWIN_WIDTH) / 8) +//#define LCD_HEIGHT ((DWIN_HEIGHT) / 12) diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 08566407b7..9cdea13319 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -21,12 +21,11 @@ */ #pragma once -#include - - #include "../../fontutils.h" #include "../../marlinui.h" +#include + typedef struct _dwin_charmap_t { wchar_t uchar; // the unicode char uint8_t idx; // the glyph of the char in the ROM diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 7655e059e2..45c1fa3122 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -83,7 +83,7 @@ void MarlinUI::init_lcd() { DWIN_Startup(); // Load the assets JPG (currently just the status screen 'icon') - DWIN_JPG_CacheToN(1, DWIN_MarlinUI_Assets); + DWIN_JPG_CacheTo1(DWIN_MarlinUI_Assets); } // This LCD should clear where it will draw anew @@ -545,8 +545,8 @@ void MarlinUI::draw_status_message(const bool blink) { // Show the location value dwin_string.set(Z_LBL); - if (!isnan(ubl.z_values[x_plot][y_plot])) - dwin_string.add(ftostr43sign(ubl.z_values[x_plot][y_plot])); + if (!isnan(Z_VALUES_ARR[x_plot][y_plot])) + dwin_string.add(ftostr43sign(Z_VALUES_ARR[x_plot][y_plot])); else dwin_string.add(PSTR(" -----")); lcd_moveto( diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 40f815a3e7..0fb6902e80 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -104,7 +104,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); // Set brightness on enabled LCD here TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_LCD_Brightness(brightness)); - TERN_(DWIN_CREALITY_LCD_JYERSUI, DWIN_Backlight_SetLuminance(backlight ? brightness : 0)); + TERN_(DWIN_CREALITY_LCD_JYERSUI, DWIN_LCD_Brightness(backlight ? brightness : 0)); } #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index be016f8683..49ecd89957 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -21,12 +21,11 @@ */ #pragma once -#include "../inc/MarlinConfig.h" - #include "../module/motion.h" - #include "buttons.h" +#include "../inc/MarlinConfig.h" + #if HAS_BUZZER #include "../libs/buzzer.h" #endif diff --git a/Marlin/src/sd/SdFile.h b/Marlin/src/sd/SdFile.h index 1691898899..1ff05828d2 100644 --- a/Marlin/src/sd/SdFile.h +++ b/Marlin/src/sd/SdFile.h @@ -33,7 +33,6 @@ #include "SdBaseFile.h" #include -#include /** * \class SdFile diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index 277a68411d..8ce4f57cf8 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -10,21 +10,21 @@ set -e # Build with configs included in the PR # use_example_configs "Creality/Ender-3 V2/CrealityUI" -opt_enable MARLIN_DEV_MODE BUFFER_MONITORING +opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_disable DWIN_CREALITY_LCD -opt_enable DWIN_CREALITY_LCD_ENHANCED +opt_enable DWIN_CREALITY_LCD_ENHANCED BLTOUCH AUTO_BED_LEVELING_UBL Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with Enhanced UI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityUI" opt_disable DWIN_CREALITY_LCD -opt_enable DWIN_CREALITY_LCD_JYERSUI +opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY exec_test $1 $2 "Ender 3 v2 with JyersUI" "$3" use_example_configs "Creality/Ender-3 V2/MarlinUI" -opt_add SDCARD_EEPROM_EMULATION +opt_add SDCARD_EEPROM_EMULATION NOZZLE_AS_PROBE AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" restore_configs diff --git a/ini/features.ini b/ini/features.ini index b4398378ad..949c55c06e 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -44,10 +44,11 @@ HAS_SPI_TFT = src_filter=+ SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/master.zip SPI_EEPROM = src_filter=+ +HAS_DWIN_E3V2|IS_DWIN_MARLINUI = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ DWIN_CREALITY_LCD_ENHANCED = src_filter=+ DWIN_CREALITY_LCD_JYERSUI = src_filter=+ -DWIN_MARLINUI_.+ = src_filter=+ +IS_DWIN_MARLINUI = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ HAS_TOUCH_BUTTONS = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 5e40455098..bd2a4ed21f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -50,7 +50,7 @@ lib_deps = default_src_filter = + - - + - - - - - - - - - - - - + - - - - - - - - - - - From e31d52184b321f1dbf9f091cb7188c58aef87cdb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Sep 2021 01:15:01 -0500 Subject: [PATCH 0686/2168] =?UTF-8?q?=F0=9F=8E=A8=20Handle=20more=20pre-de?= =?UTF-8?q?fined=20pins=20in=20pins=5Fpostprocess=20(#22771)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 4 - Marlin/src/inc/SanityCheck.h | 4 - Marlin/src/inc/Warnings.cpp | 457 ++++++++++++++++++ Marlin/src/pins/pins_postprocess.h | 261 +++++++--- .../PlatformIO/scripts/preflight-checks.py | 17 +- 5 files changed, 660 insertions(+), 83 deletions(-) create mode 100644 Marlin/src/inc/Warnings.cpp diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 96f6a66b0b..147853eaf9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -30,10 +30,6 @@ #include "MarlinCore.h" -#if ENABLED(MARLIN_DEV_MODE) - #warning "WARNING! Disable MARLIN_DEV_MODE for the final build!" -#endif - #include "HAL/shared/Delay.h" #include "HAL/shared/esp_wifi.h" #include "HAL/shared/cpu_exception/exception_hook.h" diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ab8b252ba6..e43e9af400 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1001,10 +1001,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif -#if !HAS_RESUME_CONTINUE && DISABLED(HOST_PROMPT_SUPPORT) && DISABLED(EXTENSIBLE_UI) - #warning "Your Configuration provides no method to acquire user feedback!" -#endif - /** * Instant Freeze */ diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp new file mode 100644 index 0000000000..aba3d94366 --- /dev/null +++ b/Marlin/src/inc/Warnings.cpp @@ -0,0 +1,457 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * Warnings.cpp + * Test configuration values and give warnings at compile-time. + */ + +#include "MarlinConfig.h" + +// +// Warnings! Located here so they will appear just once in the build output. +// + +#if ENABLED(MARLIN_DEV_MODE) + #warning "WARNING! Disable MARLIN_DEV_MODE for the final build!" +#endif + +#if NONE(HAS_RESUME_CONTINUE, HOST_PROMPT_SUPPORT) + #warning "Your Configuration provides no method to acquire user feedback!" +#endif + +#if AUTO_ASSIGNED_X2_STEPPER + #warning "Auto-assigned X2 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_X2_MS1 + #warning "Auto-assigned X2_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_X2_MS2 + #warning "Auto-assigned X2_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_X2_MS3 + #warning "Auto-assigned X2_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_X2_CS + #warning "Auto-assigned X2_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_X2_DIAG + #if X2_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned X2_DIAG_PIN to X_MIN_PIN." + #elif X2_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned X2_DIAG_PIN to X_MAX_PIN." + #elif X2_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned X2_DIAG_PIN to Y_MIN_PIN." + #elif X2_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned X2_DIAG_PIN to Y_MAX_PIN." + #elif X2_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned X2_DIAG_PIN to Z_MIN_PIN." + #elif X2_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned X2_DIAG_PIN to Z_MAX_PIN." + #elif X2_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned X2_DIAG_PIN to X_DIAG_PIN." + #elif X2_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned X2_DIAG_PIN to Y_DIAG_PIN." + #elif X2_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned X2_DIAG_PIN to Z_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E0_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E1_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E2_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E3_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E4_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E5_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E6_DIAG_PIN." + #elif X2_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned X2_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_Y2_STEPPER + #warning "Auto-assigned Y2 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_Y2_MS1 + #warning "Auto-assigned Y2_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_Y2_MS2 + #warning "Auto-assigned Y2_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_Y2_MS3 + #warning "Auto-assigned Y2_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_Y2_CS + #warning "Auto-assigned Y2_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_Y2_DIAG + #if Y2_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned Y2_DIAG_PIN to X_MIN_PIN." + #elif Y2_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned Y2_DIAG_PIN to X_MAX_PIN." + #elif Y2_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned Y2_DIAG_PIN to Y_MIN_PIN." + #elif Y2_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned Y2_DIAG_PIN to Y_MAX_PIN." + #elif Y2_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned Y2_DIAG_PIN to Z_MIN_PIN." + #elif Y2_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned Y2_DIAG_PIN to Z_MAX_PIN." + #elif Y2_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to X_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to Y_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to Z_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E0_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E1_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E2_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E3_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E4_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E5_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E6_DIAG_PIN." + #elif Y2_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned Y2_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_Z2_STEPPER + #warning "Auto-assigned Z2 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_Z2_MS1 + #warning "Auto-assigned Z2_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_Z2_MS2 + #warning "Auto-assigned Z2_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_Z2_MS3 + #warning "Auto-assigned Z2_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_Z2_CS + #warning "Auto-assigned Z2_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_Z2_DIAG + #if Z2_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned Z2_DIAG_PIN to X_MIN_PIN." + #elif Z2_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned Z2_DIAG_PIN to X_MAX_PIN." + #elif Z2_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned Z2_DIAG_PIN to Y_MIN_PIN." + #elif Z2_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned Z2_DIAG_PIN to Y_MAX_PIN." + #elif Z2_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned Z2_DIAG_PIN to Z_MIN_PIN." + #elif Z2_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned Z2_DIAG_PIN to Z_MAX_PIN." + #elif Z2_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to X_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to Y_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to Z_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E0_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E1_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E2_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E3_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E4_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E5_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E6_DIAG_PIN." + #elif Z2_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned Z2_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_Z3_STEPPER + #warning "Auto-assigned Z3 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_Z3_CS + #warning "Auto-assigned Z3_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_Z3_MS1 + #warning "Auto-assigned Z3_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_Z3_MS2 + #warning "Auto-assigned Z3_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_Z3_MS3 + #warning "Auto-assigned Z3_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_Z3_DIAG + #if Z3_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned Z3_DIAG_PIN to X_MIN_PIN." + #elif Z3_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned Z3_DIAG_PIN to X_MAX_PIN." + #elif Z3_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned Z3_DIAG_PIN to Y_MIN_PIN." + #elif Z3_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned Z3_DIAG_PIN to Y_MAX_PIN." + #elif Z3_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned Z3_DIAG_PIN to Z_MIN_PIN." + #elif Z3_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned Z3_DIAG_PIN to Z_MAX_PIN." + #elif Z3_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to X_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to Y_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to Z_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E0_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E1_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E2_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E3_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E4_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E5_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E6_DIAG_PIN." + #elif Z3_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned Z3_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_Z4_STEPPER + #warning "Auto-assigned Z4 STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_Z4_CS + #warning "Auto-assigned Z4_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_Z4_MS1 + #warning "Auto-assigned Z4_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_Z4_MS2 + #warning "Auto-assigned Z4_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_Z4_MS3 + #warning "Auto-assigned Z4_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_Z4_DIAG + #if Z4_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned Z4_DIAG_PIN to X_MIN_PIN." + #elif Z4_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned Z4_DIAG_PIN to X_MAX_PIN." + #elif Z4_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned Z4_DIAG_PIN to Y_MIN_PIN." + #elif Z4_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned Z4_DIAG_PIN to Y_MAX_PIN." + #elif Z4_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned Z4_DIAG_PIN to Z_MIN_PIN." + #elif Z4_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned Z4_DIAG_PIN to Z_MAX_PIN." + #elif Z4_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to X_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to Y_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to Z_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E0_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E1_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E2_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E3_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E4_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E5_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E6_DIAG_PIN." + #elif Z4_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned Z4_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_I_STEPPER + #warning "Auto-assigned I STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_I_CS + #warning "Auto-assigned I_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_I_MS1 + #warning "Auto-assigned I_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_I_MS2 + #warning "Auto-assigned I_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_I_MS3 + #warning "Auto-assigned I_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_I_DIAG + #if I_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned I_DIAG_PIN to X_MIN_PIN." + #elif I_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned I_DIAG_PIN to X_MAX_PIN." + #elif I_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned I_DIAG_PIN to Y_MIN_PIN." + #elif I_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned I_DIAG_PIN to Y_MAX_PIN." + #elif I_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned I_DIAG_PIN to Z_MIN_PIN." + #elif I_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned I_DIAG_PIN to Z_MAX_PIN." + #elif I_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned I_DIAG_PIN to X_DIAG_PIN." + #elif I_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned I_DIAG_PIN to Y_DIAG_PIN." + #elif I_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned I_DIAG_PIN to Z_DIAG_PIN." + #elif I_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E0_DIAG_PIN." + #elif I_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E1_DIAG_PIN." + #elif I_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E2_DIAG_PIN." + #elif I_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E3_DIAG_PIN." + #elif I_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E4_DIAG_PIN." + #elif I_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E5_DIAG_PIN." + #elif I_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E6_DIAG_PIN." + #elif I_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned I_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_J_STEPPER + #warning "Auto-assigned J STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_J_CS + #warning "Auto-assigned J_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_J_MS1 + #warning "Auto-assigned J_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_J_MS2 + #warning "Auto-assigned J_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_J_MS3 + #warning "Auto-assigned J_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_J_DIAG + #if J_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned J_DIAG_PIN to X_MIN_PIN." + #elif J_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned J_DIAG_PIN to X_MAX_PIN." + #elif J_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned J_DIAG_PIN to Y_MIN_PIN." + #elif J_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned J_DIAG_PIN to Y_MAX_PIN." + #elif J_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned J_DIAG_PIN to Z_MIN_PIN." + #elif J_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned J_DIAG_PIN to Z_MAX_PIN." + #elif J_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned J_DIAG_PIN to X_DIAG_PIN." + #elif J_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned J_DIAG_PIN to Y_DIAG_PIN." + #elif J_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned J_DIAG_PIN to Z_DIAG_PIN." + #elif J_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E0_DIAG_PIN." + #elif J_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E1_DIAG_PIN." + #elif J_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E2_DIAG_PIN." + #elif J_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E3_DIAG_PIN." + #elif J_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E4_DIAG_PIN." + #elif J_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E5_DIAG_PIN." + #elif J_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E6_DIAG_PIN." + #elif J_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned J_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif +#if AUTO_ASSIGNED_K_STEPPER + #warning "Auto-assigned K STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs." +#endif +#if AUTO_ASSIGNED_K_CS + #warning "Auto-assigned K_CS_PIN to an unused En_CS_PIN." +#endif +#if AUTO_ASSIGNED_K_MS1 + #warning "Auto-assigned K_MS1_PIN to an unused En_MS1_PIN." +#endif +#if AUTO_ASSIGNED_K_MS2 + #warning "Auto-assigned K_MS2_PIN to an unused En_MS2_PIN." +#endif +#if AUTO_ASSIGNED_K_MS3 + #warning "Auto-assigned K_MS3_PIN to an unused En_MS3_PIN." +#endif +#if AUTO_ASSIGNED_K_DIAG + #if K_USE_ENDSTOP == _XMIN_ + #warning "Auto-assigned K_DIAG_PIN to X_MIN_PIN." + #elif K_USE_ENDSTOP == _XMAX_ + #warning "Auto-assigned K_DIAG_PIN to X_MAX_PIN." + #elif K_USE_ENDSTOP == _YMIN_ + #warning "Auto-assigned K_DIAG_PIN to Y_MIN_PIN." + #elif K_USE_ENDSTOP == _YMAX_ + #warning "Auto-assigned K_DIAG_PIN to Y_MAX_PIN." + #elif K_USE_ENDSTOP == _ZMIN_ + #warning "Auto-assigned K_DIAG_PIN to Z_MIN_PIN." + #elif K_USE_ENDSTOP == _ZMAX_ + #warning "Auto-assigned K_DIAG_PIN to Z_MAX_PIN." + #elif K_USE_ENDSTOP == _XDIAG_ + #warning "Auto-assigned K_DIAG_PIN to X_DIAG_PIN." + #elif K_USE_ENDSTOP == _YDIAG_ + #warning "Auto-assigned K_DIAG_PIN to Y_DIAG_PIN." + #elif K_USE_ENDSTOP == _ZDIAG_ + #warning "Auto-assigned K_DIAG_PIN to Z_DIAG_PIN." + #elif K_USE_ENDSTOP == _E0DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E0_DIAG_PIN." + #elif K_USE_ENDSTOP == _E1DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E1_DIAG_PIN." + #elif K_USE_ENDSTOP == _E2DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E2_DIAG_PIN." + #elif K_USE_ENDSTOP == _E3DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E3_DIAG_PIN." + #elif K_USE_ENDSTOP == _E4DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E4_DIAG_PIN." + #elif K_USE_ENDSTOP == _E5DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E5_DIAG_PIN." + #elif K_USE_ENDSTOP == _E6DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E6_DIAG_PIN." + #elif K_USE_ENDSTOP == _E7DIAG_ + #warning "Auto-assigned K_DIAG_PIN to E7_DIAG_PIN." + #endif +#endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 6b5c695e85..72313cf3e6 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -542,6 +542,7 @@ #define __EPIN(p,q) E##p##_##q##_PIN #define _EPIN(p,q) __EPIN(p,q) #define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) +#define _En_DIAG_(p) _E##p##_DIAG_ // The E0/E1 steppers are always used for Dual E #if ENABLED(E_DUAL_STEPPER_DRIVERS) @@ -554,6 +555,11 @@ #endif // The X2 axis, if any, should be the next open extruder port +#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) && !defined(X2_DIAG_PIN) && !defined(X2_STEP_PIN) && !PIN_EXISTS(X2_CS_PIN) + #define Y2_E_INDEX INCREMENT(X2_E_INDEX) +#else + #define Y2_E_INDEX X2_E_INDEX +#endif #if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) #ifndef X2_STEP_PIN #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) @@ -561,19 +567,33 @@ #define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE) #if X2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(X2_STEP) #error "No E stepper plug left for X2!" + #else + #define AUTO_ASSIGNED_X2_STEPPER 1 #endif #endif #ifndef X2_MS1_PIN #define X2_MS1_PIN _EPIN(X2_E_INDEX, MS1) + #if PIN_EXISTS(X2_MS1) + #define AUTO_ASSIGNED_X2_MS1 1 + #endif #endif #ifndef X2_MS2_PIN #define X2_MS2_PIN _EPIN(X2_E_INDEX, MS2) + #if PIN_EXISTS(X2_MS2) + #define AUTO_ASSIGNED_X2_MS2 1 + #endif #endif #ifndef X2_MS3_PIN #define X2_MS3_PIN _EPIN(X2_E_INDEX, MS3) + #if PIN_EXISTS(X2_MS3) + #define AUTO_ASSIGNED_X2_MS3 1 + #endif #endif #if AXIS_HAS_SPI(X2) && !defined(X2_CS_PIN) #define X2_CS_PIN _EPIN(X2_E_INDEX, CS) + #if PIN_EXISTS(X2_CS) + #define AUTO_ASSIGNED_X2_CS 1 + #endif #endif #if AXIS_HAS_UART(X2) #ifndef X2_SERIAL_TX_PIN @@ -587,7 +607,7 @@ // // Auto-assign pins for stallGuard sensorless homing // - #if !defined(X2_USE_ENDSTOP) && defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) + #if !defined(X2_DIAG_PIN) && !defined(X2_USE_ENDSTOP) && defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... #define X2_USE_ENDSTOP _XMIN_ @@ -601,16 +621,12 @@ #define X2_USE_ENDSTOP _YMAX_ #elif DIAG_REMAPPED(X2, Z_MAX) #define X2_USE_ENDSTOP _ZMAX_ - #else // Otherwise use the driver DIAG_PIN directly - #define _X2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define X2_USE_ENDSTOP _X2_USE_ENDSTOP(X2_E_INDEX) + #else // Otherwise pick the next free En_DIAG_PIN directly + #define X2_USE_ENDSTOP _En_DIAG_(X2_E_INDEX) #endif - #undef X2_DIAG_PIN + #define AUTO_ASSIGNED_X2_DIAG 1 + #undef X2_DIAG_PIN // Defined in Conditionals_post.h based on X2_USE_ENDSTOP #endif - - #define Y2_E_INDEX INCREMENT(X2_E_INDEX) -#else - #define Y2_E_INDEX X2_E_INDEX #endif #ifndef X2_CS_PIN @@ -627,6 +643,11 @@ #endif // The Y2 axis, if any, should be the next open extruder port +#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !defined(Y2_DIAG_PIN) && !defined(Y2_STEP_PIN) && !PIN_EXISTS(Y2_CS_PIN) + #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) +#else + #define Z2_E_INDEX Y2_E_INDEX +#endif #if ENABLED(Y_DUAL_STEPPER_DRIVERS) #ifndef Y2_STEP_PIN #define Y2_STEP_PIN _EPIN(Y2_E_INDEX, STEP) @@ -634,19 +655,33 @@ #define Y2_ENABLE_PIN _EPIN(Y2_E_INDEX, ENABLE) #if Y2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Y2_STEP) #error "No E stepper plug left for Y2!" + #else + #define AUTO_ASSIGNED_Y2_STEPPER 1 #endif #endif #ifndef Y2_MS1_PIN #define Y2_MS1_PIN _EPIN(Y2_E_INDEX, MS1) + #if PIN_EXISTS(Y2_MS1) + #define AUTO_ASSIGNED_Y2_MS1 1 + #endif #endif #ifndef Y2_MS2_PIN #define Y2_MS2_PIN _EPIN(Y2_E_INDEX, MS2) + #if PIN_EXISTS(Y2_MS2) + #define AUTO_ASSIGNED_Y2_MS2 1 + #endif #endif #ifndef Y2_MS3_PIN #define Y2_MS3_PIN _EPIN(Y2_E_INDEX, MS3) + #if PIN_EXISTS(Y2_MS3) + #define AUTO_ASSIGNED_Y2_MS3 1 + #endif #endif #if AXIS_HAS_SPI(Y2) && !defined(Y2_CS_PIN) #define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS) + #if PIN_EXISTS(Y2_CS) + #define AUTO_ASSIGNED_Y2_CS 1 + #endif #endif #if AXIS_HAS_UART(Y2) #ifndef Y2_SERIAL_TX_PIN @@ -657,7 +692,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Y2_USE_ENDSTOP) && defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) + #if !defined(Y2_DIAG_PIN) && !defined(Y2_USE_ENDSTOP) && defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) #if DIAG_REMAPPED(Y2, X_MIN) #define Y2_USE_ENDSTOP _XMIN_ @@ -672,14 +707,11 @@ #elif DIAG_REMAPPED(Y2, Z_MAX) #define Y2_USE_ENDSTOP _ZMAX_ #else - #define _Y2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Y2_USE_ENDSTOP _Y2_USE_ENDSTOP(Y2_E_INDEX) + #define Y2_USE_ENDSTOP _En_DIAG_(Y2_E_INDEX) #endif - #undef Y2_DIAG_PIN + #define AUTO_ASSIGNED_Y2_DIAG 1 + #undef Y2_DIAG_PIN // Defined in Conditionals_post.h based on Y2_USE_ENDSTOP #endif - #define Z2_E_INDEX INCREMENT(Y2_E_INDEX) -#else - #define Z2_E_INDEX Y2_E_INDEX #endif #ifndef Y2_CS_PIN @@ -696,6 +728,11 @@ #endif // The Z2 axis, if any, should be the next open extruder port +#if NUM_Z_STEPPER_DRIVERS >= 2 && !defined(Z2_DIAG_PIN) && !defined(Z2_STEP_PIN) && !PIN_EXISTS(Z2_CS_PIN) + #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) +#else + #define Z3_E_INDEX Z2_E_INDEX +#endif #if NUM_Z_STEPPER_DRIVERS >= 2 #ifndef Z2_STEP_PIN #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) @@ -703,19 +740,33 @@ #define Z2_ENABLE_PIN _EPIN(Z2_E_INDEX, ENABLE) #if Z2_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z2_STEP) #error "No E stepper plug left for Z2!" + #else + #define AUTO_ASSIGNED_Z2_STEPPER 1 #endif #endif #ifndef Z2_MS1_PIN #define Z2_MS1_PIN _EPIN(Z2_E_INDEX, MS1) + #if PIN_EXISTS(Z2_MS1) + #define AUTO_ASSIGNED_Z2_MS1 1 + #endif #endif #ifndef Z2_MS2_PIN #define Z2_MS2_PIN _EPIN(Z2_E_INDEX, MS2) + #if PIN_EXISTS(Z2_MS2) + #define AUTO_ASSIGNED_Z2_MS2 1 + #endif #endif #ifndef Z2_MS3_PIN #define Z2_MS3_PIN _EPIN(Z2_E_INDEX, MS3) + #if PIN_EXISTS(Z2_MS3) + #define AUTO_ASSIGNED_Z2_MS3 1 + #endif #endif #if AXIS_HAS_SPI(Z2) && !defined(Z2_CS_PIN) #define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS) + #if PIN_EXISTS(Z2_CS) + #define AUTO_ASSIGNED_Z2_CS 1 + #endif #endif #if AXIS_HAS_UART(Z2) #ifndef Z2_SERIAL_TX_PIN @@ -726,7 +777,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + #if !defined(Z2_DIAG_PIN) && !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) #if DIAG_REMAPPED(Z2, X_MIN) #define Z2_USE_ENDSTOP _XMIN_ @@ -741,14 +792,11 @@ #elif DIAG_REMAPPED(Z2, Z_MAX) #define Z2_USE_ENDSTOP _ZMAX_ #else - #define _Z2_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z2_USE_ENDSTOP _Z2_USE_ENDSTOP(Z2_E_INDEX) + #define Z2_USE_ENDSTOP _En_DIAG_(Z2_E_INDEX) #endif - #undef Z2_DIAG_PIN + #define AUTO_ASSIGNED_Z2_DIAG 1 + #undef Z2_DIAG_PIN // Defined in Conditionals_post.h based on Z2_USE_ENDSTOP #endif - #define Z3_E_INDEX INCREMENT(Z2_E_INDEX) -#else - #define Z3_E_INDEX Z2_E_INDEX #endif #ifndef Z2_CS_PIN @@ -764,6 +812,12 @@ #define Z2_MS3_PIN -1 #endif +// The Z3 axis, if any, should be the next open extruder port +#if NUM_Z_STEPPER_DRIVERS >= 3 && !defined(Z3_DIAG_PIN) && !defined(Z3_STEP_PIN) && !PIN_EXISTS(Z3_CS_PIN) + #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) +#else + #define Z4_E_INDEX Z3_E_INDEX +#endif #if NUM_Z_STEPPER_DRIVERS >= 3 #ifndef Z3_STEP_PIN #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) @@ -771,21 +825,33 @@ #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE) #if Z3_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z3_STEP) #error "No E stepper plug left for Z3!" + #else + #define AUTO_ASSIGNED_Z3_STEPPER 1 #endif #endif - #if AXIS_HAS_SPI(Z3) - #ifndef Z3_CS_PIN - #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) + #if AXIS_HAS_SPI(Z3) && !defined(Z3_CS_PIN) + #define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS) + #if PIN_EXISTS(Z3_CS) + #define AUTO_ASSIGNED_Z3_CS 1 #endif #endif #ifndef Z3_MS1_PIN #define Z3_MS1_PIN _EPIN(Z3_E_INDEX, MS1) + #if PIN_EXISTS(Z3_MS1) + #define AUTO_ASSIGNED_Z3_MS1 1 + #endif #endif #ifndef Z3_MS2_PIN #define Z3_MS2_PIN _EPIN(Z3_E_INDEX, MS2) + #if PIN_EXISTS(Z3_MS2) + #define AUTO_ASSIGNED_Z3_MS2 1 + #endif #endif #ifndef Z3_MS3_PIN #define Z3_MS3_PIN _EPIN(Z3_E_INDEX, MS3) + #if PIN_EXISTS(Z3_MS3) + #define AUTO_ASSIGNED_Z3_MS3 1 + #endif #endif #if AXIS_HAS_UART(Z3) #ifndef Z3_SERIAL_TX_PIN @@ -796,7 +862,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + #if !defined(Z3_DIAG_PIN) && !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) #if DIAG_REMAPPED(Z3, X_MIN) #define Z3_USE_ENDSTOP _XMIN_ @@ -811,14 +877,11 @@ #elif DIAG_REMAPPED(Z3, Z_MAX) #define Z3_USE_ENDSTOP _ZMAX_ #else - #define _Z3_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z3_USE_ENDSTOP _Z3_USE_ENDSTOP(Z3_E_INDEX) + #define Z3_USE_ENDSTOP _En_DIAG_(Z3_E_INDEX) #endif - #undef Z3_DIAG_PIN + #define AUTO_ASSIGNED_Z3_DIAG 1 + #undef Z3_DIAG_PIN // Defined in Conditionals_post.h based on Z3_USE_ENDSTOP #endif - #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) -#else - #define Z4_E_INDEX Z3_E_INDEX #endif #ifndef Z3_CS_PIN @@ -834,6 +897,12 @@ #define Z3_MS3_PIN -1 #endif +// The Z4 axis, if any, should be the next open extruder port +#if NUM_Z_STEPPER_DRIVERS >= 4 && !defined(Z4_DIAG_PIN) && !defined(Z4_STEP_PIN) && !PIN_EXISTS(Z4_CS_PIN) + #define I_E_INDEX INCREMENT(Z4_E_INDEX) +#else + #define I_E_INDEX Z4_E_INDEX +#endif #if NUM_Z_STEPPER_DRIVERS >= 4 #ifndef Z4_STEP_PIN #define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP) @@ -841,21 +910,33 @@ #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE) #if Z4_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(Z4_STEP) #error "No E stepper plug left for Z4!" + #else + #define AUTO_ASSIGNED_Z4_STEPPER 1 #endif #endif - #if AXIS_HAS_SPI(Z4) - #ifndef Z4_CS_PIN - #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) + #if AXIS_HAS_SPI(Z4) && !defined(Z4_CS_PIN) + #define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS) + #if PIN_EXISTS(Z4_CS) + #define AUTO_ASSIGNED_Z4_CS 1 #endif #endif #ifndef Z4_MS1_PIN #define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1) + #if PIN_EXISTS(Z4_MS1) + #define AUTO_ASSIGNED_Z4_MS1 1 + #endif #endif #ifndef Z4_MS2_PIN #define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2) + #if PIN_EXISTS(Z4_MS2) + #define AUTO_ASSIGNED_Z4_MS2 1 + #endif #endif #ifndef Z4_MS3_PIN #define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3) + #if PIN_EXISTS(Z4_MS3) + #define AUTO_ASSIGNED_Z4_MS3 1 + #endif #endif #if AXIS_HAS_UART(Z4) #ifndef Z4_SERIAL_TX_PIN @@ -866,7 +947,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + #if !defined(Z4_DIAG_PIN) && !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) #if DIAG_REMAPPED(Z4, X_MIN) #define Z4_USE_ENDSTOP _XMIN_ @@ -881,14 +962,11 @@ #elif DIAG_REMAPPED(Z4, Z_MAX) #define Z4_USE_ENDSTOP _ZMAX_ #else - #define _Z4_USE_ENDSTOP(P) _E##P##_DIAG_ - #define Z4_USE_ENDSTOP _Z4_USE_ENDSTOP(Z4_E_INDEX) + #define Z4_USE_ENDSTOP _En_DIAG_(Z4_E_INDEX) #endif - #undef Z4_DIAG_PIN + #define AUTO_ASSIGNED_Z4_DIAG 1 + #undef Z4_DIAG_PIN // Defined in Conditionals_post.h based on Z4_USE_ENDSTOP #endif - #define I_E_INDEX INCREMENT(Z4_E_INDEX) -#else - #define I_E_INDEX Z4_E_INDEX #endif #ifndef Z4_CS_PIN @@ -904,6 +982,12 @@ #define Z4_MS3_PIN -1 #endif +// The I axis, if any, should be the next open extruder port +#if LINEAR_AXES >= 4 && !defined(I_DIAG_PIN) && !defined(I_STEP_PIN) && !PIN_EXISTS(I_CS_PIN) + #define J_E_INDEX INCREMENT(I_E_INDEX) +#else + #define J_E_INDEX I_E_INDEX +#endif #if LINEAR_AXES >= 4 #ifndef I_STEP_PIN #define I_STEP_PIN _EPIN(I_E_INDEX, STEP) @@ -911,21 +995,33 @@ #define I_ENABLE_PIN _EPIN(I_E_INDEX, ENABLE) #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(I_STEP) #error "No E stepper plug left for I!" + #else + #define AUTO_ASSIGNED_I_STEPPER 1 #endif #endif - #if AXIS_HAS_SPI(I) - #ifndef I_CS_PIN - #define I_CS_PIN _EPIN(I_E_INDEX, CS) + #if AXIS_HAS_SPI(I) && !defined(I_CS_PIN) + #define I_CS_PIN _EPIN(I_E_INDEX, CS) + #if PIN_EXISTS(I_CS) + #define AUTO_ASSIGNED_I_CS 1 #endif #endif #ifndef I_MS1_PIN #define I_MS1_PIN _EPIN(I_E_INDEX, MS1) + #if PIN_EXISTS(I_MS1) + #define AUTO_ASSIGNED_I_MS1 1 + #endif #endif #ifndef I_MS2_PIN #define I_MS2_PIN _EPIN(I_E_INDEX, MS2) + #if PIN_EXISTS(I_MS2) + #define AUTO_ASSIGNED_I_MS2 1 + #endif #endif #ifndef I_MS3_PIN #define I_MS3_PIN _EPIN(I_E_INDEX, MS3) + #if PIN_EXISTS(I_MS3) + #define AUTO_ASSIGNED_I_MS3 1 + #endif #endif #if AXIS_HAS_UART(I) #ifndef I_SERIAL_TX_PIN @@ -936,7 +1032,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(I_USE_ENDSTOP) && defined(I_STALL_SENSITIVITY) && _PEXI(I_E_INDEX, DIAG) + #if !defined(I_DIAG_PIN) && !defined(I_USE_ENDSTOP) && defined(I_STALL_SENSITIVITY) && _PEXI(I_E_INDEX, DIAG) #define I_DIAG_PIN _EPIN(I_E_INDEX, DIAG) #if DIAG_REMAPPED(I, X_MIN) #define I_USE_ENDSTOP _XMIN_ @@ -951,14 +1047,11 @@ #elif DIAG_REMAPPED(I, Z_MAX) #define I_USE_ENDSTOP _ZMAX_ #else - #define _I_USE_ENDSTOP(P) _E##P##_DIAG_ - #define I_USE_ENDSTOP _I_USE_ENDSTOP(I_E_INDEX) + #define I_USE_ENDSTOP _En_DIAG_(I_E_INDEX) #endif - #undef I_DIAG_PIN + #define AUTO_ASSIGNED_I_DIAG 1 + #undef I_DIAG_PIN // Defined in Conditionals_post.h based on I_USE_ENDSTOP #endif - #define J_E_INDEX INCREMENT(I_E_INDEX) -#else - #define J_E_INDEX I_E_INDEX #endif #ifndef I_CS_PIN @@ -974,6 +1067,12 @@ #define I_MS3_PIN -1 #endif +// The J axis, if any, should be the next open extruder port +#if LINEAR_AXES >= 5 && !defined(J_DIAG_PIN) && !defined(J_STEP_PIN) && !PIN_EXISTS(J_CS_PIN) + #define K_E_INDEX INCREMENT(J_E_INDEX) +#else + #define K_E_INDEX J_E_INDEX +#endif #if LINEAR_AXES >= 5 #ifndef J_STEP_PIN #define J_STEP_PIN _EPIN(J_E_INDEX, STEP) @@ -981,21 +1080,33 @@ #define J_ENABLE_PIN _EPIN(J_E_INDEX, ENABLE) #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(J_STEP) #error "No E stepper plug left for J!" + #else + #define AUTO_ASSIGNED_J_STEPPER 1 #endif #endif - #if AXIS_HAS_SPI(J) - #ifndef J_CS_PIN - #define J_CS_PIN _EPIN(J_E_INDEX, CS) + #if AXIS_HAS_SPI(J) && !defined(J_CS_PIN) + #define J_CS_PIN _EPIN(J_E_INDEX, CS) + #if PIN_EXISTS(J_CS) + #define AUTO_ASSIGNED_J_CS 1 #endif #endif #ifndef J_MS1_PIN #define J_MS1_PIN _EPIN(J_E_INDEX, MS1) + #if PIN_EXISTS(J_MS1) + #define AUTO_ASSIGNED_J_MS1 1 + #endif #endif #ifndef J_MS2_PIN #define J_MS2_PIN _EPIN(J_E_INDEX, MS2) + #if PIN_EXISTS(J_MS2) + #define AUTO_ASSIGNED_J_MS2 1 + #endif #endif #ifndef J_MS3_PIN #define J_MS3_PIN _EPIN(J_E_INDEX, MS3) + #if PIN_EXISTS(J_MS3) + #define AUTO_ASSIGNED_J_MS3 1 + #endif #endif #if AXIS_HAS_UART(J) #ifndef J_SERIAL_TX_PIN @@ -1006,7 +1117,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(J_USE_ENDSTOP) && defined(J_STALL_SENSITIVITY) && _PEXI(J_E_INDEX, DIAG) + #if !defined(J_DIAG_PIN) && !defined(J_USE_ENDSTOP) && defined(J_STALL_SENSITIVITY) && _PEXI(J_E_INDEX, DIAG) #define J_DIAG_PIN _EPIN(J_E_INDEX, DIAG) #if DIAG_REMAPPED(J, X_MIN) #define J_USE_ENDSTOP _XMIN_ @@ -1021,14 +1132,11 @@ #elif DIAG_REMAPPED(I, Z_MAX) #define J_USE_ENDSTOP _ZMAX_ #else - #define _J_USE_ENDSTOP(P) _E##P##_DIAG_ - #define J_USE_ENDSTOP _J_USE_ENDSTOP(J_E_INDEX) + #define J_USE_ENDSTOP _En_DIAG_(J_E_INDEX) #endif - #undef J_DIAG_PIN + #define AUTO_ASSIGNED_J_DIAG 1 + #undef J_DIAG_PIN // Defined in Conditionals_post.h based on J_USE_ENDSTOP #endif - #define K_E_INDEX INCREMENT(J_E_INDEX) -#else - #define K_E_INDEX J_E_INDEX #endif #ifndef J_CS_PIN @@ -1044,6 +1152,7 @@ #define J_MS3_PIN -1 #endif +// The K axis, if any, should be the next open extruder port #if LINEAR_AXES >= 6 #ifndef K_STEP_PIN #define K_STEP_PIN _EPIN(K_E_INDEX, STEP) @@ -1051,21 +1160,33 @@ #define K_ENABLE_PIN _EPIN(K_E_INDEX, ENABLE) #if K_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(K_STEP) #error "No E stepper plug left for K!" + #else + #define AUTO_ASSIGNED_K_STEPPER 1 #endif #endif - #if AXIS_HAS_SPI(K) - #ifndef K_CS_PIN - #define K_CS_PIN _EPIN(K_E_INDEX, CS) + #if AXIS_HAS_SPI(K) && !defined(K_CS_PIN) + #define K_CS_PIN _EPIN(K_E_INDEX, CS) + #if PIN_EXISTS(K_CS) + #define AUTO_ASSIGNED_K_CS 1 #endif #endif #ifndef K_MS1_PIN #define K_MS1_PIN _EPIN(K_E_INDEX, MS1) + #if PIN_EXISTS(K_MS1) + #define AUTO_ASSIGNED_K_MS1 1 + #endif #endif #ifndef K_MS2_PIN #define K_MS2_PIN _EPIN(K_E_INDEX, MS2) + #if PIN_EXISTS(K_MS2) + #define AUTO_ASSIGNED_K_MS2 1 + #endif #endif #ifndef K_MS3_PIN #define K_MS3_PIN _EPIN(K_E_INDEX, MS3) + #if PIN_EXISTS(K_MS3) + #define AUTO_ASSIGNED_K_MS3 1 + #endif #endif #if AXIS_HAS_UART(K) #ifndef K_SERIAL_TX_PIN @@ -1076,7 +1197,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(K_USE_ENDSTOP) && defined(K_STALL_SENSITIVITY) && _PEXI(K_E_INDEX, DIAG) + #if !defined(K_DIAG_PIN) && !defined(K_USE_ENDSTOP) && defined(K_STALL_SENSITIVITY) && _PEXI(K_E_INDEX, DIAG) #define K_DIAG_PIN _EPIN(K_E_INDEX, DIAG) #if DIAG_REMAPPED(K, X_MIN) #define K_USE_ENDSTOP _XMIN_ @@ -1091,10 +1212,10 @@ #elif DIAG_REMAPPED(K, Z_MAX) #define K_USE_ENDSTOP _ZMAX_ #else - #define _K_USE_ENDSTOP(P) _E##P##_DIAG_ - #define K_USE_ENDSTOP _K_USE_ENDSTOP(K_E_INDEX) + #define K_USE_ENDSTOP _En_DIAG_(K_E_INDEX) #endif - #undef K_DIAG_PIN + #define AUTO_ASSIGNED_K_DIAG 1 + #undef K_DIAG_PIN // Defined in Conditionals_post.h based on K_USE_ENDSTOP #endif #endif diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 27e5c9d70a..b949df97c8 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -75,14 +75,21 @@ def sanity_check_target(): err = "ERROR: Config files found in directory %s. Please move them into the Marlin subfolder." % p raise SystemExit(err) + # + # Give warnings on every build + # + warnfile = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src", "inc", "Warnings.cpp.o") + if os.path.exists(warnfile): + os.remove(warnfile) + # # Check for old files indicating an entangled Marlin (mixing old and new code) # mixedin = [] - for p in [ os.path.join(env['PROJECT_DIR'], "Marlin/src/lcd/dogm") ]: - for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: - if os.path.isfile(os.path.join(p, f)): - mixedin += [ f ] + p = os.path.join(env['PROJECT_DIR'], "Marlin", "src", "lcd", "dogm") + for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: + if os.path.isfile(os.path.join(p, f)): + mixedin += [ f ] if mixedin: err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) raise SystemExit(err) @@ -90,4 +97,4 @@ def sanity_check_target(): # Detect that 'vscode init' is running from SCons.Script import COMMAND_LINE_TARGETS if "idedata" not in COMMAND_LINE_TARGETS: - sanity_check_target() + sanity_check_target() From 0cc17b920ae9c804d5b9b2c95325e959c6f4eea5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 16 Sep 2021 01:03:27 +0000 Subject: [PATCH 0687/2168] [cron] Bump distribution date (2021-09-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 12ec86b460..2e2dc18701 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-15" +//#define STRING_DISTRIBUTION_DATE "2021-09-16" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6dec849a4e..119617e59e 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 "2021-09-15" + #define STRING_DISTRIBUTION_DATE "2021-09-16" #endif /** From 02ae11ed72724a0f0a670069fe6b93933031de8b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 15 Sep 2021 21:12:39 -0500 Subject: [PATCH 0688/2168] =?UTF-8?q?=F0=9F=94=A7=20Add=20MANUAL=5FFEEDRAT?= =?UTF-8?q?E=20sanity-check?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 82 ++++++++++++++---------------------- 1 file changed, 32 insertions(+), 50 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index e43e9af400..9c1948157f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3282,9 +3282,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, sanity_arr_2[] = DEFAULT_MAX_FEEDRATE, sanity_arr_3[] = DEFAULT_MAX_ACCELERATION, - sanity_arr_7[] = HOMING_FEEDRATE_MM_M; + sanity_arr_4[] = HOMING_FEEDRATE_MM_M; -#define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0) +#define __PLUS_TEST(I,A) && (sanity_arr_##A[_MIN(I,signed(COUNT(sanity_arr_##A)-1))] > 0) +#define _PLUS_TEST(A) (1 REPEAT2(14,__PLUS_TEST,A)) #if HAS_MULTI_EXTRUDER #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" #else @@ -3293,68 +3294,49 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); -static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) - && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) - && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), - "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); +static_assert(_PLUS_TEST(1), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); -static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) - && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) - && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), - "DEFAULT_MAX_FEEDRATE values must be positive."); +static_assert(_PLUS_TEST(2), "DEFAULT_MAX_FEEDRATE values must be positive."); static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); -static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) - && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) - && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), - "DEFAULT_MAX_ACCELERATION values must be positive."); +static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."); -static_assert(COUNT(sanity_arr_7) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); -static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) - && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) - && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), - "HOMING_FEEDRATE_MM_M values must be positive."); +static_assert(COUNT(sanity_arr_4) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); +static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); -#if ENABLED(LIMITED_MAX_ACCEL_EDITING) - #ifdef MAX_ACCEL_EDIT_VALUES - constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES; - static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); - static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); - static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2) - && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5) - && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8), - "MAX_ACCEL_EDIT_VALUES values must be positive."); - #endif +#ifdef MAX_ACCEL_EDIT_VALUES + constexpr float sanity_arr_5[] = MAX_ACCEL_EDIT_VALUES; + static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); + static_assert(_PLUS_TEST(5), "MAX_ACCEL_EDIT_VALUES values must be positive."); #endif -#if ENABLED(LIMITED_MAX_FR_EDITING) - #ifdef MAX_FEEDRATE_EDIT_VALUES - constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES; - static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); - static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); - static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2) - && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5) - && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8), - "MAX_FEEDRATE_EDIT_VALUES values must be positive."); - #endif +#ifdef MAX_FEEDRATE_EDIT_VALUES + constexpr float sanity_arr_6[] = MAX_FEEDRATE_EDIT_VALUES; + static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); + static_assert(_PLUS_TEST(6), "MAX_FEEDRATE_EDIT_VALUES values must be positive."); #endif -#if ENABLED(LIMITED_JERK_EDITING) - #ifdef MAX_JERK_EDIT_VALUES - constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES; - static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); - static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); - static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2) - && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5) - && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8), - "MAX_JERK_EDIT_VALUES values must be positive."); - #endif +#ifdef MAX_JERK_EDIT_VALUES + constexpr float sanity_arr_7[] = MAX_JERK_EDIT_VALUES; + static_assert(COUNT(sanity_arr_7) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_7) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); + static_assert(_PLUS_TEST(7), "MAX_JERK_EDIT_VALUES values must be positive."); #endif -#undef _ARR_TEST +#ifdef MANUAL_FEEDRATE + constexpr float sanity_arr_8[] = MANUAL_FEEDRATE; + static_assert(COUNT(sanity_arr_8) >= LOGICAL_AXES, "MANUAL_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_8) <= LOGICAL_AXES, "MANUAL_FEEDRATE has too many elements. " _LOGICAL_AXES_STR "elements only."); + static_assert(_PLUS_TEST(8), "MANUAL_FEEDRATE values must be positive."); +#endif + +#undef __PLUS_TEST +#undef _PLUS_TEST #undef _EXTRA_NOTE #if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) From 08a40c43750eb49521849792520d8d819c0fcd29 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Thu, 16 Sep 2021 03:46:16 -0400 Subject: [PATCH 0689/2168] =?UTF-8?q?=E2=9C=A8=20Improve=20pause/filament?= =?UTF-8?q?=20change=20for=20ExtUI=20(#22655)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 ++ Marlin/src/feature/pause.cpp | 16 ++++++++++++---- Marlin/src/lcd/extui/ui_api.cpp | 2 ++ Marlin/src/lcd/extui/ui_api.h | 2 ++ Marlin/src/lcd/marlinui.cpp | 9 ++------- buildroot/tests/BIGTREE_GTR_V1_0 | 7 ++++--- 6 files changed, 24 insertions(+), 14 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 622251c35a..6e44f009ed 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2425,6 +2425,8 @@ #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety. #define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed. #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change. + //#define FILAMENT_CHANGE_RESUME_ON_INSERT // Automatically continue / load filament when runout sensor is triggered again. + //#define PAUSE_REHEAT_FAST_RESUME // Reduce number of waits by not prompting again post-timeout before continuing. //#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change. //#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index f9e3d1b9c2..6dfd19a3a0 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -203,6 +203,16 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load while (wait_for_user) { impatient_beep(max_beep_count); + #if BOTH(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) + #if ENABLED(MULTI_FILAMENT_SENSOR) + #define _CASE_INSERTED(N) case N-1: if (READ(FIL_RUNOUT##N##_PIN) != FIL_RUNOUT##N##_STATE) wait_for_user = false; break; + switch (active_extruder) { + REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _CASE_INSERTED) + } + #else + if (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE) wait_for_user = false; + #endif + #endif idle_no_sleep(); } } @@ -545,14 +555,12 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status_P(GET_TEXT(MSG_REHEATDONE))); - wait_for_user = true; - nozzle_timed_out = false; + IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); + nozzle_timed_out = false; first_impatient_beep(max_beep_count); } idle_no_sleep(); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 4ef96251bc..b838299b18 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1037,6 +1037,8 @@ namespace ExtUI { #if M600_PURGE_MORE_RESUMABLE void setPauseMenuResponse(PauseMenuResponse response) { pause_menu_response = response; } + PauseMessage pauseModeStatus = PAUSE_MESSAGE_STATUS; + PauseMode getPauseMode() { return pause_mode;} #endif void printFile(const char *filename) { diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 59759319be..9e1ae3a9c0 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -234,6 +234,8 @@ namespace ExtUI { #if M600_PURGE_MORE_RESUMABLE void setPauseMenuResponse(PauseMenuResponse); + extern PauseMessage pauseModeStatus; + PauseMode getPauseMode(); #endif #if ENABLED(LIN_ADVANCE) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 0fb6902e80..369413d3a6 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1716,9 +1716,8 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/ ) { - if (mode == PAUSE_MODE_SAME) - return; pause_mode = mode; + ExtUI::pauseModeStatus = message; switch (message) { case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); @@ -1727,11 +1726,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); case PAUSE_MESSAGE_PURGE: - #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_CONT_PURGE)); - #else - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); - #endif + ExtUI::onUserConfirmRequired_P(GET_TEXT(TERN(ADVANCED_PAUSE_CONTINUOUS_PURGE, MSG_FILAMENT_CHANGE_CONT_PURGE, MSG_FILAMENT_CHANGE_PURGE))); case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT)); case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 index 58cbe4a142..0a80a6b78c 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0 +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -12,10 +12,11 @@ opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ # Not necessary to enable auto-fan for all extruders to hit problematic code paths opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 \ - FIL_RUNOUT_PIN 3 FIL_RUNOUT2_PIN 4 FIL_RUNOUT3_PIN 5 FIL_RUNOUT4_PIN 6 FIL_RUNOUT5_PIN 7 FIL_RUNOUT6_PIN 8 FIL_RUNOUT7_PIN 9 FIL_RUNOUT8_PIN 10 \ - FIL_RUNOUT4_STATE HIGH FIL_RUNOUT8_STATE HIGH + NUM_RUNOUT_SENSORS 8 FIL_RUNOUT_PIN 3 FIL_RUNOUT2_PIN 4 FIL_RUNOUT3_PIN 5 FIL_RUNOUT4_PIN 6 FIL_RUNOUT5_PIN 7 \ + FIL_RUNOUT6_PIN 8 FIL_RUNOUT7_PIN 9 FIL_RUNOUT8_PIN 10 FIL_RUNOUT4_STATE HIGH FIL_RUNOUT8_STATE HIGH \ + FILAMENT_RUNOUT_SCRIPT '"M600 T%c"' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH NEOPIXEL_LED Z_SAFE_HOMING NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE \ - FILAMENT_RUNOUT_SENSOR FIL_RUNOUT4_PULLUP FIL_RUNOUT8_PULLUP + FILAMENT_RUNOUT_SENSOR FIL_RUNOUT4_PULLUP FIL_RUNOUT8_PULLUP FILAMENT_CHANGE_RESUME_ON_INSERT PAUSE_REHEAT_FAST_RESUME exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | Runout Sensors w/ distinct states" "$3" restore_configs From 323b38ee88dbf2a4691a20439dbb95a824822199 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 16 Sep 2021 04:36:26 -0500 Subject: [PATCH 0690/2168] =?UTF-8?q?=F0=9F=92=A1=20Adjust=20headers,=20fo?= =?UTF-8?q?rmatting?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/pinsDebug.h | 3 +++ Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h | 3 +++ Marlin/src/HAL/AVR/pinsDebug_plus_70.h | 3 +++ .../dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp | 1 - Marlin/src/HAL/DUE/pinsDebug.h | 3 +++ Marlin/src/HAL/ESP32/spi_pins.h | 3 +++ Marlin/src/HAL/LINUX/main.cpp | 4 ++++ Marlin/src/HAL/LINUX/pinsDebug.h | 3 +++ Marlin/src/HAL/LPC1768/pinsDebug.h | 3 +++ Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 1 - Marlin/src/HAL/SAMD51/QSPIFlash.h | 1 - Marlin/src/HAL/STM32/MarlinSPI.cpp | 1 + Marlin/src/HAL/STM32/MarlinSerial.cpp | 4 ++++ Marlin/src/HAL/STM32/MarlinSerial.h | 3 +++ .../src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 1 + Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp | 1 + Marlin/src/HAL/STM32/eeprom_if_iic.cpp | 1 + Marlin/src/HAL/STM32/eeprom_sdcard.cpp | 1 + Marlin/src/HAL/STM32/fast_pwm.cpp | 1 + Marlin/src/HAL/STM32/pinsDebug.h | 3 +++ Marlin/src/HAL/STM32/spi_pins.h | 3 +++ Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 1 + Marlin/src/HAL/STM32/tft/tft_spi.cpp | 1 + Marlin/src/HAL/STM32/tft/xpt2046.cpp | 1 + Marlin/src/HAL/STM32/usb_host.cpp | 1 + Marlin/src/HAL/STM32/usb_serial.cpp | 4 ++++ Marlin/src/HAL/STM32/usb_serial.h | 3 +++ Marlin/src/HAL/STM32/watchdog.cpp | 1 + .../STM32F1/dogm/u8g_com_stm32duino_swspi.cpp | 4 ++++ Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 3 +++ Marlin/src/HAL/STM32F1/pinsDebug.h | 3 +++ Marlin/src/HAL/STM32F1/spi_pins.h | 3 +++ Marlin/src/HAL/TEENSY31_32/eeprom.cpp | 4 ++++ Marlin/src/HAL/TEENSY35_36/pinsDebug.h | 3 +++ Marlin/src/HAL/TEENSY40_41/pinsDebug.h | 3 +++ Marlin/src/HAL/shared/Delay.cpp | 1 + .../src/feature/bedlevel/ubl/ubl_motion.cpp | 1 + Marlin/src/feature/cancel_object.cpp | 1 + Marlin/src/feature/closedloop.cpp | 1 + Marlin/src/feature/direct_stepping.cpp | 1 + Marlin/src/feature/repeat.cpp | 1 + Marlin/src/gcode/calibrate/M12.cpp | 1 + Marlin/src/gcode/config/M281.cpp | 1 + Marlin/src/gcode/feature/pause/G27.cpp | 1 - Marlin/src/gcode/gcode_d.cpp | 1 + Marlin/src/gcode/host/M360.cpp | 1 + Marlin/src/gcode/host/M876.cpp | 1 + Marlin/src/gcode/lcd/M250.cpp | 1 + Marlin/src/gcode/motion/G6.cpp | 1 + Marlin/src/inc/SanityCheck.h | 8 +++---- Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp | 22 +++++++++++++++++++ .../lcd/dogm/fontdata/fontdata_ISO10646_1.h | 4 ++++ Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp | 1 + .../extui/anycubic_chiron/chiron_tft_defs.h | 2 +- .../lcd/extui/dgus_reloaded/DGUSRxHandler.h | 1 - .../extui/dgus_reloaded/DGUSScreenHandler.h | 1 - .../extui/dgus_reloaded/DGUSSetupHandler.h | 1 - .../lcd/extui/dgus_reloaded/DGUSTxHandler.h | 1 - .../bioprinter/ui_landscape.h | 1 - .../bioprinter/ui_portrait.h | 1 - .../cocoa_press/cocoa_press_ui.h | 1 - .../generic/custom_user_menus.h | 1 - .../theme/bootscreen_logo_portrait.h | 1 - .../theme/marlin_bootscreen_landscape.h | 1 - .../theme/marlin_bootscreen_portrait.h | 1 - Marlin/src/lcd/extui/mks_ui/draw_about.cpp | 1 + .../mks_ui/draw_acceleration_settings.cpp | 1 + .../extui/mks_ui/draw_advance_settings.cpp | 1 + .../draw_auto_level_offset_settings.cpp | 1 + .../lcd/extui/mks_ui/draw_baby_stepping.cpp | 1 + .../lcd/extui/mks_ui/draw_change_speed.cpp | 1 + .../src/lcd/extui/mks_ui/draw_cloud_bind.cpp | 1 + .../lcd/extui/mks_ui/draw_eeprom_settings.cpp | 1 + .../extui/mks_ui/draw_encoder_settings.cpp | 1 + .../lcd/extui/mks_ui/draw_error_message.cpp | 1 + .../src/lcd/extui/mks_ui/draw_extrusion.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_fan.cpp | 1 + .../lcd/extui/mks_ui/draw_filament_change.cpp | 1 + .../extui/mks_ui/draw_filament_settings.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_home.cpp | 1 + .../draw_homing_sensitivity_settings.cpp | 1 + .../lcd/extui/mks_ui/draw_jerk_settings.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_language.cpp | 1 + .../lcd/extui/mks_ui/draw_level_settings.cpp | 1 + .../lcd/extui/mks_ui/draw_machine_para.cpp | 1 + .../extui/mks_ui/draw_machine_settings.cpp | 1 + .../src/lcd/extui/mks_ui/draw_manuaLevel.cpp | 1 + .../mks_ui/draw_max_feedrate_settings.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_more.cpp | 1 + .../lcd/extui/mks_ui/draw_motor_settings.cpp | 1 + .../src/lcd/extui/mks_ui/draw_move_motor.cpp | 1 + .../src/lcd/extui/mks_ui/draw_number_key.cpp | 1 + .../src/lcd/extui/mks_ui/draw_operation.cpp | 1 + .../lcd/extui/mks_ui/draw_pause_message.cpp | 1 + .../lcd/extui/mks_ui/draw_pause_position.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 1 + .../src/lcd/extui/mks_ui/draw_print_file.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 1 + .../src/lcd/extui/mks_ui/draw_ready_print.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_set.cpp | 1 + .../lcd/extui/mks_ui/draw_step_settings.cpp | 1 + .../mks_ui/draw_tmc_current_settings.cpp | 1 + .../mks_ui/draw_tmc_step_mode_settings.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_tool.cpp | 1 + .../extui/mks_ui/draw_touch_calibration.cpp | 1 + .../mks_ui/draw_tramming_pos_settings.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 1 + Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp | 1 + .../src/lcd/extui/mks_ui/draw_wifi_list.cpp | 1 + .../lcd/extui/mks_ui/draw_wifi_settings.cpp | 1 + .../src/lcd/extui/mks_ui/draw_wifi_tips.cpp | 1 + .../src/lcd/extui/mks_ui/gb2312_puhui16.cpp | 1 + Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 1 + Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 1 + .../lcd/extui/mks_ui/printer_operation.cpp | 1 + .../extui/mks_ui/tft_lvgl_configuration.cpp | 1 + .../lcd/extui/mks_ui/tft_multi_language.cpp | 1 + Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 1 + Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 1 + Marlin/src/lcd/fontutils.cpp | 22 +++++++++++++++++++ Marlin/src/lcd/fontutils.h | 22 +++++++++++++++++++ Marlin/src/lcd/tft_io/touch_calibration.cpp | 3 +++ Marlin/src/lcd/tft_io/touch_calibration.h | 3 +++ Marlin/src/lcd/touch/touch_buttons.cpp | 3 +++ Marlin/src/lcd/touch/touch_buttons.h | 3 +++ Marlin/src/libs/BL24CXX.cpp | 3 +++ Marlin/src/module/thermistor/thermistor_99.h | 1 - Marlin/src/pins/pinsDebug.h | 7 ++++-- Marlin/src/pins/pinsDebug_list.h | 7 +++--- Marlin/src/pins/sanguino/pins_MELZI_V2.h | 3 +++ Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h | 1 - Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 1 - Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 3 +++ Marlin/src/pins/stm32f4/pins_ANET_ET4.h | 1 - Marlin/src/pins/stm32f4/pins_ANET_ET4P.h | 1 - Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 3 +++ Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 3 +++ Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 3 +++ Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h | 3 +-- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 3 +-- .../variants/MARLIN_FLY_F407ZG/variant.h | 1 - .../variants/MARLIN_LERDGE/variant.h | 1 - buildroot/share/fonts/genallfont.sh | 4 ++++ 145 files changed, 269 insertions(+), 36 deletions(-) diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 5fc48a1edc..fcbb7af3e1 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h index 051972a861..582ae79ba7 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h +++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h index db3fdf1f76..d9aa44c3cb 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h +++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/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 index fcfcef88be..68f6a5c1a7 100644 --- a/Marlin/src/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 @@ -20,7 +20,6 @@ * */ - /** * Based on u8g_com_msp430_hw_spi.c * diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index 225ba95ce9..f01c53c8ce 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/ESP32/spi_pins.h b/Marlin/src/HAL/ESP32/spi_pins.h index cfe71eee4a..58881f0ea7 100644 --- a/Marlin/src/HAL/ESP32/spi_pins.h +++ b/Marlin/src/HAL/ESP32/spi_pins.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp index 31f6de98ee..f2af2ff33f 100644 --- a/Marlin/src/HAL/LINUX/main.cpp +++ b/Marlin/src/HAL/LINUX/main.cpp @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __PLAT_LINUX__ //#define GPIO_LOGGING // Full GPIO and Positional Logging diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h index 9803c5d362..7bfd97d024 100644 --- a/Marlin/src/HAL/LINUX/pinsDebug.h +++ b/Marlin/src/HAL/LINUX/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h index 466bf170b4..a2f5c123a2 100644 --- a/Marlin/src/HAL/LPC1768/pinsDebug.h +++ b/Marlin/src/HAL/LPC1768/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index 7e50492598..aa90eb39a3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -20,7 +20,6 @@ /** * Support routines for X86_64 */ - #pragma once /** diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h index db4abec91c..58822fe05f 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.h +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -25,7 +25,6 @@ * * Derived from Adafruit_SPIFlash class with no SdFat references */ - #pragma once #include diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index e1be50820f..7078d210dc 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #if defined(HAL_STM32) && !defined(STM32H7xx) diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 3caedc72eb..37a8f40fd0 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index ab5c4260af..bf861fb8a7 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 914969f10c..54e1820c78 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp index 5bd4c18577..f30b3dedb2 100644 --- a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp index 26b3d9044e..ad8712c0c0 100644 --- a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index 77563b2ae5..473b656f9a 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index a8fcbe5f82..917e12615f 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index c77dbc4c75..73d850fc43 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h index e2052c5c77..7f341a8c25 100644 --- a/Marlin/src/HAL/STM32/spi_pins.h +++ b/Marlin/src/HAL/STM32/spi_pins.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index dacf533224..e68b3c1269 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 29a309f40e..790513e7ed 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index 912e6c2db7..cf4a8f18e9 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index f0879a36a4..d77f0b28e9 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 959ca4ff43..b607275db5 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32/usb_serial.h b/Marlin/src/HAL/STM32/usb_serial.h index ca61b9ed23..3edb6fd618 100644 --- a/Marlin/src/HAL/STM32/usb_serial.h +++ b/Marlin/src/HAL/STM32/usb_serial.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index 72c74a2e3b..1eccdec498 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../platforms.h" #ifdef HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index f1cd6b3730..26ea1ea19a 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __STM32F1__ #include "../../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 4cac36554f..bc48eef34f 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index dcf3a51138..27f4b6732b 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/STM32F1/spi_pins.h b/Marlin/src/HAL/STM32F1/spi_pins.h index 7d650ffe37..3d3c8f8d2f 100644 --- a/Marlin/src/HAL/STM32F1/spi_pins.h +++ b/Marlin/src/HAL/STM32F1/spi_pins.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp index 85febebebc..d1ff940822 100644 --- a/Marlin/src/HAL/TEENSY31_32/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom.cpp @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __MK20DX256__ /** diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h index e529fa93be..7a2e1d6e59 100644 --- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h index 197cc6f1b2..94b85ea568 100644 --- a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index 05af38307b..32543c6d0a 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "Delay.h" #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 20408d8d1e..be5f6fee12 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfig.h" #if ENABLED(AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index ee5716888d..9d50bfc0d4 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../inc/MarlinConfig.h" #if ENABLED(CANCEL_OBJECTS) diff --git a/Marlin/src/feature/closedloop.cpp b/Marlin/src/feature/closedloop.cpp index 8a97f0c0cd..1b9f711a6b 100644 --- a/Marlin/src/feature/closedloop.cpp +++ b/Marlin/src/feature/closedloop.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../inc/MarlinConfig.h" #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 2698b53dd6..ce979145a1 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../inc/MarlinConfigPre.h" #if ENABLED(DIRECT_STEPPING) diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp index b52feb4a00..165f71fd0f 100644 --- a/Marlin/src/feature/repeat.cpp +++ b/Marlin/src/feature/repeat.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../inc/MarlinConfig.h" #if ENABLED(GCODE_REPEAT_MARKERS) diff --git a/Marlin/src/gcode/calibrate/M12.cpp b/Marlin/src/gcode/calibrate/M12.cpp index da24454375..191ff22d7d 100644 --- a/Marlin/src/gcode/calibrate/M12.cpp +++ b/Marlin/src/gcode/calibrate/M12.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfigPre.h" #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index b6644eb4ab..ac91f08cb4 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfig.h" #if ENABLED(EDITABLE_SERVO_ANGLES) diff --git a/Marlin/src/gcode/feature/pause/G27.cpp b/Marlin/src/gcode/feature/pause/G27.cpp index 3ce618d675..f61453e6fb 100644 --- a/Marlin/src/gcode/feature/pause/G27.cpp +++ b/Marlin/src/gcode/feature/pause/G27.cpp @@ -20,7 +20,6 @@ * */ - #include "../../../inc/MarlinConfig.h" #if ENABLED(NOZZLE_PARK_FEATURE) diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 3baff46836..83646ef67c 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../inc/MarlinConfigPre.h" #if ENABLED(MARLIN_DEV_MODE) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index cec8df7542..1830dea3bf 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfig.h" #if ENABLED(REPETIER_GCODE_M360) diff --git a/Marlin/src/gcode/host/M876.cpp b/Marlin/src/gcode/host/M876.cpp index 0d8256cf08..00efb013d2 100644 --- a/Marlin/src/gcode/host/M876.cpp +++ b/Marlin/src/gcode/host/M876.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfig.h" #if ENABLED(HOST_PROMPT_SUPPORT) && DISABLED(EMERGENCY_PARSER) diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index 618e3d5d6c..079315311a 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfig.h" #if HAS_LCD_CONTRAST diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp index 168dc28abd..a57a293e06 100644 --- a/Marlin/src/gcode/motion/G6.cpp +++ b/Marlin/src/gcode/motion/G6.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfig.h" #if ENABLED(DIRECT_STEPPING) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 9c1948157f..53b8783647 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3279,10 +3279,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Check per-axis initializers for errors */ -constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, - sanity_arr_2[] = DEFAULT_MAX_FEEDRATE, - sanity_arr_3[] = DEFAULT_MAX_ACCELERATION, - sanity_arr_4[] = HOMING_FEEDRATE_MM_M; #define __PLUS_TEST(I,A) && (sanity_arr_##A[_MIN(I,signed(COUNT(sanity_arr_##A)-1))] > 0) #define _PLUS_TEST(A) (1 REPEAT2(14,__PLUS_TEST,A)) @@ -3292,18 +3288,22 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")" #endif +constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT; static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert(_PLUS_TEST(1), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); +constexpr float sanity_arr_2[] = DEFAULT_MAX_FEEDRATE; static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert(_PLUS_TEST(2), "DEFAULT_MAX_FEEDRATE values must be positive."); +constexpr float sanity_arr_3[] = DEFAULT_MAX_ACCELERATION; static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."); +constexpr float sanity_arr_4[] = HOMING_FEEDRATE_MM_M; static_assert(COUNT(sanity_arr_4) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 8aca19b0cd..19e3814a6f 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -1,3 +1,25 @@ +/** + * 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 . + * + */ + /** * @file lcdprint_hd44780.cpp * @brief LCD print api for HD44780 diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index 0a7ece8601..6f55d3bc3d 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -2,6 +2,9 @@ * 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 @@ -16,6 +19,7 @@ * along with this program. If not, see . * */ + #include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp index 2a21bd67ca..6d40ea0d4b 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1309_12864.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../inc/MarlinConfigPre.h" #if HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h index 70ac1490df..d9157fc4e6 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * lcd/extui/anycubic_chiron/chiron_defs.h @@ -28,7 +29,6 @@ * (not affiliated with Anycubic, Ltd.) */ -#pragma once #include "../../../inc/MarlinConfigPre.h" //#define ACDEBUGLEVEL 4 diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h index d092d3a5b7..593b2e3bb8 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #include "DGUSDisplay.h" diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index 056757fedf..402d8d3d38 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #include "config/DGUS_Addr.h" diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h index b1159ff708..20cd48c986 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once namespace DGUSSetupHandler { diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h index 5715abbedf..a034b92ece 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #include "DGUSDisplay.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h index 4faddc64b1..754f6e93e1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h index 50fc5ab9f8..e8b4281122 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h index f67961830f..6a02228925 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h index e46a280369..6935494809 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #define FTDI_CUSTOM_USER_MENUS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h index 5d9735892d..169a306afc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h @@ -20,7 +20,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000, x_max = 272.000000, diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h index e023599a27..1231d31dc3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h index e3a30a6dfe..c6065af7f7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_about.cpp b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp index 54a8ede64e..3424bf7a0e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_about.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_about.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp index 22196a28b8..5de4a13c88 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp index a564d86cc1..33fe9eb9cb 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp index d52abcff23..5ac24c4413 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp index 3165190579..428d43db7a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp index 645cd2e6e3..5248816f54 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp index 56b0e8f5ca..1d0ae7775b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp index b96c65e547..c518d85ab5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp index 4c56205465..04c6b51e2a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index 48ff56253b..6955e1803d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index d1132a33d8..b18bd28339 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp index ce804e615d..ab7a9a6001 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp index 311894825d..0eaa35e49f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp index 97680f3a0c..e3ca75da51 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp index bded5df7e7..13df99f954 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp index 447fadd55d..8dba33756a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_home.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp index e1ab58ee7b..d022dc3036 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_LVGL_UI && USE_SENSORLESS diff --git a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp index 8a97e30467..d410b2003c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index 671939cbff..b28159933f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_language.cpp b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp index 3db22583aa..3ef8c6a0ee 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_language.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp index 8c8dec8913..6fc8704607 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp index 890db3b5cd..57c32c733e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp index 3f43da992c..b14dc6b759 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp index b927b99b76..60724aa4f3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp index 2cccf899b4..1dd6a93d62 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp index e89e2f3e8a..6c5fa2fa3d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp index b86370e35a..7367cec1c2 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp index 7a37dc6a15..baa8d48da3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp index ae770a8925..a3cb7f6c1c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp index 9b87df1fdf..8be74c6b9a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index 485e010251..e5f6a5963a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp index 771a98c11f..8e107d4cee 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index 54f0917774..3489578fe9 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index 5e1dfae5d1..ebad708597 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index e3915adeb0..e58c098fbb 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index d324d8d7be..ce0091d8dd 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp index a765d0e58a..2dd3a9dfd9 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp index d4ab028eec..fc920728b4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp index 5117bd4802..60a3562b9d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index bf1b9c3459..cdac150453 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp index 8b9747972d..4cc99d7184 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index e10a07c6de..5bd11e59ec 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp index c4a21542e2..d6e52606c0 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 68430fe517..26906ffced 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp index 34b2abd094..5073b6b4e5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp index 2c3957fe9c..6283b1dc58 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp index 8509cc3ac1..e087f74286 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp index c337d18922..f2fc7b1199 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp index b1f0e0e1bb..672783f656 100644 --- a/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp +++ b/Marlin/src/lcd/extui/mks_ui/gb2312_puhui16.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 5cd1a4c525..1347f77f9a 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 624626a322..2e24d6a2c0 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 362fdeb43d..3ca5d30e64 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 79990ea42a..1cac49ffda 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp index 0771a31cb4..c69ccf6587 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 998393ebd5..70173691b0 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 4a5f08edaa..ff61315070 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/fontutils.cpp index 90fcb2ae7c..50b671ea33 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/fontutils.cpp @@ -1,3 +1,25 @@ +/** + * 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 . + * + */ + /** * @file fontutils.cpp * @brief help functions for font and char diff --git a/Marlin/src/lcd/fontutils.h b/Marlin/src/lcd/fontutils.h index 04ff81148f..3901d4439f 100644 --- a/Marlin/src/lcd/fontutils.h +++ b/Marlin/src/lcd/fontutils.h @@ -1,3 +1,25 @@ +/** + * 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 . + * + */ + /** * @file fontutils.h * @brief help functions for font and char diff --git a/Marlin/src/lcd/tft_io/touch_calibration.cpp b/Marlin/src/lcd/tft_io/touch_calibration.cpp index 1c3b8b35fc..44ebc73d71 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.cpp +++ b/Marlin/src/lcd/tft_io/touch_calibration.cpp @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index 112fbdca30..abd5667700 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 2d6158961e..9d9d6efeb2 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/touch/touch_buttons.h b/Marlin/src/lcd/touch/touch_buttons.h index 36be0ee134..39768f2594 100644 --- a/Marlin/src/lcd/touch/touch_buttons.h +++ b/Marlin/src/lcd/touch/touch_buttons.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index adcd5ed894..6407fac670 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/module/thermistor/thermistor_99.h b/Marlin/src/module/thermistor/thermistor_99.h index f813abae69..fa3dae93af 100644 --- a/Marlin/src/module/thermistor/thermistor_99.h +++ b/Marlin/src/module/thermistor/thermistor_99.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once // 100k bed thermistor with a 10K pull-up resistor - made by $ buildroot/share/scripts/createTemperatureLookupMarlin.py --rp=10000 diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index e29067268d..b384342335 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -2,6 +2,9 @@ * 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 @@ -41,7 +44,7 @@ #define REPORT_NAME_ANALOG(COUNTER, NAME) _ADD_PIN(#NAME, COUNTER) #include "pinsDebug_list.h" -#line 45 +#line 48 // manually add pins that have names that are macros which don't play well with these macros #if ANY(AVR_ATmega2560_FAMILY, AVR_ATmega1284_FAMILY, ARDUINO_ARCH_SAM, TARGET_LPC1768) @@ -160,7 +163,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #include "pinsDebug_list.h" - #line 164 + #line 167 }; diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 501ae921c2..fe670cca29 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -2,6 +2,9 @@ * 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 @@ -22,15 +25,13 @@ // Following this pattern is a must. // If the new pin name is over 28 characters long then pinsDebug.h will need to be modified. -// Pin lists 1.1.x and 2.0.x synchronized 2018-02-17 - #if TARGET_LPC1768 #define ANALOG_OK(PN) ((PN) == P0_02 || (PN) == P0_03 || (PN) == P0_23 || (PN) == P0_24 || (PN) == P0_25 || (PN) == P0_26 || (PN) == P1_30 || (PN) == P1_31) #else #define ANALOG_OK(PN) ((PN) >= 0 && (PN) < NUM_ANALOG_INPUTS) #endif -#line 34 // set __LINE__ to a known value for both passes +#line 35 // set __LINE__ to a known value for both passes // // Analog Pin Assignments diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index badf53a641..c3133432e0 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h index abdd088f9b..178c873af7 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #if NOT_TARGET(STM32F0xx) diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index 2717439f24..299b9ff49c 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #if NOT_TARGET(__STM32F1__, STM32F1xx, STM32F0xx) diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index c9d16b16b0..b25badca56 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index d2ee2e013c..196a779c8d 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #include "env_validate.h" diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h index f5ebf82a48..bad5b8f718 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4P.h @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #pragma once #define BOARD_INFO_NAME "Anet ET4P 1.x" diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 3cfa3cd3e5..6ad3849d11 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 2d5a45eee0..68e5636955 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index f65476c0b7..12e47e35cc 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h index b12f4737b7..04dcc432ca 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h @@ -19,14 +19,13 @@ * along with this program. If not, see . * */ +#pragma once /** * No offical schematics have been found. * But these differences where noted in https://github.com/bigtreetech/Rumba32/issues/1 */ -#pragma once - #define BOARD_INFO_NAME "RUMBA32 (BTT)" #if NO_EEPROM_SELECTED diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 5f8ffe975b..7ccb57e238 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once // Source: https://github.com/stm32duino/Arduino_Core_STM32/blob/master/variants/ST3DP001_EVAL/variant.cpp @@ -38,8 +39,6 @@ * C Runtime Library: "newlib Nano (default)" */ -#pragma once - #include "env_validate.h" #ifndef MACHINE_NAME diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h index ae973c89c5..6fb271dea6 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h @@ -27,7 +27,6 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ******************************************************************************* */ - #pragma once #ifdef __cplusplus diff --git a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h index f4488356b7..d82f000655 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_LERDGE/variant.h @@ -27,7 +27,6 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ******************************************************************************* */ - #pragma once #ifdef __cplusplus diff --git a/buildroot/share/fonts/genallfont.sh b/buildroot/share/fonts/genallfont.sh index d5cad54361..bffe715b9d 100755 --- a/buildroot/share/fonts/genallfont.sh +++ b/buildroot/share/fonts/genallfont.sh @@ -105,6 +105,9 @@ if [ 1 = 1 ]; then * 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 @@ -119,6 +122,7 @@ if [ 1 = 1 ]; then * along with this program. If not, see . * */ + #include #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) From 8df3e62c89f94f68465ac30e276333940e069ff7 Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Thu, 16 Sep 2021 19:48:24 +0800 Subject: [PATCH 0691/2168] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20and=20improve=20?= =?UTF-8?q?MKS=20LVGL=20UI=20(#22783)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: makerbase <4164049@qq.com> Co-authored-by: MKS-Sean <56996910+MKS-Sean@users.noreply.github.com> Co-authored-by: Scott Lahteine --- .../src/lcd/extui/mks_ui/SPIFlashStorage.cpp | 6 +- Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp | 6 +- .../extui/mks_ui/draw_advance_settings.cpp | 6 +- .../lcd/extui/mks_ui/draw_baby_stepping.cpp | 5 +- Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 26 +++--- Marlin/src/lcd/extui/mks_ui/draw_fan.cpp | 9 +- .../lcd/extui/mks_ui/draw_filament_change.cpp | 6 +- Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp | 14 +-- .../draw_homing_sensitivity_settings.cpp | 8 +- Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp | 68 +++++++-------- Marlin/src/lcd/extui/mks_ui/draw_more.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 87 +++++++++++++------ Marlin/src/lcd/extui/mks_ui/draw_preHeat.h | 2 + Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 12 +-- .../src/lcd/extui/mks_ui/draw_ready_print.cpp | 20 ++--- .../mks_ui/draw_tmc_step_mode_settings.cpp | 12 +-- Marlin/src/lcd/extui/mks_ui/draw_tool.cpp | 6 +- .../extui/mks_ui/draw_touch_calibration.cpp | 6 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 44 +++++----- Marlin/src/lcd/extui/mks_ui/draw_ui.h | 4 +- Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h | 2 +- .../src/lcd/extui/mks_ui/draw_wifi_tips.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 8 +- Marlin/src/lcd/extui/mks_ui/pic_manager.h | 48 +++++----- .../lcd/extui/mks_ui/printer_operation.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/tft_Language_en.h | 50 +++++------ Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h | 2 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 7 +- .../src/lcd/extui/mks_ui/tft_multi_language.h | 4 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32.h | 20 ++--- .../lcd/extui/mks_ui/wifiSerial_STM32F1.cpp | 3 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32F1.h | 22 ++--- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 24 ++--- Marlin/src/lcd/extui/mks_ui/wifi_module.h | 44 +++++----- Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 10 +-- 38 files changed, 320 insertions(+), 283 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 6f3d6bbb6b..2fb28415a1 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -43,9 +43,9 @@ uint32_t SPIFlashStorage::m_startAddress; static uint32_t rle_compress(T *output, uint32_t outputLength, T *input, uint32_t inputLength, uint32_t& inputProcessed) { uint32_t count = 0, out = 0, index, i; T pixel; - //32767 for uint16_t - //127 for uint16_t - //calculated at compile time + // 32767 for uint16_t + // 127 for uint16_t + // calculated at compile time constexpr T max = (0xFFFFFFFF >> (8 * (4 - sizeof(T)))) / 2; inputProcessed = 0; diff --git a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp index 68e4d9de04..42abd4bf64 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp @@ -69,14 +69,14 @@ void TFT::LCD_init() { } void TFT::LCD_clear(uint16_t color) { - setWindow(0, 0, (TFT_WIDTH), (TFT_HEIGHT)); - tftio.WriteMultiple(color, (uint32_t)(TFT_WIDTH) * (TFT_HEIGHT)); + setWindow(0, 0, TFT_WIDTH, TFT_HEIGHT); + tftio.WriteMultiple(color, uint32_t(TFT_WIDTH) * uint32_t(TFT_HEIGHT)); } void TFT::LCD_Draw_Logo() { #if HAS_LOGO_IN_FLASH setWindow(0, 0, TFT_WIDTH, TFT_HEIGHT); - for (uint16_t i = 0; i < (TFT_HEIGHT); i ++) { + for (uint16_t i = 0; i < (TFT_HEIGHT); i++) { Pic_Logo_Read((uint8_t *)"", (uint8_t *)bmp_public_buf, (TFT_WIDTH) * 2); tftio.WriteSequence((uint16_t *)bmp_public_buf, TFT_WIDTH); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp index 33fe9eb9cb..28958b6d2c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.cpp @@ -57,9 +57,9 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { break; #if ENABLED(MKS_WIFI_MODULE) case ID_WIFI_PARA: - lv_clear_advance_settings(); - lv_draw_wifi_settings(); - break; + lv_clear_advance_settings(); + lv_draw_wifi_settings(); + break; #endif #if HAS_ROTARY_ENCODER case ID_ENCODER_SETTINGS: diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp index 428d43db7a..c7e6a62341 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -55,7 +55,7 @@ enum { ID_BABY_STEP_RETURN }; -static float babystep_dist=0.01; +static float babystep_dist = 0.01; static uint8_t has_adjust_z = 0; static void event_handler(lv_obj_t *obj, lv_event_t event) { @@ -124,9 +124,8 @@ void lv_draw_baby_stepping() { buttonV = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_BABY_STEP_DIST); labelV = lv_label_create_empty(buttonV); #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonV); - } #endif lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_BABY_STEP_RETURN); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h index 917b52ab0a..ff60f121a1 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif void lv_draw_cloud_bind(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 638d0c5ec3..a390bd92e3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -103,15 +103,13 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { if (card.isFileOpen()) { feedrate_percentage = 100; planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = 100; - planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; + planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; #endif card.startOrResumeFilePrinting(); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.prepare(); - #endif + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; } } @@ -229,14 +227,14 @@ void lv_draw_dialog(uint8_t type) { lv_obj_t *labelDialog = lv_label_create(scr, ""); if (DIALOG_IS(TYPE_FINISH_PRINT, PAUSE_MESSAGE_RESUME)) { - btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); - lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); + lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text } else if (DIALOG_IS(PAUSE_MESSAGE_WAITING, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_HEAT)) { btnOk = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_ok_event_cb); - lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + lv_obj_t *labelOk = lv_label_create_empty(btnOk); // Add a label to the button + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text } else if (DIALOG_IS(PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_LOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_RESUME, PAUSE_MESSAGE_HEATING)) { // nothing to do @@ -269,7 +267,7 @@ void lv_draw_dialog(uint8_t type) { } #endif else if (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT, TYPE_FILAMENT_UNLOAD_HEAT)) { - btnCancel = lv_button_btn_create(scr, BTN_OK_X+90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); + btnCancel = lv_button_btn_create(scr, BTN_OK_X + 90, BTN_OK_Y, 100, 50, btn_cancel_event_cb); lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); @@ -287,7 +285,7 @@ void lv_draw_dialog(uint8_t type) { lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); filament_bar = lv_bar_create(scr, nullptr); - lv_obj_set_pos(filament_bar, (TFT_WIDTH-400)/2, ((TFT_HEIGHT - titleHeight)-40)/2); + lv_obj_set_pos(filament_bar, (TFT_WIDTH - 400) / 2, ((TFT_HEIGHT - titleHeight) - 40) / 2); lv_obj_set_size(filament_bar, 400, 25); lv_bar_set_style(filament_bar, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); lv_bar_set_anim_time(filament_bar, 1000); @@ -301,11 +299,11 @@ void lv_draw_dialog(uint8_t type) { lv_obj_t *labelCancel = lv_label_create_empty(btnCancel); // Add a label to the button if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) { - lv_label_set_text(labelOk, pause_msg_menu.purgeMore); // Set the labels text + lv_label_set_text(labelOk, pause_msg_menu.purgeMore); // Set the labels text lv_label_set_text(labelCancel, pause_msg_menu.continuePrint); } else { - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text lv_label_set_text(labelCancel, print_file_dialog_menu.cancel); } } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp index ab7a9a6001..b2107709a4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.cpp @@ -44,9 +44,11 @@ enum { ID_F_RETURN }; +uint8_t fanPercent = 0; static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; - uint8_t fanPercent = map(thermalManager.fan_speed[0], 0, 255, 0, 100); + const uint8_t temp = map(thermalManager.fan_speed[0], 0, 255, 0, 100); + if (abs(fanPercent - temp) > 2) fanPercent = temp; switch (obj->mks_obj_id) { case ID_F_ADD: if (fanPercent < 100) fanPercent++; break; case ID_F_DEC: if (fanPercent != 0) fanPercent--; break; @@ -56,6 +58,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_F_RETURN: clear_cur_ui(); draw_return_ui(); return; } thermalManager.set_fan_speed(0, map(fanPercent, 0, 100, 0, 255)); + if (obj->mks_obj_id != ID_F_RETURN) disp_fan_value(); } void lv_draw_fan() { @@ -63,7 +66,7 @@ void lv_draw_fan() { scr = lv_screen_create(FAN_UI); // Create an Image button - buttonAdd = lv_big_button_create(scr, "F:/bmp_Add.bin", fan_menu.add, INTERVAL_V, titleHeight, event_handler, ID_F_ADD); + buttonAdd = lv_big_button_create(scr, "F:/bmp_Add.bin", fan_menu.add, INTERVAL_V, titleHeight, event_handler, ID_F_ADD); lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); lv_big_button_create(scr, "F:/bmp_Dec.bin", fan_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_F_DEC); lv_big_button_create(scr, "F:/bmp_speed255.bin", fan_menu.full, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_F_HIGH); @@ -78,7 +81,7 @@ void lv_draw_fan() { void disp_fan_value() { #if HAS_FAN - sprintf_P(public_buf_l, PSTR("%s: %3d%%"), fan_menu.state, (int)map(thermalManager.fan_speed[0], 0, 255, 0, 100)); + sprintf_P(public_buf_l, PSTR("%s: %3d%%"), fan_menu.state, fanPercent); #else sprintf_P(public_buf_l, PSTR("%s: ---"), fan_menu.state); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp index 0eaa35e49f..8432c74b1a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -52,7 +52,8 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_FILAMNT_IN: uiCfg.filament_load_heat_flg = true; if (ABS(thermalManager.degTargetHotend(uiCfg.extruderIndex) - thermalManager.wholeDegHotend(uiCfg.extruderIndex)) <= 1 - || gCfgItems.filament_limit_temp <= thermalManager.wholeDegHotend(uiCfg.extruderIndex)) { + || gCfgItems.filament_limit_temp <= thermalManager.wholeDegHotend(uiCfg.extruderIndex) + ) { lv_clear_filament_change(); lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); } @@ -115,9 +116,8 @@ void lv_draw_filament_change() { buttonType = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_FILAMNT_TYPE); #if HAS_ROTARY_ENCODER - if (gCfgItems.encoder_enable) { + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonType); - } #endif lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_FILAMNT_RETURN); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp index 13df99f954..fa9f7b0c47 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.cpp @@ -30,7 +30,7 @@ #include "../../../inc/MarlinConfig.h" extern lv_group_t *g; -static lv_obj_t *scr,*outL,*outV = 0; +static lv_obj_t *scr, *outL, *outV = 0; static int currentWritePos = 0; extern uint8_t public_buf[513]; extern "C" { extern char public_buf_m[100]; } @@ -59,7 +59,7 @@ void lv_show_gcode_output(void * that, const char * txt) { if (!memcmp(txt, "echo:", 5)) { public_buf[0] = 0; // Clear output buffer return; - } + } // Avoid overflow if the answer is too large size_t len = strlen((const char*)public_buf), tlen = strlen(txt); @@ -69,17 +69,17 @@ void lv_show_gcode_output(void * that, const char * txt) { } } -void lv_serial_capt_hook(void * userPointer, uint8_t c) -{ +void lv_serial_capt_hook(void * userPointer, uint8_t c) { if (c == '\n' || currentWritePos == sizeof(public_buf_m) - 1) { // End of line, probably end of command anyway public_buf_m[currentWritePos] = 0; lv_show_gcode_output(userPointer, public_buf_m); currentWritePos = 0; } - else public_buf_m[currentWritePos++] = c; + else + public_buf_m[currentWritePos++] = c; } -void lv_eom_hook(void *) -{ + +void lv_eom_hook(void *) { // Message is done, let's remove the hook now MYSERIAL1.setHook(); // We are back from the keyboard, so let's redraw ourselves diff --git a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp index d022dc3036..212f2b4995 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.cpp @@ -67,10 +67,10 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { break; #if Z2_SENSORLESS case ID_SENSITIVITY_Z2: - value = z2_sensitivity; - lv_clear_homing_sensitivity_settings(); - lv_draw_number_key(); - break; + value = z2_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + break; #endif } } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index b28159933f..e1184c2195 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -41,10 +41,10 @@ static const char * kb_map_lc[] = {"1#", "q", "w", "e", "r", "t", "y", "u", "i", LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; static const lv_btnm_ctrl_t kb_ctrl_lc_map[] = { - LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, - LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, + LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; static const char * kb_map_uc[] = {"1#", "Q", "W", "E", "R", "T", "Y", "U", "I", "O", "P", LV_SYMBOL_BACKSPACE, "\n", "abc", "A", "S", "D", "F", "G", "H", "J", "K", "L", LV_SYMBOL_NEW_LINE, "\n", @@ -52,32 +52,33 @@ static const char * kb_map_uc[] = {"1#", "Q", "W", "E", "R", "T", "Y", "U", "I", LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; static const lv_btnm_ctrl_t kb_ctrl_uc_map[] = { - LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, - LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, + LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; -static const char * kb_map_spec[] = {"0", "1", "2", "3", "4" ,"5", "6", "7", "8", "9", ".", LV_SYMBOL_BACKSPACE, "\n", +static const char * kb_map_spec[] = {"0", "1", "2", "3", "4", "5", "6", "7", "8", "9", ".", LV_SYMBOL_BACKSPACE, "\n", "abc", "+", "-", "/", "*", "=", "%", "!", "?", "#", "<", ">", "\n", "\\", "@", "$", "(", ")", "{", "}", "[", "]", ";", "\"", "'", "\n", LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; static const lv_btnm_ctrl_t kb_ctrl_spec_map[] = { - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, - LV_KB_CTRL_BTN_FLAGS | 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + LV_KB_CTRL_BTN_FLAGS | 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; static const lv_btnm_ctrl_t kb_ctrl_num_map[] = { - 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, - 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, - 1, 1, 1, 2, - 1, 1, 1, 1, 1}; + 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + 1, 1, 1, 2, + 1, 1, 1, 1, 1 +}; static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { if (event != LV_EVENT_VALUE_CHANGED) return; - lv_kb_ext_t * ext = (lv_kb_ext_t * )lv_obj_get_ext_attr(kb); + lv_kb_ext_t *ext = (lv_kb_ext_t*)lv_obj_get_ext_attr(kb); const uint16_t btn_id = lv_btnm_get_active_btn(kb); if (btn_id == LV_BTNM_BTN_NONE) return; if (lv_btnm_get_btn_ctrl(kb, btn_id, LV_BTNM_CTRL_HIDDEN | LV_BTNM_CTRL_INACTIVE)) return; @@ -120,12 +121,12 @@ static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { switch (keyboard_value) { #if ENABLED(MKS_WIFI_MODULE) case wifiName: - memcpy(uiCfg.wifi_name,ret_ta_txt,sizeof(uiCfg.wifi_name)); + memcpy(uiCfg.wifi_name, ret_ta_txt, sizeof(uiCfg.wifi_name)); lv_clear_keyboard(); draw_return_ui(); break; case wifiPassWord: - memcpy(uiCfg.wifi_key,ret_ta_txt,sizeof(uiCfg.wifi_name)); + memcpy(uiCfg.wifi_key, ret_ta_txt, sizeof(uiCfg.wifi_name)); lv_clear_keyboard(); draw_return_ui(); break; @@ -157,8 +158,8 @@ static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { #endif // MKS_WIFI_MODULE case autoLevelGcodeCommand: uint8_t buf[100]; - strncpy((char *)buf,ret_ta_txt,sizeof(buf)); - update_gcode_command(AUTO_LEVELING_COMMAND_ADDR,buf); + strncpy((char *)buf, ret_ta_txt, sizeof(buf)); + update_gcode_command(AUTO_LEVELING_COMMAND_ADDR, buf); lv_clear_keyboard(); draw_return_ui(); break; @@ -176,7 +177,7 @@ static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { } else lv_kb_set_ta(kb, nullptr); // De-assign the text area to hide it cursor if needed - return; + return; } // Add the characters to the text area if set @@ -223,16 +224,16 @@ void lv_draw_keyboard() { static lv_style_t rel_style, pr_style; lv_style_copy(&rel_style, &lv_style_btn_rel); - rel_style.body.radius = 0; + rel_style.body.radius = 0; rel_style.body.border.width = 1; - rel_style.body.main_color = lv_color_make(0xA9, 0x62, 0x1D); - rel_style.body.grad_color = lv_color_make(0xA7, 0x59, 0x0E); + rel_style.body.main_color = lv_color_make(0xA9, 0x62, 0x1D); + rel_style.body.grad_color = lv_color_make(0xA7, 0x59, 0x0E); lv_style_copy(&pr_style, &lv_style_btn_pr); - pr_style.body.radius = 0; + pr_style.body.radius = 0; pr_style.body.border.width = 1; - pr_style.body.main_color = lv_color_make(0x72, 0x42, 0x15); - pr_style.body.grad_color = lv_color_make(0x6A, 0x3A, 0x0C); + pr_style.body.main_color = lv_color_make(0x72, 0x42, 0x15); + pr_style.body.grad_color = lv_color_make(0x6A, 0x3A, 0x0C); // Create a keyboard and apply the styles lv_obj_t *kb = lv_kb_create(scr, nullptr); @@ -251,9 +252,9 @@ void lv_draw_keyboard() { lv_obj_align(ta, nullptr, LV_ALIGN_IN_TOP_MID, 0, 10); switch (keyboard_value) { case autoLevelGcodeCommand: - get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); - public_buf_m[sizeof(public_buf_m)-1] = 0; - lv_ta_set_text(ta, public_buf_m); + get_gcode_command(AUTO_LEVELING_COMMAND_ADDR, (uint8_t *)public_buf_m); + public_buf_m[sizeof(public_buf_m) - 1] = '\0'; + lv_ta_set_text(ta, public_buf_m); break; case GCodeCommand: // Start with uppercase by default @@ -261,7 +262,7 @@ void lv_draw_keyboard() { lv_btnm_set_ctrl_map(kb, kb_ctrl_uc_map); // Fallthrough default: - lv_ta_set_text(ta, ""); + lv_ta_set_text(ta, ""); } // Assign the text area to the keyboard @@ -272,5 +273,4 @@ void lv_clear_keyboard() { lv_obj_del(scr); } - #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.h b/Marlin/src/lcd/extui/mks_ui/draw_more.h index 74ac7e994d..86ee6f895f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif void lv_draw_more(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index 3489578fe9..1d804c3b2a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -32,10 +32,17 @@ static lv_obj_t *scr; extern lv_group_t* g; -static lv_obj_t *buttonType, *buttonStep; +static lv_obj_t *buttonType, *buttonStep, *buttonAdd, *buttonDec; static lv_obj_t *labelType; static lv_obj_t *labelStep; static lv_obj_t *tempText1; +static lv_obj_t *btn_pla; +static lv_obj_t *btn_abs; +static lv_obj_t *label_abs; +static lv_obj_t *label_pla; + +static lv_style_t btn_style_pre; +static lv_style_t btn_style_rel; enum { ID_P_ADD = 1, @@ -43,7 +50,9 @@ enum { ID_P_TYPE, ID_P_STEP, ID_P_OFF, - ID_P_RETURN + ID_P_RETURN, + ID_P_ABS, + ID_P_PLA }; static void event_handler(lv_obj_t *obj, lv_event_t event) { @@ -55,10 +64,11 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { thermalManager.temp_hotend[uiCfg.extruderIndex].target += uiCfg.stepHeat; if (uiCfg.extruderIndex == 0) max_target = HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - #if HAS_MULTI_HOTEND - else + else { + #if HAS_MULTI_HOTEND max_target = HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - #endif + #endif + } if (thermalManager.degTargetHotend(uiCfg.extruderIndex) > max_target) thermalManager.setTargetHotend(max_target, uiCfg.extruderIndex); thermalManager.start_watching_hotend(uiCfg.extruderIndex); @@ -83,16 +93,16 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { thermalManager.setTargetHotend(0, uiCfg.extruderIndex); thermalManager.start_watching_hotend(uiCfg.extruderIndex); } - #if HAS_HEATED_BED - else { + else { + #if HAS_HEATED_BED if (thermalManager.degTargetBed() > uiCfg.stepHeat) thermalManager.temp_bed.target -= uiCfg.stepHeat; else thermalManager.setTargetBed(0); thermalManager.start_watching_bed(); - } - #endif + #endif + } disp_desire_temp(); break; case ID_P_TYPE: @@ -102,25 +112,24 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { uiCfg.extruderIndex = 1; } else if (uiCfg.extruderIndex == 1) { - if (TEMP_SENSOR_BED != 0) { + if (ENABLED(HAS_HEATED_BED)) { uiCfg.curTempType = 1; } else { - uiCfg.curTempType = 0; + uiCfg.curTempType = 0; uiCfg.extruderIndex = 0; } } } else if (uiCfg.extruderIndex == 0) { - if (TEMP_SENSOR_BED != 0) - uiCfg.curTempType = 1; - else - uiCfg.curTempType = 0; + uiCfg.curTempType = TERN(HAS_HEATED_BED, 1, 0); } } else if (uiCfg.curTempType == 1) { uiCfg.extruderIndex = 0; - uiCfg.curTempType = 0; + uiCfg.curTempType = 0; + disp_add_dec(); + disp_ext_heart(); } disp_temp_type(); break; @@ -138,30 +147,44 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { thermalManager.setTargetHotend(0, uiCfg.extruderIndex); thermalManager.start_watching_hotend(uiCfg.extruderIndex); } - #if HAS_HEATED_BED - else { + else { + #if HAS_HEATED_BED thermalManager.temp_bed.target = 0; thermalManager.start_watching_bed(); - } - #endif + #endif + } disp_desire_temp(); break; case ID_P_RETURN: clear_cur_ui(); draw_return_ui(); break; + case ID_P_ABS: + thermalManager.setTargetHotend(PREHEAT_2_TEMP_HOTEND, 0); + break; + case ID_P_PLA: + thermalManager.setTargetHotend(PREHEAT_1_TEMP_HOTEND, 0); + break; } } +void disp_add_dec() { + // Create image buttons + buttonAdd = lv_big_button_create(scr, "F:/bmp_Add.bin", preheat_menu.add, INTERVAL_V, titleHeight, event_handler, ID_P_ADD); + buttonDec = lv_big_button_create(scr, "F:/bmp_Dec.bin", preheat_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_P_DEC); +} + void lv_draw_preHeat() { scr = lv_screen_create(PRE_HEAT_UI); // Create image buttons - lv_big_button_create(scr, "F:/bmp_Add.bin", preheat_menu.add, INTERVAL_V, titleHeight, event_handler, ID_P_ADD); - lv_big_button_create(scr, "F:/bmp_Dec.bin", preheat_menu.dec, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_P_DEC); + disp_add_dec(); buttonType = lv_imgbtn_create(scr, nullptr, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_TYPE); buttonStep = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_STEP); + + if (uiCfg.curTempType == 0) disp_ext_heart(); + #if HAS_ROTARY_ENCODER if (gCfgItems.encoder_enable) { lv_group_add_obj(g, buttonType); @@ -184,26 +207,38 @@ void lv_draw_preHeat() { disp_desire_temp(); } +void disp_ext_heart() { + btn_abs = lv_btn_create(scr, 160, 40, 80, 40, event_handler, ID_P_ABS); + btn_pla = lv_btn_create(scr, 260, 40, 80, 40, event_handler, ID_P_PLA); + + lv_btn_set_style(btn_abs, LV_BTN_STYLE_PR, &btn_style_pre); + lv_btn_set_style(btn_abs, LV_BTN_STYLE_REL, &btn_style_rel); + lv_btn_set_style(btn_pla, LV_BTN_STYLE_PR, &btn_style_pre); + lv_btn_set_style(btn_pla, LV_BTN_STYLE_REL, &btn_style_rel); + + label_abs = lv_label_create(btn_abs, PREHEAT_2_LABEL); + label_pla = lv_label_create(btn_pla, PREHEAT_1_LABEL); +} + void disp_temp_type() { if (uiCfg.curTempType == 0) { if (uiCfg.extruderIndex == 1) { - lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); if (gCfgItems.multiple_language) { lv_label_set_text(labelType, preheat_menu.ext2); lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } else { - lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); + lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru1.bin"); if (gCfgItems.multiple_language) { lv_label_set_text(labelType, preheat_menu.ext1); lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } - } else { - lv_imgbtn_set_src_both(buttonType, "F:/bmp_bed.bin"); + lv_imgbtn_set_src_both(buttonType, "F:/bmp_bed.bin"); if (gCfgItems.multiple_language) { lv_label_set_text(labelType, preheat_menu.hotbed); lv_obj_align(labelType, buttonType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h index 2993a95f00..023f1228b3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h @@ -30,6 +30,8 @@ void lv_clear_preHeat(); void disp_temp_type(); void disp_step_heat(); void disp_desire_temp(); +void disp_ext_heart(); +void disp_add_dec(); #ifdef __cplusplus } /* C-declarations for C++ */ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index e58c098fbb..58bbbfbd5b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -160,8 +160,8 @@ void lv_draw_printing() { buttonZpos = lv_imgbtn_create(scr, "F:/bmp_zpos_state.bin", 350, 86, event_handler, ID_BABYSTEP); - buttonPause = lv_imgbtn_create(scr, uiCfg.print_state == WORKING ? "F:/bmp_pause.bin" : "F:/bmp_resume.bin", 5, 240, event_handler, ID_PAUSE); - buttonStop = lv_imgbtn_create(scr, "F:/bmp_stop.bin", 165, 240, event_handler, ID_STOP); + buttonPause = lv_imgbtn_create(scr, uiCfg.print_state == WORKING ? "F:/bmp_pause.bin" : "F:/bmp_resume.bin", 5, 240, event_handler, ID_PAUSE); + buttonStop = lv_imgbtn_create(scr, "F:/bmp_stop.bin", 165, 240, event_handler, ID_STOP); buttonOperat = lv_imgbtn_create(scr, "F:/bmp_operate.bin", 325, 240, event_handler, ID_OPTION); #if HAS_ROTARY_ENCODER @@ -185,7 +185,7 @@ void lv_draw_printing() { labelBed = lv_label_create(scr, 250, 196, nullptr); #endif - labelFan = lv_label_create(scr, 395, 196, nullptr); + labelFan = lv_label_create(scr, 395, 196, nullptr); labelTime = lv_label_create(scr, 250, 96, nullptr); labelZpos = lv_label_create(scr, 395, 96, nullptr); @@ -210,8 +210,8 @@ void lv_draw_printing() { lv_bar_set_style(bar1, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); lv_bar_set_anim_time(bar1, 1000); lv_bar_set_value(bar1, 0, LV_ANIM_ON); - bar1ValueText = lv_label_create_empty(bar1); - lv_label_set_text(bar1ValueText,"0%"); + bar1ValueText = lv_label_create_empty(bar1); + lv_label_set_text(bar1ValueText, "0%"); lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); disp_ext_temp(); @@ -291,7 +291,7 @@ void setProBarRate() { if (disp_state == PRINTING_UI) { lv_bar_set_value(bar1, rate, LV_ANIM_ON); sprintf_P(public_buf_l, "%d%%", rate); - lv_label_set_text(bar1ValueText,public_buf_l); + lv_label_set_text(bar1ValueText, public_buf_l); lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); if (marlin_state == MF_SD_COMPLETE) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index ce0091d8dd..a8d8b29ac0 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -43,7 +43,7 @@ #include "mks_hardware.h" #include -#define ICON_POS_Y 38 +#define ICON_POS_Y 260 #define TARGET_LABEL_MOD_Y -36 #define LABEL_MOD_Y 30 @@ -183,16 +183,16 @@ void lv_draw_ready_print() { lv_label_set_text(det_info, " "); } else { - lv_big_button_create(scr, "F:/bmp_tool.bin", main_menu.tool, 20, 150, event_handler, ID_TOOL); - lv_big_button_create(scr, "F:/bmp_set.bin", main_menu.set, 180, 150, event_handler, ID_SET); - lv_big_button_create(scr, "F:/bmp_printing.bin", main_menu.print, 340, 150, event_handler, ID_PRINT); + lv_big_button_create(scr, "F:/bmp_tool.bin", main_menu.tool, 20, 90, event_handler, ID_TOOL); + lv_big_button_create(scr, "F:/bmp_set.bin", main_menu.set, 180, 90, event_handler, ID_SET); + lv_big_button_create(scr, "F:/bmp_printing.bin", main_menu.print, 340, 90, event_handler, ID_PRINT); // Monitoring #if HAS_HOTEND - buttonExt1 = lv_big_button_create(scr, "F:/bmp_ext1_state.bin", " ", 55, ICON_POS_Y, event_handler, ID_INFO_EXT); + buttonExt1 = lv_big_button_create(scr, "F:/bmp_ext1_state.bin", " ", 20, ICON_POS_Y, event_handler, ID_INFO_EXT); #endif #if HAS_MULTI_HOTEND - buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 163, ICON_POS_Y, event_handler, ID_INFO_EXT); + buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 180, ICON_POS_Y, event_handler, ID_INFO_EXT); #endif #if HAS_HEATED_BED buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", TERN(HAS_MULTI_HOTEND, 271, 210), ICON_POS_Y, event_handler, ID_INFO_BED); @@ -219,22 +219,22 @@ void lv_temp_refr() { #if HAS_HOTEND sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); lv_label_set_text(labelExt1, public_buf_l); - lv_obj_align(labelExt1, buttonExt1, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + lv_obj_align(labelExt1, buttonExt1, LV_ALIGN_OUT_RIGHT_MID, 0, 0); #endif #if HAS_MULTI_HOTEND sprintf(public_buf_l, printing_menu.temp1, thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); lv_label_set_text(labelExt2, public_buf_l); - lv_obj_align(labelExt2, buttonExt2, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + lv_obj_align(labelExt2, buttonExt2, LV_ALIGN_OUT_RIGHT_MID, 0, 0); #endif #if HAS_HEATED_BED sprintf(public_buf_l, printing_menu.bed_temp, thermalManager.wholeDegBed(), thermalManager.degTargetBed()); lv_label_set_text(labelBed, public_buf_l); - lv_obj_align(labelBed, buttonBedstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + lv_obj_align(labelBed, buttonBedstate, LV_ALIGN_OUT_RIGHT_MID, 0, 0); #endif #if HAS_FAN sprintf_P(public_buf_l, PSTR("%d%%"), (int)thermalManager.fanSpeedPercent(0)); lv_label_set_text(labelFan, public_buf_l); - lv_obj_align(labelFan, buttonFanstate, LV_ALIGN_OUT_BOTTOM_MID, 0, 0); + lv_obj_align(labelFan, buttonFanstate, LV_ALIGN_OUT_RIGHT_MID, 0, 0); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index cdac150453..f25f850c2a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -104,16 +104,16 @@ void lv_draw_tmc_step_mode_settings() { scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle); bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false; - TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop()); - TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop()); - TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop()); + TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop()); TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop()); TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop()); if (!uiCfg.para_ui_page) { - buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X); - buttonYState = lv_screen_menu_item_onoff(scr, machine_menu.Y_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_TMC_MODE_Y, 1, stealth_Y); - buttonZState = lv_screen_menu_item_onoff(scr, machine_menu.Z_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_TMC_MODE_Z, 2, stealth_Z); + buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X); + buttonYState = lv_screen_menu_item_onoff(scr, machine_menu.Y_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 2, event_handler, ID_TMC_MODE_Y, 1, stealth_Y); + buttonZState = lv_screen_menu_item_onoff(scr, machine_menu.Z_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 3, event_handler, ID_TMC_MODE_Z, 2, stealth_Z); buttonE0State = lv_screen_menu_item_onoff(scr, machine_menu.E0_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 4, event_handler, ID_TMC_MODE_E0, 2, stealth_E0); lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.next, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_TMC_MODE_DOWN, true); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp index 4cc99d7184..9a0462f148 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -60,8 +60,8 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_T_HOME: lv_draw_home(); break; case ID_T_LEVELING: #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); - public_buf_m[sizeof(public_buf_m)-1] = 0; + get_gcode_command(AUTO_LEVELING_COMMAND_ADDR, (uint8_t *)public_buf_m); + public_buf_m[sizeof(public_buf_m) - 1] = 0; queue.inject_P(PSTR(public_buf_m)); #else uiCfg.leveling_first_time = true; @@ -89,7 +89,7 @@ void lv_draw_tool() { lv_big_button_create(scr, "F:/bmp_mov.bin", tool_menu.move, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight, event_handler, ID_T_MOV); lv_big_button_create(scr, "F:/bmp_zero.bin", tool_menu.home, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight, event_handler, ID_T_HOME); lv_big_button_create(scr, "F:/bmp_leveling.bin", tool_menu.TERN(AUTO_BED_LEVELING_BILINEAR, autoleveling, leveling), INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_LEVELING); - lv_big_button_create(scr, "F:/bmp_filamentchange.bin", tool_menu.filament, BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight, event_handler,ID_T_FILAMENT); + lv_big_button_create(scr, "F:/bmp_filamentchange.bin", tool_menu.filament, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_FILAMENT); lv_big_button_create(scr, "F:/bmp_more.bin", tool_menu.more, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_MORE); lv_big_button_create(scr, "F:/bmp_return.bin", common_menu.text_back, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_T_RETURN); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index 5bd11e59ec..c7e2d5bc31 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -71,9 +71,9 @@ void lv_update_touch_calibration_screen() { if (calibration_stage < CALIBRATION_SUCCESS) { // handle current state switch (calibration_stage) { - case CALIBRATION_TOP_LEFT: str = GET_TEXT(MSG_TOP_LEFT); break; - case CALIBRATION_BOTTOM_LEFT: str = GET_TEXT(MSG_BOTTOM_LEFT); break; - case CALIBRATION_TOP_RIGHT: str = GET_TEXT(MSG_TOP_RIGHT); break; + case CALIBRATION_TOP_LEFT: str = GET_TEXT(MSG_TOP_LEFT); break; + case CALIBRATION_BOTTOM_LEFT: str = GET_TEXT(MSG_BOTTOM_LEFT); break; + case CALIBRATION_TOP_RIGHT: str = GET_TEXT(MSG_TOP_RIGHT); break; case CALIBRATION_BOTTOM_RIGHT: str = GET_TEXT(MSG_BOTTOM_RIGHT); break; default: break; } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 26906ffced..c44bdfea93 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -159,7 +159,7 @@ void gCfgItems_init() { gCfgItems.spi_flash_flag = FLASH_INF_VALID_FLAG; W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); - //init gcode command + // init gcode command W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[0], AUTO_LEVELING_COMMAND_ADDR, 100); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[1], OTHERS_COMMAND_ADDR_1, 100); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[2], OTHERS_COMMAND_ADDR_2, 100); @@ -208,7 +208,7 @@ void ui_cfg_init() { memset(&ipPara, 0, sizeof(ipPara)); strcpy_P(wifiPara.ap_name, PSTR(WIFI_AP_NAME)); strcpy_P(wifiPara.keyCode, PSTR(WIFI_KEY_CODE)); - //client + // client strcpy_P(ipPara.ip_addr, PSTR(IP_ADDR)); strcpy_P(ipPara.mask, PSTR(IP_MASK)); strcpy_P(ipPara.gate, PSTR(IP_GATE)); @@ -216,7 +216,7 @@ void ui_cfg_init() { ipPara.dhcp_flag = IP_DHCP_FLAG; - //AP + // AP strcpy_P(ipPara.dhcpd_ip, PSTR(AP_IP_ADDR)); strcpy_P(ipPara.dhcpd_mask, PSTR(AP_IP_MASK)); strcpy_P(ipPara.dhcpd_gate, PSTR(AP_IP_GATE)); @@ -238,33 +238,33 @@ void update_spi_flash() { uint8_t command_buf[512]; W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command before erase spi flash + // read back the gcode command before erase spi flash W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); } -void update_gcode_command(int addr,uint8_t *s) { +void update_gcode_command(int addr, uint8_t *s) { uint8_t command_buf[512]; W25QXX.init(SPI_QUARTER_SPEED); - //read back the gcode command before erase spi flash + // read back the gcode command before erase spi flash W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); switch (addr) { - case AUTO_LEVELING_COMMAND_ADDR: memcpy(&command_buf[0*100], s, 100); break; - case OTHERS_COMMAND_ADDR_1: memcpy(&command_buf[1*100], s, 100); break; - case OTHERS_COMMAND_ADDR_2: memcpy(&command_buf[2*100], s, 100); break; - case OTHERS_COMMAND_ADDR_3: memcpy(&command_buf[3*100], s, 100); break; - case OTHERS_COMMAND_ADDR_4: memcpy(&command_buf[4*100], s, 100); break; + case AUTO_LEVELING_COMMAND_ADDR: memcpy(&command_buf[0 * 100], s, 100); break; + case OTHERS_COMMAND_ADDR_1: memcpy(&command_buf[1 * 100], s, 100); break; + case OTHERS_COMMAND_ADDR_2: memcpy(&command_buf[2 * 100], s, 100); break; + case OTHERS_COMMAND_ADDR_3: memcpy(&command_buf[3 * 100], s, 100); break; + case OTHERS_COMMAND_ADDR_4: memcpy(&command_buf[4 * 100], s, 100); break; default: break; } W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); } -void get_gcode_command(int addr,uint8_t *d) { +void get_gcode_command(int addr, uint8_t *d) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead((uint8_t *)d, addr, 100); } @@ -369,14 +369,14 @@ void tft_style_init() { style_num_text.text.line_space = -5; lv_style_copy(&style_sel_text, &lv_style_scr); - style_sel_text.body.main_color = LV_COLOR_BACKGROUND; - style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; - style_sel_text.text.color = LV_COLOR_YELLOW; - style_sel_text.text.sel_color = LV_COLOR_YELLOW; - style_sel_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); - style_sel_text.line.width = 0; - style_sel_text.text.letter_space = 0; - style_sel_text.text.line_space = -5; + style_sel_text.body.main_color = LV_COLOR_BACKGROUND; + style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; + style_sel_text.text.color = LV_COLOR_YELLOW; + style_sel_text.text.sel_color = LV_COLOR_YELLOW; + style_sel_text.text.font = TERN(HAS_SPI_FLASH_FONT, &gb2312_puhui32, LV_FONT_DEFAULT); + style_sel_text.line.width = 0; + style_sel_text.text.letter_space = 0; + style_sel_text.text.line_space = -5; lv_style_copy(&style_line, &lv_style_plain); style_line.line.color = LV_COLOR_MAKE(0x49, 0x54, 0xFF); style_line.line.width = 1; @@ -624,7 +624,7 @@ char *creat_title_text() { if (j >= 400) break; } for (i = 0; i < 400; i += 2) { - p_index = (uint16_t *)(&bmp_public_buf[i]); + p_index = (uint16_t *)(&bmp_public_buf[i]); if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; } SPI_TFT.tftio.WriteSequence((uint16_t*)bmp_public_buf, 200); @@ -1353,7 +1353,7 @@ extern volatile uint32_t systick_uptime_millis; void print_time_count() { if ((systick_uptime_millis % 1000) == 0) - if (print_time.start == 1) print_time.seconds++; + if (print_time.start == 1) print_time.seconds++; } void LV_TASK_HANDLER() { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h index b7e66a2727..edb513a8b5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -458,8 +458,8 @@ void tft_style_init(); extern char *creat_title_text(); void preview_gcode_prehandle(char *path); void update_spi_flash(); -void update_gcode_command(int addr,uint8_t *s); -void get_gcode_command(int addr,uint8_t *d); +void update_gcode_command(int addr, uint8_t *s); +void get_gcode_command(int addr, uint8_t *d); void lv_serial_capt_hook(void *, uint8_t); void lv_eom_hook(void *); #if HAS_GCODE_PREVIEW diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp index 5073b6b4e5..c12449f316 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.cpp @@ -71,7 +71,7 @@ void lv_draw_wifi() { if (gCfgItems.wifi_mode_sel == STA_MODEL) { if (gCfgItems.cloud_enable) - buttonCloud = lv_imgbtn_create(scr, "F:/bmp_cloud.bin", BTN_X_PIXEL+INTERVAL_V*2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_CLOUD); + buttonCloud = lv_imgbtn_create(scr, "F:/bmp_cloud.bin", BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_CLOUD); buttonReconnect = lv_imgbtn_create(scr, "F:/bmp_wifi.bin", BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_W_RECONNECT); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h index e2005d5cbc..8dbedf832e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h @@ -28,7 +28,7 @@ void lv_draw_wifi_list(); void lv_clear_wifi_list(); void disp_wifi_list(); -void cutWifiName(char *name, int len,char *outStr); +void cutWifiName(char *name, int len, char *outStr); void wifi_scan_handle(); #define NUMBER_OF_PAGE 5 diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp index f2fc7b1199..a5207d5669 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.cpp @@ -38,7 +38,7 @@ TIPS_DISP tips_disp; tips_menu_def tips_menu; void lv_draw_wifi_tips() { - static lv_obj_t *text_tips,*wifi_name; + static lv_obj_t *text_tips, *wifi_name; scr = lv_screen_create(WIFI_TIPS_UI, ""); diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 1347f77f9a..3bd04563ba 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -714,7 +714,7 @@ void disp_assets_update_progress(const char *msg) { char buf[30]; memset(buf, ' ', COUNT(buf)); strncpy(buf, msg, strlen(msg)); - buf[COUNT(buf)-1] = '\0'; + buf[COUNT(buf) - 1] = '\0'; disp_string(100, 165, buf, 0xFFFF, 0x0000); } diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 2e24d6a2c0..8333709074 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -265,12 +265,12 @@ const char *bakPath = "_assets"; void spiFlashErase_PIC() { volatile uint32_t pic_sectorcnt = 0; W25QXX.init(SPI_QUARTER_SPEED); - //erase 0x001000 -64K + // erase 0x001000 -64K for (pic_sectorcnt = 0; pic_sectorcnt < (64 - 4) / 4; pic_sectorcnt++) { watchdog_refresh(); W25QXX.SPI_FLASH_SectorErase(PICINFOADDR + pic_sectorcnt * 4 * 1024); } - //erase 64K -- 6M + // erase 64K -- 6M for (pic_sectorcnt = 0; pic_sectorcnt < (PIC_SIZE_xM * 1024 / 64 - 1); pic_sectorcnt++) { watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase((pic_sectorcnt + 1) * 64 * 1024); @@ -281,7 +281,7 @@ void spiFlashErase_PIC() { void spiFlashErase_FONT() { volatile uint32_t Font_sectorcnt = 0; W25QXX.init(SPI_QUARTER_SPEED); - for (Font_sectorcnt = 0; Font_sectorcnt < 32-1; Font_sectorcnt++) { + for (Font_sectorcnt = 0; Font_sectorcnt < 32 - 1; Font_sectorcnt++) { watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase(FONTINFOADDR + Font_sectorcnt * 64 * 1024); } @@ -565,7 +565,7 @@ void Pic_Read(uint8_t *Pname, uint8_t *P_Rbuff) { W25QXX.SPI_FLASH_BufferRead(&PIC.name[j], PIC_NAME_ADDR + tmp_cnt, 1); tmp_cnt++; } while (PIC.name[j++] != '\0'); - //pic size + // pic size W25QXX.SPI_FLASH_BufferRead(PIC.size.bytes, PIC_SIZE_ADDR + i * 4, 4); if ((strcmp((char*)Pname, (char*)PIC.name)) == 0) { diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h index 90e2407ab0..95405af1cf 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -55,19 +55,19 @@ #define PIC_MAX_CN 100 // Maximum number of pictures #define PIC_NAME_MAX_LEN 50 // Picture name maximum length -#define LOGO_MAX_SIZE_TFT35 (300*1024) -#define LOGO_MAX_SIZE_TFT32 (150*1024) -#define TITLELOGO_MAX_SIZE (150*1024) // Little logo maximum -#define DEFAULT_VIEW_MAX_SIZE (200*200*2) -#define FLASH_VIEW_MAX_SIZE (200*200*2) +#define LOGO_MAX_SIZE_TFT35 (300 * 1024) +#define LOGO_MAX_SIZE_TFT32 (150 * 1024) +#define TITLELOGO_MAX_SIZE (150 * 1024) // Little logo maximum +#define DEFAULT_VIEW_MAX_SIZE (200 * 200 * 2) +#define FLASH_VIEW_MAX_SIZE (200 * 200 * 2) -#define PER_PIC_MAX_SPACE_TFT35 (9*1024) -#define PER_PIC_MAX_SPACE_TFT32 (16*1024) -#define PER_FONT_MAX_SPACE (16*1024) +#define PER_PIC_MAX_SPACE_TFT35 (9 * 1024) +#define PER_PIC_MAX_SPACE_TFT32 (16 * 1024) +#define PER_FONT_MAX_SPACE (16 * 1024) #if SPI_FLASH_SIZE == 0x200000 - //pic - //Robin_pro pic addr + // pic + // Robin_pro pic addr #define PIC_NAME_ADDR 0x001000 // Pic information addr #define PIC_SIZE_ADDR 0x001800 // Pic size information addr #define PIC_COUNTER_ADDR 0x002000 // Pic total number @@ -77,8 +77,8 @@ // TFT35 #define DEFAULT_VIEW_ADDR_TFT35 0x1EA070 - #define BAK_VIEW_ADDR_TFT35 (DEFAULT_VIEW_ADDR_TFT35+90*1024) - #define PIC_ICON_LOGO_ADDR_TFT35 (BAK_VIEW_ADDR_TFT35+80*1024) + #define BAK_VIEW_ADDR_TFT35 (DEFAULT_VIEW_ADDR_TFT35 + 90 * 1024) + #define PIC_ICON_LOGO_ADDR_TFT35 (BAK_VIEW_ADDR_TFT35 + 80 * 1024) #define PIC_DATA_ADDR_TFT35 0x003000 // (PIC_ICON_LOGO_ADDR_TFT35+350*1024) //0xC5800 #define PIC_DATA_ADDR_TFT32 0x00F000 @@ -87,11 +87,11 @@ // font #define FONTINFOADDR 0x150000 // 6M -- font addr - #define UNIGBK_FLASH_ADDR (FONTINFOADDR+4096) // 4*1024 + #define UNIGBK_FLASH_ADDR (FONTINFOADDR + 4096) // 4*1024 #else - //pic - //Robin_pro pic addr + // pic + // Robin_pro pic addr #define PIC_NAME_ADDR 0x003000 // Pic information addr #define PIC_SIZE_ADDR 0x007000 // Pic size information addr #define PIC_COUNTER_ADDR 0x008000 // Pic total number @@ -99,9 +99,9 @@ // TFT35 #define DEFAULT_VIEW_ADDR_TFT35 0xC5800 - #define BAK_VIEW_ADDR_TFT35 (DEFAULT_VIEW_ADDR_TFT35+90*1024) - #define PIC_ICON_LOGO_ADDR_TFT35 (BAK_VIEW_ADDR_TFT35+80*1024) - #define PIC_DATA_ADDR_TFT35 (PIC_ICON_LOGO_ADDR_TFT35+350*1024) //0xC5800 + #define BAK_VIEW_ADDR_TFT35 (DEFAULT_VIEW_ADDR_TFT35 + 90 * 1024) + #define PIC_ICON_LOGO_ADDR_TFT35 (BAK_VIEW_ADDR_TFT35 + 80 * 1024) + #define PIC_DATA_ADDR_TFT35 (PIC_ICON_LOGO_ADDR_TFT35 + 350 * 1024) // 0xC5800 // TFT32 #define PIC_DATA_ADDR_TFT32 0x02F000 @@ -110,20 +110,20 @@ // font #define FONTINFOADDR 0x600000 // 6M -- font addr - #define UNIGBK_FLASH_ADDR (FONTINFOADDR+4096) // 4*1024 - #define GBK_FLASH_ADDR (UNIGBK_FLASH_ADDR+180224) // 176*1024 + #define UNIGBK_FLASH_ADDR (FONTINFOADDR + 4096) // 4*1024 + #define GBK_FLASH_ADDR (UNIGBK_FLASH_ADDR + 180224) // 176*1024 #endif // Flash flag -#define REFLSHE_FLGA_ADD (0x800000-32) +#define REFLSHE_FLGA_ADD (0x800000 - 32) // SD card information first addr #define VAR_INF_ADDR 0x000000 #define FLASH_INF_VALID_FLAG 0x20201118 -//Store some gcode commands, such as auto leveling commands -#define GCODE_COMMAND_ADDR VAR_INF_ADDR + 3*1024 +// Store some gcode commands, such as auto leveling commands +#define GCODE_COMMAND_ADDR VAR_INF_ADDR + 3 * 1024 #define AUTO_LEVELING_COMMAND_ADDR GCODE_COMMAND_ADDR #define OTHERS_COMMAND_ADDR_1 AUTO_LEVELING_COMMAND_ADDR + 100 #define OTHERS_COMMAND_ADDR_2 OTHERS_COMMAND_ADDR_1 + 100 @@ -155,7 +155,7 @@ typedef struct pic_msg PIC_MSG; #define FONT_SIZE_xM 2 void Pic_Read(uint8_t *Pname, uint8_t *P_Rbuff); -void Pic_Logo_Read(uint8_t *LogoName,uint8_t *Logo_Rbuff,uint32_t LogoReadsize); +void Pic_Logo_Read(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize); void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size); uint32_t lv_get_pic_addr(uint8_t *Pname); void get_spi_flash_data(const char *rec_buf, int offset, int size); diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 3ca5d30e64..04d8f16fcc 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -55,7 +55,7 @@ void printer_state_polling() { gcode.process_subcommands_now_P(PSTR("M25")); - //save the position + // save the position uiCfg.current_x_position_bak = current_position.x; uiCfg.current_y_position_bak = current_position.y; uiCfg.current_z_position_bak = current_position.z; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h index e1a2a256d9..a41864eec4 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_en.h @@ -503,7 +503,7 @@ #define TEXT_WIFI_FORGET_EN "Forget Network" #define TEXT_DISCONECTED_EN "Wi-Fi Connected" -//wifi-list +// wifi-list #define MAIN_BUILT_EN "Build" #define MAIN_FILAMENT_EN "Filament" #define MAIN_SETUP_EN "Setup" @@ -512,7 +512,7 @@ #define FILE_MENU_BUILD_EN "Build" #define FILE_MENU_MENU_EN " < Menu" -//about +// about #define ABOUT_TITLE_EN "About" #define ABOUT_BUILT_MACHINES_EN "Built Machines" #define ABOUT_SPARK_EN "Spark" @@ -520,52 +520,52 @@ #define ABOUT_SERIAL_NUMBER_EN "Serial Number:" #define ABOUT_S_NUMBER_EN "DCPLX02KFC6P" -//set +// set #define SETUP_TITLE_EN "Setup" #define SETUP_WIFI_EN "Wi-Fi" #define SETUP_MANUAL_IP_EN "Manual IP" #define SETUP_WIFI_NOT_CONNECTED_EN "Not Connected" #define SETUP_WIFI_NETWORK_EN "WiFi_Network" -//build +// build #define BUILD_TITLE_EN "Build" #define BUILD_SD_CARD_EN "SD Card" #define BUILD_USB_DRIVE_EN "USB Drive" -//SD card +// SD card #define SD_CARD_TITLE_EN "SD Card" #define SD_CARD_BACK_EN "< Back" -//USB Drive +// USB Drive #define USB_DRIVE_TITLE_EN "USB Drive" #define USB_DRIVE_BACK_EN "< Back" #define FILE_PAGES_EN "%d/%d" #define FILE_NEXT_PAGE_EN "Next Page" #define MEDIA_SELECT_TITLE_EN "Select Media" -//BUILD PLATE +// BUILD PLATE #define PLATE_TITLE_EN "Build Plate" #define PLATE_BACK_EN "< Back" #define PLATE_CONFIRM_EN "Confirm >" #define PLATE_TIPS_EN "Confirm that there is a Clear\nBuild Plate installed in the\nmachine." -//build model +// build model #define MODEL_TITLE_EN "Build Model" #define MODEL_START_BUILD_EN "Start Build" #define MODEL_BACK_EN "< Back" -//building +// building #define BUILDING_TITLE_EN "Building" #define BUILDING_MENU_EN "Build Menu" #define BUILDING_COMPLETED "Build\nComplete" -//building menu +// building menu #define BUILDING_MENU_TITLE_EN "Build Menu" #define BUILDING_MENU_SETTINGS_EN "Build Settings" #define BUILDING_MENU_PAUSE_EN "Pause Build" #define BUILDING_MENU_CANCEL_EN "Cancel Build" #define BUILDING_MENU_BACK_EN "< Back" -//build settings +// build settings #define SETTINGS_TITLE_EN "Build Settings" #define SETTINGS_NOZZLE_TEMPER_EN "Nozzle Temp:" #define SETTINGS_NOZZLE_VALUE_EN "%d" @@ -575,13 +575,13 @@ #define SETTINGS_SPEED_VALUE_EN "Standard" #define SETTINGS_BACK_EN "< Back" -//build paused +// build paused #define PAUSED_TITLE_EN "Build Paused" #define PAUSED_RESUME_EN "Resume Build" #define PAUSED_CANCEL_EN "Cancel Build" #define PAUSED_BACK_EN "< Back" -//build cancel +// build cancel #define CANCEL_TITLE_EN "Cancel Build" #define CANCEL_BUILD_EN "Cancel Build" #define CANCEL_TIPS_EN "Are you sure you want to\ncancel this build? The model\nwill be deleted from this\nmachine. It will need to be\nresent from your computer\nbefore it can be built in the\nfuture." @@ -589,31 +589,31 @@ #define CANCEL_BUILD_DISPLAY_EN "Build\nCanceled" #define CANCEL_OVER_PLATE_TIPS_EN "Confirm that the Build Plate\nhas been removed from the\nmachine." -//filament model enter +// filament model enter #define FILAMENT_MODEL_ENTER_TITLE_EN "Model-PLA" #define FILAMENT_MODEL_ENTER_BACK_EN "< Back" #define FILAMENT_MODEL_ENTER_BEGIN_EN "Begin >" #define FILAMENT_MODEL_ENTER_TIPS_EN "The Model Filament spool\ncompartment is located on\nthe right side of the machine." -//filament model PLA +// filament model PLA #define FILAMENT_MODEL_PLA_TITLE_EN "Model-PLA" #define FILAMENT_PLA_LOAD_TITLE_EN "Load Filament" #define FILAMENT_PLA_UNLOAD_TITLE_EN "Unload Filament" #define FILAMENT_MODEL_PLA_LOAD_EN "Load Filament" #define FILAMENT_MODEL_PLA_UNLOAD_EN "Unload Filament" -//filament support enter +// filament support enter #define FILAMENT_SUPPORT_ENTER_TITLE_EN "Support-PVA" #define FILAMENT_SUPPORT_ENTER_BACK_EN "< Back" #define FILAMENT_SUPPORT_ENTER_BEGIN_EN "Begin >" #define FILAMENT_SUPPORT_ENTER_TIPS_EN "The Support Filament spool\ncompartment is located on\nthe left side of the machine." -//filament heating +// filament heating #define FILAMENT_HEATING_LOAD_TITLE_EN "Load Filament" #define FILAMENT_HEATING_UNLOAD_TITLE_EN "Unload Filament" #define FILAMENT_HEATING_CANCEL_EN "< Cancel" #define FILAMENT_HEATING_MATERIAL_EN "Material:" #define FILAMENT_HEATING_PLA_EN "Model-PLA" #define FILAMENT_HEATING_TIPS_EN "Print head is heating..." -//rotate left +// rotate left #define ROTATE_LEFT_LOAD_TITLE_EN "Load Filament" #define ROTATE_LEFT_UNLOAD_TITLE_EN "Unload Filament" #define ROTATE_LEFT_CANCEL_EN "< Cancel" @@ -622,7 +622,7 @@ #define ROTATE_LEFT_NEXT_EN "Next >" #define ROTATE_LEFT_TIPS_EN "Rotate extruder selection\ndial to the left." -//hang spool +// hang spool #define HANG_SPOOL_TITLE_EN "Load Filament" #define HANG_SPOOL_PREVIOUS_EN "< Previous" #define HANG_SPOOL_MATERIAL_EN "Material:" @@ -630,7 +630,7 @@ #define HANG_SPOOL_NEXT_EN "Next >" #define HANG_SPOOL_TIPS_EN "Hang the spool in the spool\ncompartment as shown." -//feed filament +// feed filament #define FEED_FILAMENT_TITLE_EN "Load Filament" #define FEED_FILAMENT_PREVIOUS_EN "< Previous" #define FEED_FILAMENT_MATERIAL_EN "Material:" @@ -638,7 +638,7 @@ #define FEED_FILAMENT_NEXT_EN "Next >" #define FEED_FILAMENT_TIPS_EN "Feed filament into extruder\nup beyond the gears." -//feed filament +// feed filament #define ROTATE_UP_TITLE_EN "Load Filament" #define ROTATE_UP_PREVIOUS_EN "< Previous" #define ROTATE_UP_MATERIAL_EN "Material:" @@ -646,20 +646,20 @@ #define ROTATE_UP_NEXT_EN "Next >" #define ROTATE_UP_TIPS_EN "Rotate extruder selection\ndial up." -//filament begin +// filament begin #define FEED_BEGIN_TITLE_EN "Load Filament" #define FEED_BEGIN_MATERIAL_EN "Material:" #define FEED_BEGIN_PLA_EN "Model-PLA" #define FEED_BEGIN_NEXT_EN "Next >" #define FEED_BEGIN_TIPS_EN "Press Next when filament\nbegins to extrude." -//filament finish +// filament finish #define FEED_FINISH_TITLE_EN "Load Filament" #define FEED_FINISH_MATERIAL_EN "Material:" #define FEED_FINISH_PLA_EN "Model-PLA" #define FEED_FINISH_NEXT_EN "Finish >" #define FEED_FINISH_TIPS_EN "Remove filament from the\nnozzle and discard." -//fiament remove +// fiament remove #define REMOVE_SPOOL_TITLE_EN "Unload Filament" #define REMOVE_SPOOL_PREVIOUS_EN "< Previous" #define REMOVE_SPOOL_FINISH_EN "Finish >" @@ -671,7 +671,7 @@ #define LOAD_FINISH_EN "Load\nFilament\nComplete" #define UNLOAD_FINISH_EN "Unload\nFilament\nComplete" -//manual ip +// manual ip #define MANUAL_IP_TITLE_EN "Manual IP" #define MANUAL_IP_CANCEL_EN "< Cancel" #define MANUAL_IP_APPLY_EN "Join >" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h index fd52f2cfa9..12c600f088 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_ru.h @@ -215,7 +215,7 @@ #define AUTO_SHUTDOWN_RU "авто-откл" #define MANUAL_SHUTDOWN_RU "ручн-откл" -#define DIALOG_CONFIRM_RU "да"//"подтвердить" +#define DIALOG_CONFIRM_RU "да" // "подтвердить" #define DIALOG_CANCLE_RU "отмена" #define DIALOG_OK_RU "да" #define DIALOG_RESET_RU "сброс" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 1cac49ffda..9a742e1f3b 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -241,8 +241,7 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co SPI_TFT.setWindow((uint16_t)area->x1, (uint16_t)area->y1, width, height); - for (uint16_t i = 0; i < height; i++) - SPI_TFT.tftio.WriteSequence((uint16_t*)(color_p + width * i), width); + SPI_TFT.tftio.WriteSequence((uint16_t*)color_p, width * height); lv_disp_flush_ready(disp); // Indicate you are ready with the flushing @@ -333,7 +332,7 @@ bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) { extern uint8_t currentFlashPage; -//spi_flash +// spi_flash uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0; lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { static char last_path_name[30]; @@ -382,7 +381,7 @@ lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p return LV_FS_RES_OK; } -//sd +// sd char *cur_namefff; uint32_t sd_read_base_addr = 0, sd_read_addr_offset = 0, small_image_size = 409; lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { diff --git a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h index 79faad74e2..0d0285f322 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h @@ -48,7 +48,7 @@ void disp_language_init(); #define MULTI_LANGUAGE_ENABLE 1 #define MULTI_LANGUAGE_DISABLE 0 -typedef struct machine_common_disp{ +typedef struct machine_common_disp { const char *default_value; const char *next; @@ -742,7 +742,7 @@ typedef struct pause_msg_disp { extern pause_msg_def pause_msg_menu; -typedef struct eeprom_disp{ +typedef struct eeprom_disp { const char *title; const char *store; const char *read; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h index 87de27c044..cf32bad396 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.h @@ -37,7 +37,7 @@ class WifiSerial { // Set up / tear down void begin(uint32_t baud); - void begin(uint32_t baud,uint8_t config); + void begin(uint32_t baud, uint8_t config); void end(); int available(void); int read(void); @@ -51,13 +51,13 @@ class WifiSerial { bool isHalfDuplex(void) const; void enableHalfDuplexRx(void); - private: - void setRx(uint32_t _rx); - void setTx(uint32_t _tx); - void setRx(PinName _rx); - void setTx(PinName _tx); - void init(PinName _rx, PinName _tx); - bool _rx_enabled; - uint8_t _config; - unsigned long _baud; + private: + void setRx(uint32_t _rx); + void setTx(uint32_t _tx); + void setRx(PinName _rx); + void setTx(PinName _tx); + void init(PinName _rx, PinName _tx); + bool _rx_enabled; + uint8_t _config; + unsigned long _baud; }; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp index 75830ce1bd..654fca6cb3 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp @@ -68,7 +68,8 @@ WifiSerial::WifiSerial(usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) { #define disable_timer_if_necessary(dev, ch) NOOP static void usart_enable_no_irq(usart_dev *usart_device, bool with_irq) { - if (with_irq) usart_enable(usart_device); + if (with_irq) + usart_enable(usart_device); else { usart_reg_map *regs = usart_device->regs; regs->CR1 |= (USART_CR1_TE | USART_CR1_RE); // Preserve word length, etc. Use 'or' to preserve USART_CR1_M_8N1 diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h index 6af2f9743b..d0fee4e3ac 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.h @@ -39,18 +39,18 @@ class WifiSerial { /* Set up/tear down */ void begin(uint32 baud); - void begin(uint32 baud,uint8_t config); + void begin(uint32 baud, uint8_t config); void end(); int available(); int read(); int write(uint8_t); inline void wifi_usart_irq(usart_reg_map *regs) { /* Handling RXNEIE and TXEIE interrupts. - * RXNE signifies availability of a byte in DR. - * - * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. - * We enable RXNEIE. - */ + * RXNE signifies availability of a byte in DR. + * + * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. + * We enable RXNEIE. + */ if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { #ifdef USART_SAFE_INSERT /* If the buffer is full and the user defines USART_SAFE_INSERT, @@ -63,15 +63,15 @@ class WifiSerial { } /* TXE signifies readiness to send a byte to DR. */ if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { - if (!rb_is_empty(this->usart_device->wb)) - regs->DR=rb_remove(this->usart_device->wb); - else - regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE + if (!rb_is_empty(this->usart_device->wb)) + regs->DR = rb_remove(this->usart_device->wb); + else + regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE } } int wifi_rb_is_full(); struct usart_dev *usart_device; - private: + private: uint8 tx_pin; uint8 rx_pin; }; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 70173691b0..0e937b2baa 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -55,13 +55,13 @@ #define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); #define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); -extern uint8_t Explore_Disk (char *path , uint8_t recu_level); +extern uint8_t Explore_Disk(char *path, uint8_t recu_level); extern uint8_t commands_in_queue; extern uint8_t sel_id; -extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); +extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); -volatile SZ_USART_FIFO WifiRxFifo; +volatile SZ_USART_FIFO WifiRxFifo; #define WAIT_ESP_TRANS_TIMEOUT_TICK 10500 @@ -487,7 +487,7 @@ static bool longName2DosName(const char *longName, char *dosName) { if (len > UDISKBUFLEN) return 0; if (wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { - const int timeOut = 2000; //millisecond + const int timeOut = 2000; // millisecond dmaTransmitBegin(); if (HAL_DMA_PollForTransferCustomize(&wifiUsartDMArx, HAL_DMA_FULL_TRANSFER, timeOut) == HAL_OK) { memcpy((unsigned char *) wifiDmaRcvFifo.bufferAddr[tmpW], (uint8_t *)bufToCpy, len); @@ -612,14 +612,14 @@ int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { return 0; } - if (len > 0) { + if (len > 0) { memcpy(&buf_to_wifi[4 + index_to_wifi], buf, len); index_to_wifi += len; if (index_to_wifi < 1) return 0; - if (buf_to_wifi[index_to_wifi + 3] == '\n') { + if (buf_to_wifi[index_to_wifi + 3] == '\n') { // mask "wait" "busy" "X:" if ( ((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't')) || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y')) @@ -768,7 +768,7 @@ int write_to_file(char *buf, int len) { if (res == -1) { ZERO(public_buf); file_writer.write_index = 0; - return -1; + return -1; } return 0; @@ -840,7 +840,7 @@ uint8_t Explore_Disk(char *path , uint8_t recu_level) { static void wifi_gcode_exec(uint8_t *cmd_line) { int8_t tempBuf[100] = { 0 }; uint8_t *tmpStr = 0; - int cmd_value; + int cmd_value; volatile int print_rate; if (strchr((char *)cmd_line, '\n') && (strchr((char *)cmd_line, 'G') || strchr((char *)cmd_line, 'M') || strchr((char *)cmd_line, 'T'))) { tmpStr = (uint8_t *)strchr((char *)cmd_line, '\n'); @@ -1492,7 +1492,7 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { memcpy(file_writer.saveFileName, msg + 5, fileNameLen); - utf8_2_unicode(file_writer.saveFileName,fileNameLen); + utf8_2_unicode(file_writer.saveFileName, fileNameLen); ZERO(public_buf); @@ -1745,7 +1745,7 @@ int32_t readWifiFifo(uint8_t *retBuf, uint32_t bufLen) { void stopEspTransfer() { if (wifi_link_state == WIFI_TRANS_FILE) - wifi_link_state = WIFI_CONNECTED; + wifi_link_state = WIFI_CONNECTED; TERN_(SDSUPPORT, card.closefile()); @@ -2015,8 +2015,8 @@ void get_wifi_commands() { if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { case 0 ... 1: - TERN_(ARC_SUPPORT, case 2 ... 3:) - TERN_(BEZIER_CURVE_SUPPORT, case 5:) + TERN_(ARC_SUPPORT, case 2 ... 3:) + TERN_(BEZIER_CURVE_SUPPORT, case 5:) SERIAL_ECHOLNPGM(STR_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); break; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index d02716e435..15b90ab367 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -56,7 +56,7 @@ #define UDISKBUFLEN 1024 -typedef enum{ +typedef enum { udisk_buf_empty = 0, udisk_buf_full, } UDISK_DATA_BUFFER_STATE; @@ -74,41 +74,41 @@ typedef struct { typedef struct { uint8_t flag; // 0x0: no error; 0x01: error - uint32_t start_tick; //error start time + uint32_t start_tick; // error start time uint32_t now_tick; } WIFI_TRANS_ERROR; extern volatile WIFI_TRANS_ERROR wifiTransError; typedef struct { - char ap_name[32]; //wifi-name - char keyCode[64]; //wifi password - int decodeType; - int baud; - int mode; + char ap_name[32]; // wifi-name + char keyCode[64]; // wifi password + int decodeType; + int baud; + int mode; } WIFI_PARA; typedef struct { char state; char hostUrl[96]; - int port; + int port; char id[21]; } CLOUD_PARA; typedef struct { - char dhcp_flag; - char ip_addr[16]; - char mask[16]; - char gate[16]; - char dns[16]; + char dhcp_flag; + char ip_addr[16]; + char mask[16]; + char gate[16]; + char dns[16]; - char dhcpd_flag; - char dhcpd_ip[16]; - char dhcpd_mask[16]; - char dhcpd_gate[16]; - char dhcpd_dns[16]; - char start_ip_addr[16]; - char end_ip_addr[16]; + char dhcpd_flag; + char dhcpd_ip[16]; + char dhcpd_mask[16]; + char dhcpd_gate[16]; + char dhcpd_dns[16]; + char start_ip_addr[16]; + char end_ip_addr[16]; } IP_PARA; typedef enum { @@ -144,8 +144,8 @@ extern volatile TRANSFER_STATE esp_state; typedef struct { char buf[20][80]; - int rd_index; - int wt_index; + int rd_index; + int wt_index; } QUEUE; typedef enum { diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index ff61315070..675e0eb666 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -36,7 +36,7 @@ #define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); #define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); -extern SZ_USART_FIFO WifiRxFifo; +extern SZ_USART_FIFO WifiRxFifo; extern int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); extern int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); @@ -301,7 +301,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t return stat; } else if (state == header) { - //store the header byte + // store the header byte hdr[hdrIdx++] = c; if (hdrIdx >= headerLength) { // get the body length, prepare a buffer for it @@ -423,7 +423,7 @@ EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint3 EspUploadResult Sync(uint16_t timeout) { uint8_t buf[36]; EspUploadResult stat; - int i ; + int i; // compose the data for the sync attempt memset(buf, 0x55, sizeof(buf)); @@ -449,8 +449,8 @@ EspUploadResult Sync(uint16_t timeout) { if (rc != success || bodyLen != 2) break; } } - //DEBUG - //else debug//printf("stat=%d\n", (int)stat); + // DEBUG + //else printf("stat=%d\n", (int)stat); return stat; } From 46dfc7ba341325d4e9a69e7e8979215b90e79334 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 17 Sep 2021 01:06:26 +0000 Subject: [PATCH 0692/2168] [cron] Bump distribution date (2021-09-17) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 2e2dc18701..a9073c0a49 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-16" +//#define STRING_DISTRIBUTION_DATE "2021-09-17" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 119617e59e..942626cec2 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 "2021-09-16" + #define STRING_DISTRIBUTION_DATE "2021-09-17" #endif /** From 11fce69781efb4e377f5349e14263a3466ba325d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 18 Sep 2021 00:58:51 +0000 Subject: [PATCH 0693/2168] [cron] Bump distribution date (2021-09-18) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a9073c0a49..6b091c0f45 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-17" +//#define STRING_DISTRIBUTION_DATE "2021-09-18" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 942626cec2..b36f29bf99 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 "2021-09-17" + #define STRING_DISTRIBUTION_DATE "2021-09-18" #endif /** From fede20fbe69d4d3687a07b4a9cb70b681f5c51b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Sep 2021 18:58:55 -0500 Subject: [PATCH 0694/2168] =?UTF-8?q?=F0=9F=92=AC=20Add=20non-translated?= =?UTF-8?q?=20STR=5FDONE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/language.h | 1 + Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 ++-- Marlin/src/gcode/config/M43.cpp | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 3341656671..7588a7b28c 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -165,6 +165,7 @@ #define STR_SAVED_POS "Position saved" #define STR_RESTORING_POS "Restoring position" #define STR_INVALID_POS_SLOT "Invalid slot. Total: " +#define STR_DONE "Done." #define STR_SD_CANT_OPEN_SUBDIR "Cannot open subdir " #define STR_SD_INIT_FAIL "No SD card" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 747c61a8b9..750c63f7c6 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -609,7 +609,7 @@ void unified_bed_leveling::G29() { settings.load_mesh(param.KLS_storage_slot); storage_slot = param.KLS_storage_slot; - SERIAL_ECHOLNPGM("Done."); + SERIAL_ECHOLNPGM(STR_DONE); } // @@ -637,7 +637,7 @@ void unified_bed_leveling::G29() { settings.store_mesh(param.KLS_storage_slot); storage_slot = param.KLS_storage_slot; - SERIAL_ECHOLNPGM("Done."); + SERIAL_ECHOLNPGM(STR_DONE); } if (parser.seen_test('T')) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index b2455c4b60..08b45efa15 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -112,7 +112,7 @@ inline void toggle_pins() { } SERIAL_EOL(); } - SERIAL_ECHOLNPGM("Done."); + SERIAL_ECHOLNPGM(STR_DONE); } // toggle_pins From ad38699c115585134841b479a112f723e17d0b17 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Apr 2021 17:08:57 -0500 Subject: [PATCH 0695/2168] =?UTF-8?q?=F0=9F=9A=B8=20Better=20bed=20positio?= =?UTF-8?q?n?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 20 ++++++++++---------- Marlin/src/lcd/dogm/status/bed.h | 11 +++++------ 2 files changed, 15 insertions(+), 16 deletions(-) diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index dfbf7b4291..f17dd06365 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -480,7 +480,7 @@ #endif #ifndef STATUS_CUTTER_TEXT_X - #define STATUS_CUTTER_TEXT_X (STATUS_CUTTER_X -1) + #define STATUS_CUTTER_TEXT_X (STATUS_CUTTER_X - 1) #endif #ifndef STATUS_CUTTER_TEXT_Y @@ -488,12 +488,12 @@ #endif static_assert( - sizeof(status_cutter_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(0)), + sizeof(status_cutter_bmp) == (STATUS_CUTTER_BYTEWIDTH) * STATUS_CUTTER_HEIGHT(0), "Status cutter bitmap (status_cutter_bmp) dimensions don't match data." ); #ifdef STATUS_CUTTER_ANIM static_assert( - sizeof(status_cutter_on_bmp) == (STATUS_CUTTER_BYTEWIDTH) * (STATUS_CUTTER_HEIGHT(1)), + sizeof(status_cutter_on_bmp) == (STATUS_CUTTER_BYTEWIDTH) * STATUS_CUTTER_HEIGHT(1), "Status cutter bitmap (status_cutter_on_bmp) dimensions don't match data." ); #endif @@ -530,12 +530,12 @@ #endif static_assert( - sizeof(status_chamber_bmp) == (STATUS_CHAMBER_BYTEWIDTH) * (STATUS_CHAMBER_HEIGHT(0)), + sizeof(status_chamber_bmp) == (STATUS_CHAMBER_BYTEWIDTH) * STATUS_CHAMBER_HEIGHT(0), "Status chamber bitmap (status_chamber_bmp) dimensions don't match data." ); #ifdef STATUS_CHAMBER_ANIM static_assert( - sizeof(status_chamber_on_bmp) == (STATUS_CHAMBER_BYTEWIDTH) * (STATUS_CHAMBER_HEIGHT(1)), + sizeof(status_chamber_on_bmp) == (STATUS_CHAMBER_BYTEWIDTH) * STATUS_CHAMBER_HEIGHT(1), "Status chamber bitmap (status_chamber_on_bmp) dimensions don't match data." ); #endif @@ -565,12 +565,12 @@ #endif static_assert( - sizeof(status_cooler_bmp1) == (STATUS_COOLER_BYTEWIDTH) * (STATUS_COOLER_HEIGHT(0)), + sizeof(status_cooler_bmp1) == (STATUS_COOLER_BYTEWIDTH) * STATUS_COOLER_HEIGHT(0), "Status cooler bitmap (status_cooler_bmp1) dimensions don't match data." ); #ifdef STATUS_COOLER_ANIM static_assert( - sizeof(status_cooler_bmp2) == (STATUS_COOLER_BYTEWIDTH) * (STATUS_COOLER_HEIGHT(1)), + sizeof(status_cooler_bmp2) == (STATUS_COOLER_BYTEWIDTH) * STATUS_COOLER_HEIGHT(1), "Status cooler bitmap (status_cooler_bmp2) dimensions don't match data." ); #endif @@ -647,7 +647,7 @@ #if STATUS_BED_WIDTH && !STATUS_HEATERS_WIDTH #ifndef STATUS_BED_X - #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_BED_BYTEWIDTH) * 8) + #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_BED_BYTEWIDTH) * 8 - TERN0(STATUS_HEAT_PERCENT, 4)) #endif #ifndef STATUS_BED_HEIGHT @@ -667,12 +667,12 @@ #endif static_assert( - sizeof(status_bed_bmp) == (STATUS_BED_BYTEWIDTH) * (STATUS_BED_HEIGHT(0)), + sizeof(status_bed_bmp) == (STATUS_BED_BYTEWIDTH) * STATUS_BED_HEIGHT(0), "Status bed bitmap (status_bed_bmp) dimensions don't match data." ); #ifdef STATUS_BED_ANIM static_assert( - sizeof(status_bed_on_bmp) == (STATUS_BED_BYTEWIDTH) * (STATUS_BED_HEIGHT(1)), + sizeof(status_bed_on_bmp) == (STATUS_BED_BYTEWIDTH) * STATUS_BED_HEIGHT(1), "Status bed bitmap (status_bed_on_bmp) dimensions don't match data." ); #endif diff --git a/Marlin/src/lcd/dogm/status/bed.h b/Marlin/src/lcd/dogm/status/bed.h index c484a12929..175a50e341 100644 --- a/Marlin/src/lcd/dogm/status/bed.h +++ b/Marlin/src/lcd/dogm/status/bed.h @@ -29,9 +29,7 @@ #define STATUS_BED_ANIM #define STATUS_BED_WIDTH 24 - #ifndef STATUS_BED_X - #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) - #endif + #define STATUS_BED_TEXT_X (STATUS_BED_X + 11) const unsigned char status_bed_bmp[] PROGMEM = { @@ -62,9 +60,6 @@ #else #define STATUS_BED_WIDTH 21 - #ifndef STATUS_BED_X - #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) - #endif #ifdef STATUS_BED_ANIM @@ -108,3 +103,7 @@ #endif #endif + +#ifndef STATUS_BED_X + #define STATUS_BED_X (LCD_PIXEL_WIDTH - (STATUS_BED_BYTEWIDTH + STATUS_CHAMBER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8 - TERN0(STATUS_HEAT_PERCENT, 4)) +#endif From f46e05fcb1e8b9a4ed36d2caa09122e75188e9da Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Sep 2021 19:09:54 -0500 Subject: [PATCH 0696/2168] =?UTF-8?q?=F0=9F=9A=B8=20Move=20fade=20item=20u?= =?UTF-8?q?p?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_ubl.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index dae2c42047..03aec39c83 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -666,6 +666,10 @@ void _lcd_ubl_level_bed() { GCODES_ITEM(MSG_UBL_DEACTIVATE_MESH, PSTR("G29D")); else GCODES_ITEM(MSG_UBL_ACTIVATE_MESH, PSTR("G29A")); + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + editable.decimal = planner.z_fade_height; + EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); + #endif #if ENABLED(G26_MESH_VALIDATION) SUBMENU(MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); #endif @@ -677,10 +681,6 @@ void _lcd_ubl_level_bed() { SUBMENU(MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); SUBMENU(MSG_UBL_TOOLS, _menu_ubl_tools); GCODES_ITEM(MSG_UBL_INFO_UBL, PSTR("G29W")); - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - editable.decimal = planner.z_fade_height; - EDIT_ITEM_FAST(float3, MSG_Z_FADE_HEIGHT, &editable.decimal, 0, 100, []{ set_z_fade_height(editable.decimal); }); - #endif END_MENU(); } From d7e597f3df11df9a01b432715d7d9865e578a4e6 Mon Sep 17 00:00:00 2001 From: Steven Haigh Date: Sat, 18 Sep 2021 16:33:18 +1000 Subject: [PATCH 0697/2168] =?UTF-8?q?=F0=9F=90=9B=20STM32=20ADC=20Resoluti?= =?UTF-8?q?on=20=3D=2012=20bit=20(or=20ADC=5FRESOLUTION)=20(#22789)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.h | 7 ++++++- Marlin/src/HAL/STM32F1/HAL.h | 7 ++++++- ini/stm32-common.ini | 1 - 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 7a04c9ceeb..a68e8a8c0e 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -183,8 +183,13 @@ static inline int freeMemory() { #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif + #define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION ADC_RESOLUTION // 12 #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_READ_ADC() HAL_adc_result #define HAL_ADC_READY() true diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 1d30f43c48..3bdfb9703c 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -237,8 +237,13 @@ static inline int freeMemory() { void HAL_adc_init(); +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif + #define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 #define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) #define HAL_READ_ADC() HAL_adc_result #define HAL_ADC_READY() true diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 1d3f858bf8..54bc746ff4 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -16,7 +16,6 @@ build_flags = ${common.build_flags} -std=gnu++14 -DHAL_STM32 -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 - -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + + extra_scripts = ${common.extra_scripts} From f367a3987de2703965b2b043b191d6ed77648e6d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 18 Sep 2021 18:22:15 -0500 Subject: [PATCH 0698/2168] =?UTF-8?q?=F0=9F=93=9D=20Update=20some=20pins?= =?UTF-8?q?=20comments?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/esp32/pins_E4D.h | 9 +++++---- Marlin/src/pins/esp32/pins_FYSETC_E4.h | 3 ++- Marlin/src/pins/esp32/pins_MRR_ESPA.h | 3 ++- Marlin/src/pins/esp32/pins_MRR_ESPE.h | 3 ++- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 6 +----- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 4 ++++ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 4 ++++ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 4 ++++ Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 4 ++++ Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 2 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 2 +- Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 ++++ Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h | 4 ++++ Marlin/src/pins/lpc1769/pins_FLY_CDY.h | 4 ++++ Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 2 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 2 +- Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 2 +- 17 files changed, 45 insertions(+), 17 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 9e28af2190..54621f36c1 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -22,9 +22,10 @@ #pragma once /** - * E4d@Box pin assignments - * E4d@Box is a small factor 3D printer control board based on the ESP32 microcontroller for Laser, CNC and 3d printers - * for more info check https://atbox.tech/ and join to Facebook page E4d@box. + * E4d@box pin assignments + * + * Small factor 3D printer control board based on the ESP32 microcontroller for Laser, CNC and 3D printers. + * More info at https://atbox.tech/ and the E4d@box Facebook page. */ #include "env_validate.h" @@ -35,7 +36,7 @@ #error "E4d@box only supports one hotend / E-stepper. Comment out this line to continue." #endif -#define BOARD_INFO_NAME "E4D@BOX" +#define BOARD_INFO_NAME "E4d@box" #define BOARD_WEBSITE_URL "github.com/Exilaus/E4d@box" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h index 7dd7f94ae5..2b2fe40c4a 100644 --- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -23,7 +23,8 @@ /** * FYSETC E4 pin assignments - * FYSETC E4 is a 3D printer control board based on the ESP32 microcontroller. + * + * 3D printer control board based on the ESP32 microcontroller. * Supports 4 stepper drivers, heated bed, single hotend. */ diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index 38f43b53d3..ab4f401f26 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -23,7 +23,8 @@ /** * MRR ESPA pin assignments - * MRR ESPA is a 3D printer control board based on the ESP32 microcontroller. + * + * 3D printer control board based on the ESP32 microcontroller. * Supports 4 stepper drivers, heated bed, single hotend. */ diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index 8b4ec8b197..1f829b7755 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -23,7 +23,8 @@ /** * MRR ESPE pin assignments - * MRR ESPE is a 3D printer control board based on the ESP32 microcontroller. + * + * 3D printer control board based on the ESP32 microcontroller. * Supports 5 stepper drivers (using I2S stepper stream), heated bed, * single hotend, and LCD controller. */ diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index f94381e13a..92152170a0 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -22,11 +22,7 @@ #pragma once /** - * BIQU BQ111-A4 - * - * Applies to the following boards: - * - * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) + * BIQU BQ111-A4 pin assignments */ #include "env_validate.h" 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 6404fbbf25..48b178dab5 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * BigTreeTech SKR 1.1 pin assignments + */ + #define BOARD_INFO_NAME "BTT SKR V1.1" // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 56944273e3..dc52a7c36d 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * BigTreeTech SKR 1.3 pin assignments + */ + #define BOARD_INFO_NAME "BTT SKR V1.3" #define LPC1768_IS_SKRV1_3 1 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 56d548847c..17daf176da 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * BigTreeTech SKR 1.4 pin assignments + */ + #include "env_validate.h" #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index eee3ede713..39ab0bbd89 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * GMARSH X6 Rev.1 pin assignments + */ + #include "env_validate.h" #define BOARD_INFO_NAME "GMARSH X6 REV1" diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index a9701bc8b5..258ecd107b 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS SBASE pin assignments + * Makerbase MKS SBASE pin assignments */ #include "env_validate.h" diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index fe2a71ae03..d6b1eeab46 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS SGEN-L pin assignments + * Makerbase MKS SGEN-L pin assignments */ #include "env_validate.h" diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 8b855e8d01..9c514f8ca3 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * BigTreeTech SKR E3 Turbo pin assignments + */ + #include "env_validate.h" #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index 5af1dfec3f..2b847d339f 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * BigTreeTech SKR 1.4 Turbo pin assignments + */ + #define BOARD_INFO_NAME "BTT SKR V1.4 TURBO" // diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index 535fb32e3e..ec0b14af90 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * FLYmaker FLY-CDY pin assignments + */ + #include "env_validate.h" #define BOARD_INFO_NAME "FLY-CDY" diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index f5c158162c..23bcecc78d 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -24,7 +24,7 @@ /** * MKS SGen pin assignments * - * The pins diagram can be found and the following URL: + * Pins diagram: * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf */ diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 124f0301b1..bb39009f09 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -22,7 +22,7 @@ #pragma once /** - * MKS SGen pin assignments + * MKS SGen-L V2 pin assignments */ #include "env_validate.h" diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index f7bc9602d7..e80116efd0 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -22,7 +22,7 @@ #pragma once /** - * Smoothieboard pin assignments + * Smoothieware Smoothieboard pin assignments */ #include "env_validate.h" From c88e85c939afe4f024fcb24ca6a68950d36ec901 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 18 Sep 2021 18:24:39 -0500 Subject: [PATCH 0699/2168] =?UTF-8?q?=F0=9F=8E=A8=20Replace=20some=20infre?= =?UTF-8?q?quently-used=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/tft/tft_spi.cpp | 45 ++++++------------------ Marlin/src/HAL/STM32F1/tft/tft_spi.cpp | 48 ++++++-------------------- 2 files changed, 21 insertions(+), 72 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index a2cb66ab5b..a9847b2d2f 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -26,39 +26,22 @@ #include "tft_spi.h" -//TFT_SPI tft; - SPIClass TFT_SPI::SPIx(1); -#define TFT_CS_H WRITE(TFT_CS_PIN, HIGH) -#define TFT_CS_L WRITE(TFT_CS_PIN, LOW) - -#define TFT_DC_H WRITE(TFT_DC_PIN, HIGH) -#define TFT_DC_L WRITE(TFT_DC_PIN, LOW) - -#define TFT_RST_H WRITE(TFT_RESET_PIN, HIGH) -#define TFT_RST_L WRITE(TFT_RESET_PIN, LOW) - -#define TFT_BLK_H WRITE(TFT_BACKLIGHT_PIN, HIGH) -#define TFT_BLK_L WRITE(TFT_BACKLIGHT_PIN, LOW) - void TFT_SPI::Init() { #if PIN_EXISTS(TFT_RESET) - SET_OUTPUT(TFT_RESET_PIN); - TFT_RST_H; + OUT_WRITE(TFT_RESET_PIN, HIGH); delay(100); #endif #if PIN_EXISTS(TFT_BACKLIGHT) - SET_OUTPUT(TFT_BACKLIGHT_PIN); - TFT_BLK_H; + OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif SET_OUTPUT(TFT_DC_PIN); SET_OUTPUT(TFT_CS_PIN); - - TFT_DC_H; - TFT_CS_H; + WRITE(TFT_DC_PIN, HIGH); + WRITE(TFT_CS_PIN, HIGH); /** * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz @@ -97,7 +80,7 @@ void TFT_SPI::Init() { void TFT_SPI::DataTransferBegin(uint16_t DataSize) { SPIx.setDataSize(DataSize); SPIx.begin(); - TFT_CS_L; + WRITE(TFT_CS_PIN, LOW); } uint32_t TFT_SPI::GetID() { @@ -116,7 +99,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { SPIx.setDataSize(DATASIZE_8BIT); SPIx.setClock(SPI_CLOCK_DIV64); SPIx.begin(); - TFT_CS_L; + WRITE(TFT_CS_PIN, LOW); WriteReg(Reg); LOOP_L_N(i, 4) { @@ -131,21 +114,15 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { return data >> 7; } -bool TFT_SPI::isBusy() { - return false; -} +bool TFT_SPI::isBusy() { return false; } -void TFT_SPI::Abort() { - DataTransferEnd(); -} +void TFT_SPI::Abort() { DataTransferEnd(); } -void TFT_SPI::Transmit(uint16_t Data) { - SPIx.transfer(Data); -} +void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); } void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DataTransferBegin(DATASIZE_16BIT); //16 - TFT_DC_H; + DataTransferBegin(DATASIZE_16BIT); + WRITE(TFT_DC_PIN, HIGH); SPIx.dmaSend(Data, Count, MemoryIncrease); DataTransferEnd(); } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 5edf96fe56..9bf6bbb32b 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -26,36 +26,20 @@ #include "tft_spi.h" -// TFT_SPI tft; - SPIClass TFT_SPI::SPIx(1); -#define TFT_CS_H OUT_WRITE(TFT_CS_PIN, HIGH) -#define TFT_CS_L OUT_WRITE(TFT_CS_PIN, LOW) - -#define TFT_DC_H OUT_WRITE(TFT_DC_PIN, HIGH) -#define TFT_DC_L OUT_WRITE(TFT_DC_PIN, LOW) - -#define TFT_RST_H OUT_WRITE(TFT_RST_PIN, HIGH) -#define TFT_RST_L OUT_WRITE(TFT_RST_PIN, LOW) - -#define TFT_BLK_H OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH) -#define TFT_BLK_L OUT_WRITE(TFT_BACKLIGHT_PIN, LOW) - void TFT_SPI::Init() { #if PIN_EXISTS(TFT_RESET) - // OUT_WRITE(TFT_RESET_PIN, HIGH); - TFT_RST_H; + OUT_WRITE(TFT_RST_PIN, HIGH); delay(100); #endif #if PIN_EXISTS(TFT_BACKLIGHT) - // OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - TFT_BLK_H; + OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif - TFT_DC_H; - TFT_CS_H; + OUT_WRITE(TFT_DC_PIN, HIGH); + OUT_WRITE(TFT_CS_PIN, HIGH); /** * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz @@ -87,7 +71,7 @@ void TFT_SPI::Init() { void TFT_SPI::DataTransferBegin(uint16_t DataSize) { SPIx.setDataSize(DataSize); SPIx.begin(); - TFT_CS_L; + OUT_WRITE(TFT_CS_PIN, LOW); } #ifdef TFT_DEFAULT_DRIVER @@ -129,28 +113,16 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { #endif } -bool TFT_SPI::isBusy() { - return false; -} +bool TFT_SPI::isBusy() { return false; } -void TFT_SPI::Abort() { - DataTransferEnd(); -} +void TFT_SPI::Abort() { DataTransferEnd(); } -void TFT_SPI::Transmit(uint16_t Data) { - SPIx.send(Data); -} +void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); } void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { DataTransferBegin(); - TFT_DC_H; - if (MemoryIncrease == DMA_MINC_ENABLE) { - SPIx.dmaSend(Data, Count, true); - } - else { - SPIx.dmaSend(Data, Count, false); - } - + OUT_WRITE(TFT_DC_PIN, HIGH); + SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE); DataTransferEnd(); } From 89125cd32ea913152dcdfe0edfa1571027f44e2d Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 19 Sep 2021 01:27:58 +0200 Subject: [PATCH 0700/2168] =?UTF-8?q?=F0=9F=9A=B8=20Wake=20up=20TFT=20for?= =?UTF-8?q?=20some=20events=20(#22788)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 2 ++ Marlin/src/lcd/menu/menu_media.cpp | 1 + 2 files changed, 3 insertions(+) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 369413d3a6..b1cb030025 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1444,6 +1444,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::set_alert_status_P(PGM_P const message) { set_status_P(message, 1); + TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); TERN_(HAS_LCD_MENU, return_to_status()); } @@ -1557,6 +1558,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; defer_status_screen(); #endif + TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); LCD_MESSAGEPGM(MSG_PRINT_PAUSED); diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 1866426a65..213ad257b8 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -48,6 +48,7 @@ void lcd_sd_updir() { goto_screen(menu_media, sd_encoder_position, sd_top_line, sd_items); sd_encoder_position = 0xFFFF; defer_status_screen(); + TERN_(HAS_TOUCH_SLEEP, ui.wakeup_screen()); } #endif From a6b69ab6d518488fd87109d9ba7ecf2e82b7f2a9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 19 Sep 2021 01:01:05 +0000 Subject: [PATCH 0701/2168] [cron] Bump distribution date (2021-09-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6b091c0f45..727ca38d89 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-18" +//#define STRING_DISTRIBUTION_DATE "2021-09-19" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b36f29bf99..16ab0c5458 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 "2021-09-18" + #define STRING_DISTRIBUTION_DATE "2021-09-19" #endif /** From 10fda222ea40af91ff1244ad5b7c8737043e1011 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 19 Sep 2021 05:16:29 +0200 Subject: [PATCH 0702/2168] =?UTF-8?q?=F0=9F=90=9B=20STM32=20ADC=20followup?= =?UTF-8?q?=20(#22798)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/HAL.h | 8 ++++---- Marlin/src/HAL/STM32F1/HAL.cpp | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index ca4e2decab..f241249804 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -156,17 +156,17 @@ int freeMemory(); using FilteredADC = LPC176x::ADC; extern uint32_t HAL_adc_reading; -[[gnu::always_inline]] inline void HAL_start_adc(const pin_t pin) { +[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits } -[[gnu::always_inline]] inline uint16_t HAL_read_adc() { +[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { return HAL_adc_reading; } #define HAL_adc_init() #define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) -#define HAL_START_ADC(pin) HAL_start_adc(pin) -#define HAL_READ_ADC() HAL_read_adc() +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() #define HAL_ADC_READY() (true) // Test whether the pin is valid diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 73014945a1..df1ba33d4a 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -437,7 +437,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break; #endif } - HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only. + HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } uint16_t HAL_adc_get_result() { return HAL_adc_result; } From c1d7e234e1aba1ecc91cfc77d17d38b67618c315 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Sep 2021 18:40:56 -0500 Subject: [PATCH 0703/2168] =?UTF-8?q?=F0=9F=8C=90=20Reduce=20language=20fi?= =?UTF-8?q?le=20sizes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/multi_language.h | 47 +- Marlin/src/lcd/language/language_an.h | 362 ++--- Marlin/src/lcd/language/language_bg.h | 238 +-- Marlin/src/lcd/language/language_ca.h | 352 ++-- Marlin/src/lcd/language/language_cz.h | 1066 ++++++------ Marlin/src/lcd/language/language_da.h | 302 ++-- Marlin/src/lcd/language/language_de.h | 1174 +++++++------- Marlin/src/lcd/language/language_el.h | 340 ++-- Marlin/src/lcd/language/language_el_gr.h | 330 ++-- Marlin/src/lcd/language/language_en.h | 1370 ++++++++-------- Marlin/src/lcd/language/language_es.h | 1098 ++++++------- Marlin/src/lcd/language/language_eu.h | 554 +++---- Marlin/src/lcd/language/language_fi.h | 180 +- Marlin/src/lcd/language/language_fr.h | 1176 +++++++------- Marlin/src/lcd/language/language_gl.h | 1126 ++++++------- Marlin/src/lcd/language/language_hr.h | 234 +-- Marlin/src/lcd/language/language_hu.h | 1336 +++++++-------- Marlin/src/lcd/language/language_it.h | 1316 +++++++-------- Marlin/src/lcd/language/language_jp_kana.h | 424 ++--- Marlin/src/lcd/language/language_ko_KR.h | 138 +- Marlin/src/lcd/language/language_nl.h | 342 ++-- Marlin/src/lcd/language/language_pl.h | 1258 +++++++------- Marlin/src/lcd/language/language_pt.h | 260 +-- Marlin/src/lcd/language/language_pt_br.h | 878 +++++----- Marlin/src/lcd/language/language_ro.h | 1146 ++++++------- Marlin/src/lcd/language/language_ru.h | 1444 ++++++++--------- Marlin/src/lcd/language/language_sk.h | 1348 +++++++-------- Marlin/src/lcd/language/language_sv.h | 1258 +++++++------- Marlin/src/lcd/language/language_test.h | 180 +- Marlin/src/lcd/language/language_tr.h | 1056 ++++++------ Marlin/src/lcd/language/language_uk.h | 1430 ++++++++-------- Marlin/src/lcd/language/language_vi.h | 806 ++++----- Marlin/src/lcd/language/language_zh_CN.h | 1146 ++++++------- Marlin/src/lcd/language/language_zh_TW.h | 904 +++++------ .../share/scripts/findMissingTranslations.sh | 39 +- 35 files changed, 13337 insertions(+), 13321 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 5063faf60c..8a85f83dd4 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -1,28 +1,35 @@ -/******************** - * multi_language.h * - ********************/ - -/**************************************************************************** - * Written By Marcio Teixeira 2019 - Aleph Objects, Inc. * - * * - * 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. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ +/** + * 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 +/******************************************************* + * multi_language.h * + * By Marcio Teixeira 2019 for Aleph Objects * + *******************************************************/ + #include "../inc/MarlinConfigPre.h" typedef const char Language_Str[]; +#define LSTR PROGMEM Language_Str #ifdef LCD_LANGUAGE_5 #define NUM_LANGUAGES 5 diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 1bc6d75f3b..7d0ff7320f 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -34,191 +34,191 @@ namespace Language_an { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Aragonese"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Aragonese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" parada."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tarcheta mesa"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarcheta sacada"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu prencipal"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inicio automatico"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Amortar motors"); - PROGMEM Language_Str MSG_HOMING = _UxGT("Orichen"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Levar a l'orichen"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Orichen X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Orichen Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Orichen Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Orichen XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Encetar (pretar)"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Vinient punto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivelacion feita!"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Achustar desfases"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicau"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Establir orichen"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" parada."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Tarcheta mesa"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Tarcheta sacada"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Menu prencipal"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Inicio automatico"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Amortar motors"); + LSTR MSG_HOMING = _UxGT("Orichen"); + LSTR MSG_AUTO_HOME = _UxGT("Levar a l'orichen"); + LSTR MSG_AUTO_HOME_X = _UxGT("Orichen X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Orichen Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Orichen Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Orichen XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Encetar (pretar)"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Vinient punto"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivelacion feita!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Achustar desfases"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicau"); + LSTR MSG_SET_ORIGIN = _UxGT("Establir orichen"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Precalentar ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Precalentar ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Boquilla"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Boquilla ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Tot"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Base"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Precalentar ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Precalentar ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Boquilla"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Boquilla ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Tot"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Base"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Precalentar ") PREHEAT_1_LABEL _UxGT(" Conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Precalentar $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Precalentar $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Precal. $ Boquilla"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Precal. $ Boquilla ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Precalentar $ Tot"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Precalentar $ Base"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Precalentar $ Conf"); + LSTR MSG_PREHEAT_M = _UxGT("Precalentar $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Precalentar $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Precal. $ Boquilla"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Precal. $ Boquilla ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Precalentar $ Tot"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Precalentar $ Base"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Precalentar $ Conf"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Enfriar"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Enchegar Fuent"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Amortar Fuent"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruir"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retraer"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover Eixes"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelar base"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar base"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidat"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Boquilla ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Base"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Ixoriador"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Ixoriador ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxo"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxo ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Trigar"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Trigar *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Aceleracion"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viache min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Acel. max ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Acel. max ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Acel. max ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Acel. max ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Acel. max *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acel. retrac."); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acel. Viaje"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Trangos/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" trangos/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E trangos/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* trangos/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movimiento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Alzar memoria"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar memoria"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restaurar memoria"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Tornar a cargar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Informacion"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Achustar"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresion"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Contin. impresion"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Detener Impresion"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Menu de SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No i hai tarcheta"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Reposo..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Aguardand ordines"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impres. cancelada"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sin movimiento"); - PROGMEM Language_Str MSG_KILLED = _UxGT("Aturada d'emerch."); - PROGMEM Language_Str MSG_STOPPED = _UxGT("Aturada."); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Retraer mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraer F"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Devantar mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet F"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Retraccion auto."); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambear filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambear filamento *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Encetan. tarcheta"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar tarcheta"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z fuera"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Error: en calentar"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Error: temperatura"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Error de temperatura"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Error: Temp Max"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Error: Temp Min"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA ATURADA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Per favor reinic."); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Calentando..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Calentando base..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + LSTR MSG_COOLDOWN = _UxGT("Enfriar"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Enchegar Fuent"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Amortar Fuent"); + LSTR MSG_EXTRUDE = _UxGT("Extruir"); + LSTR MSG_RETRACT = _UxGT("Retraer"); + LSTR MSG_MOVE_AXIS = _UxGT("Mover Eixes"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelar base"); + LSTR MSG_LEVEL_BED = _UxGT("Nivelar base"); + LSTR MSG_MOVE_X = _UxGT("Mover X"); + LSTR MSG_MOVE_Y = _UxGT("Mover Y"); + LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_E = _UxGT("Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mover 100mm"); + LSTR MSG_SPEED = _UxGT("Velocidat"); + LSTR MSG_BED_Z = _UxGT("Base Z"); + LSTR MSG_NOZZLE = _UxGT("Boquilla"); + LSTR MSG_NOZZLE_N = _UxGT("Boquilla ~"); + LSTR MSG_BED = _UxGT("Base"); + LSTR MSG_FAN_SPEED = _UxGT("Ixoriador"); + LSTR MSG_FAN_SPEED_N = _UxGT("Ixoriador ~"); + LSTR MSG_FLOW = _UxGT("Fluxo"); + LSTR MSG_FLOW_N = _UxGT("Fluxo ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_AUTOTEMP = _UxGT("Temperatura Auto."); + LSTR MSG_SELECT = _UxGT("Trigar"); + LSTR MSG_SELECT_E = _UxGT("Trigar *"); + LSTR MSG_ACC = _UxGT("Aceleracion"); + LSTR MSG_VTRAV_MIN = _UxGT("Vel. viache min"); + LSTR MSG_ACCELERATION = _UxGT("Accel"); + LSTR MSG_AMAX_A = _UxGT("Acel. max ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Acel. max ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Acel. max ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Acel. max ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Acel. max ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Acel. max ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Acel. max ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); + LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); + LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); + LSTR MSG_STEPS_PER_MM = _UxGT("Trangos/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" trangos/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" trangos/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" trangos/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" trangos/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" trangos/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" trangos/mm"); + LSTR MSG_E_STEPS = _UxGT("E trangos/mm"); + LSTR MSG_EN_STEPS = _UxGT("* trangos/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movimiento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_CONTRAST = _UxGT("Contraste"); + LSTR MSG_STORE_EEPROM = _UxGT("Alzar memoria"); + LSTR MSG_LOAD_EEPROM = _UxGT("Cargar memoria"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restaurar memoria"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Tornar a cargar"); + LSTR MSG_INFO_SCREEN = _UxGT("Informacion"); + LSTR MSG_PREPARE = _UxGT("Preparar"); + LSTR MSG_TUNE = _UxGT("Achustar"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausar impresion"); + LSTR MSG_RESUME_PRINT = _UxGT("Contin. impresion"); + LSTR MSG_STOP_PRINT = _UxGT("Detener Impresion"); + LSTR MSG_MEDIA_MENU = _UxGT("Menu de SD"); + LSTR MSG_NO_MEDIA = _UxGT("No i hai tarcheta"); + LSTR MSG_DWELL = _UxGT("Reposo..."); + LSTR MSG_USERWAIT = _UxGT("Aguardand ordines"); + LSTR MSG_PRINT_ABORTED = _UxGT("Impres. cancelada"); + LSTR MSG_NO_MOVE = _UxGT("Sin movimiento"); + LSTR MSG_KILLED = _UxGT("Aturada d'emerch."); + LSTR MSG_STOPPED = _UxGT("Aturada."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Retraer mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraer F"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Devantar mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet F"); + LSTR MSG_AUTORETRACT = _UxGT("Retraccion auto."); + LSTR MSG_FILAMENTCHANGE = _UxGT("Cambear filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Cambear filamento *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Encetan. tarcheta"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar tarcheta"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z fuera"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Error: en calentar"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Error: temperatura"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("Error de temperatura"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Error: Temp Max"); + LSTR MSG_ERR_MINTEMP = _UxGT("Error: Temp Min"); + LSTR MSG_HALTED = _UxGT("IMPRESORA ATURADA"); + LSTR MSG_PLEASE_RESET = _UxGT("Per favor reinic."); + LSTR MSG_SHORT_DAY = _UxGT("d"); + LSTR MSG_SHORT_HOUR = _UxGT("h"); + LSTR MSG_SHORT_MINUTE = _UxGT("m"); + LSTR MSG_HEATING = _UxGT("Calentando..."); + LSTR MSG_BED_HEATING = _UxGT("Calentando base..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Inf. Impresora"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Inf. Impresora"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estadisticas Imp."); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Inf. Controlador"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistors"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusors"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz"); + LSTR MSG_INFO_MENU = _UxGT("Inf. Impresora"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Inf. Impresora"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Estadisticas Imp."); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Inf. Controlador"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistors"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrusors"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baudios"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocolo"); + LSTR MSG_CASE_LIGHT = _UxGT("Luz"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Conteo de impresion"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tiempo total d'imp."); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impresion mas larga"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total d'extrusion"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Conteo de impresion"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tiempo total d'imp."); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Impresion mas larga"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total d'extrusion"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impresions"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Mas larga"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrusion"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impresions"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Mas larga"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrusion"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temperatura menima"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temperatura maxima"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fuente de aliment"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temperatura menima"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temperatura maxima"); + LSTR MSG_INFO_PSU = _UxGT("Fuente de aliment"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Fuerza d'o driver"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escri. DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Resumir imp."); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Fuerza d'o driver"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escri. DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Resumir imp."); // // Filament Change screens show up to 3 lines on a 4-line display @@ -227,15 +227,15 @@ namespace Language_an { #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Aguardand iniciar", "d'o filamento", "cambear")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Meta o filamento", "y prete lo boton", "pa continar...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Aguardand iniciar", "d'o filamento", "cambear")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Meta o filamento", "y prete lo boton", "pa continar...")); #else // LCD_HEIGHT < 4 // Up to 2 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Aguardand iniciar", "d'o fil. cambear")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("Meta o filamento", "y prete lo boton")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Aguardand iniciar", "d'o fil. cambear")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("Meta o filamento", "y prete lo boton")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Aguardando a", "expulsar filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Aguardando a", "cargar filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Aguardando impre.", "pa continar")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Aguardando a", "expulsar filament")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Aguardando a", "cargar filamento")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Aguardando impre.", "pa continar")); } diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 37d896f60d..3d332ca058 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -33,127 +33,127 @@ namespace Language_bg { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Bulgarian"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Bulgarian"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Готов."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Картата е поставена"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Картата е извадена"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Меню"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Изкл. двигатели"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Паркиране"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Задай Начало"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Изходна точка"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Готов."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Картата е поставена"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Картата е извадена"); + LSTR MSG_MAIN = _UxGT("Меню"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Изкл. двигатели"); + LSTR MSG_AUTO_HOME = _UxGT("Паркиране"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Задай Начало"); + LSTR MSG_SET_ORIGIN = _UxGT("Изходна точка"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Подгряване ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Подгряване ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Подгряване ") PREHEAT_1_LABEL _UxGT(" Дюза"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Подгряване ") PREHEAT_1_LABEL _UxGT(" Дюза ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Подгр. ") PREHEAT_1_LABEL _UxGT(" Всички"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Подгр. ") PREHEAT_1_LABEL _UxGT(" Легло"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Настройки ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1 = _UxGT("Подгряване ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Подгряване ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Подгряване ") PREHEAT_1_LABEL _UxGT(" Дюза"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Подгряване ") PREHEAT_1_LABEL _UxGT(" Дюза ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Подгр. ") PREHEAT_1_LABEL _UxGT(" Всички"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Подгр. ") PREHEAT_1_LABEL _UxGT(" Легло"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Настройки ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Подгряване $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Подгряване $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Подгряване $ Дюза"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Подгряване $ Дюза ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Подгр. $ Всички"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Подгр. $ Легло"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Настройки $"); + LSTR MSG_PREHEAT_M = _UxGT("Подгряване $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Подгряване $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Подгряване $ Дюза"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Подгряване $ Дюза ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Подгр. $ Всички"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Подгр. $ Легло"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Настройки $"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Охлаждане"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Вкл. захранване"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Изкл. захранване"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Екструзия"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Откат"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Движение по ос"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Нивелиране"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Нивелиране"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Движение по X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Движение по Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Премести с %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Премести с 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Премести с 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Премести с 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Скорост"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); - PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Дюза"); - PROGMEM Language_Str MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" Дюза ~"); - PROGMEM Language_Str MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" Легло"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Вентилатор"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Вентилатор ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Поток"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Поток ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Управление"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Минимум"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Максимум"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Авто-темп."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Вкл."); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Изкл."); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-откат"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-travel"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Стъпки/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" стъпки/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E стъпки/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* стъпки/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Движение"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Нишка"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Диам. нишка"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Диам. нишка *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD контраст"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Запази в EPROM"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Зареди от EPROM"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Фабрични настройки"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Обнови"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Преглед"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Действия"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Настройка"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Пауза"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Възобнови печата"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Спри печата"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Меню карта"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Няма карта"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Почивка..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Изчакване"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Печатът е прекъснат"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Няма движение"); - PROGMEM Language_Str MSG_KILLED = _UxGT("УБИТО."); - PROGMEM Language_Str MSG_STOPPED = _UxGT("СПРЯНО."); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Откат mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Смяна Откат mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Откат V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Скок mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Възврат mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Смяна Възврат mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Възврат V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автоoткат"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Смяна нишка"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Смяна нишка *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Иниц. SD-Карта"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Смяна SD-Карта"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z-сондата е извадена"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Отстояние"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Министъпка X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Министъпка Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Министъпка Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Стоп Кр.Изключватели"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Делта Калибровка"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калибровка X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровка Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калибровка Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровка Център"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неправилен принтер"); + LSTR MSG_COOLDOWN = _UxGT("Охлаждане"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Вкл. захранване"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Изкл. захранване"); + LSTR MSG_EXTRUDE = _UxGT("Екструзия"); + LSTR MSG_RETRACT = _UxGT("Откат"); + LSTR MSG_MOVE_AXIS = _UxGT("Движение по ос"); + LSTR MSG_BED_LEVELING = _UxGT("Нивелиране"); + LSTR MSG_LEVEL_BED = _UxGT("Нивелиране"); + LSTR MSG_MOVE_X = _UxGT("Движение по X"); + LSTR MSG_MOVE_Y = _UxGT("Движение по Y"); + LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); + LSTR MSG_MOVE_E = _UxGT("Екструдер"); + LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); + LSTR MSG_MOVE_N_MM = _UxGT("Премести с %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Премести с 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Премести с 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Премести с 100mm"); + LSTR MSG_SPEED = _UxGT("Скорост"); + LSTR MSG_BED_Z = _UxGT("Bed Z"); + LSTR MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Дюза"); + LSTR MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" Дюза ~"); + LSTR MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" Легло"); + LSTR MSG_FAN_SPEED = _UxGT("Вентилатор"); + LSTR MSG_FAN_SPEED_N = _UxGT("Вентилатор ~"); + LSTR MSG_FLOW = _UxGT("Поток"); + LSTR MSG_FLOW_N = _UxGT("Поток ~"); + LSTR MSG_CONTROL = _UxGT("Управление"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Минимум"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Максимум"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); + LSTR MSG_AUTOTEMP = _UxGT("Авто-темп."); + LSTR MSG_LCD_ON = _UxGT("Вкл."); + LSTR MSG_LCD_OFF = _UxGT("Изкл."); + LSTR MSG_A_RETRACT = _UxGT("A-откат"); + LSTR MSG_A_TRAVEL = _UxGT("A-travel"); + LSTR MSG_STEPS_PER_MM = _UxGT("Стъпки/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" стъпки/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" стъпки/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" стъпки/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" стъпки/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" стъпки/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" стъпки/mm"); + LSTR MSG_E_STEPS = _UxGT("E стъпки/mm"); + LSTR MSG_EN_STEPS = _UxGT("* стъпки/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Температура"); + LSTR MSG_MOTION = _UxGT("Движение"); + LSTR MSG_FILAMENT = _UxGT("Нишка"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Диам. нишка"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Диам. нишка *"); + LSTR MSG_CONTRAST = _UxGT("LCD контраст"); + LSTR MSG_STORE_EEPROM = _UxGT("Запази в EPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Зареди от EPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Фабрични настройки"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Обнови"); + LSTR MSG_INFO_SCREEN = _UxGT("Преглед"); + LSTR MSG_PREPARE = _UxGT("Действия"); + LSTR MSG_TUNE = _UxGT("Настройка"); + LSTR MSG_PAUSE_PRINT = _UxGT("Пауза"); + LSTR MSG_RESUME_PRINT = _UxGT("Възобнови печата"); + LSTR MSG_STOP_PRINT = _UxGT("Спри печата"); + LSTR MSG_MEDIA_MENU = _UxGT("Меню карта"); + LSTR MSG_NO_MEDIA = _UxGT("Няма карта"); + LSTR MSG_DWELL = _UxGT("Почивка..."); + LSTR MSG_USERWAIT = _UxGT("Изчакване"); + LSTR MSG_PRINT_ABORTED = _UxGT("Печатът е прекъснат"); + LSTR MSG_NO_MOVE = _UxGT("Няма движение"); + LSTR MSG_KILLED = _UxGT("УБИТО."); + LSTR MSG_STOPPED = _UxGT("СПРЯНО."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Откат mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Смяна Откат mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Откат V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Скок mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Възврат mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Смяна Възврат mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Възврат V"); + LSTR MSG_AUTORETRACT = _UxGT("Автоoткат"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Смяна нишка"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Смяна нишка *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Иниц. SD-Карта"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Смяна SD-Карта"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z-сондата е извадена"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z Отстояние"); + LSTR MSG_BABYSTEP_X = _UxGT("Министъпка X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Министъпка Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Министъпка Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Стоп Кр.Изключватели"); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Делта Калибровка"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Калибровка X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровка Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Калибровка Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровка Център"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Неправилен принтер"); } diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index a554fafdfd..06db1e8186 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -30,204 +30,204 @@ namespace Language_ca { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Catalan"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Catalan"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" preparada."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Targeta detectada."); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Targeta extreta."); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inici automatic"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desactiva motors"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu de depuracio"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progres"); - PROGMEM Language_Str MSG_HOMING = _UxGT("Origen"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ves a l'origen"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X a origen"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y a origen"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z a origen"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Premeu per iniciar"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Següent punt"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Anivellament fet!"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ajusta decalatge"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Decalatge aplicat"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Estableix origen"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" preparada."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Targeta detectada."); + LSTR MSG_MEDIA_REMOVED = _UxGT("Targeta extreta."); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); + LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Inici automatic"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Desactiva motors"); + LSTR MSG_DEBUG_MENU = _UxGT("Menu de depuracio"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progres"); + LSTR MSG_HOMING = _UxGT("Origen"); + LSTR MSG_AUTO_HOME = _UxGT("Ves a l'origen"); + LSTR MSG_AUTO_HOME_X = _UxGT("X a origen"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Y a origen"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Z a origen"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Premeu per iniciar"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Següent punt"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Anivellament fet!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ajusta decalatge"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Decalatge aplicat"); + LSTR MSG_SET_ORIGIN = _UxGT("Estableix origen"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preescalfa ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preescalfa ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Tot"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Llit"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Conf."); + LSTR MSG_PREHEAT_1 = _UxGT("Preescalfa ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Preescalfa ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" End ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Tot"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Llit"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preescalfa ") PREHEAT_1_LABEL _UxGT(" Conf."); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Preescalfa $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Preescalfa $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Preescalfa $ End"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Preescalfa $ End ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Preescalfa $ Tot"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Preescalfa $ Llit"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Preescalfa $ Conf."); + LSTR MSG_PREHEAT_M = _UxGT("Preescalfa $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Preescalfa $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preescalfa $ End"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preescalfa $ End ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preescalfa $ Tot"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preescalfa $ Llit"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preescalfa $ Conf."); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Refreda"); + LSTR MSG_COOLDOWN = _UxGT("Refreda"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudeix"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retreu"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mou eixos"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Anivella llit"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Anivella llit"); + LSTR MSG_EXTRUDE = _UxGT("Extrudeix"); + LSTR MSG_RETRACT = _UxGT("Retreu"); + LSTR MSG_MOVE_AXIS = _UxGT("Mou eixos"); + LSTR MSG_BED_LEVELING = _UxGT("Anivella llit"); + LSTR MSG_LEVEL_BED = _UxGT("Anivella llit"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Movent.."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY lliures"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mou X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mou Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mou Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mou %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mou 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mou 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mou 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocitat"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Llit Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Llit"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flux"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flux ~"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VViatge min"); + LSTR MSG_MOVING = _UxGT("Movent.."); + LSTR MSG_FREE_XY = _UxGT("XY lliures"); + LSTR MSG_MOVE_X = _UxGT("Mou X"); + LSTR MSG_MOVE_Y = _UxGT("Mou Y"); + LSTR MSG_MOVE_Z = _UxGT("Mou Z"); + LSTR MSG_MOVE_E = _UxGT("Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); + LSTR MSG_MOVE_N_MM = _UxGT("Mou %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mou 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mou 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mou 100mm"); + LSTR MSG_SPEED = _UxGT("Velocitat"); + LSTR MSG_BED_Z = _UxGT("Llit Z"); + LSTR MSG_NOZZLE = _UxGT("Nozzle"); + LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); + LSTR MSG_BED = _UxGT("Llit"); + LSTR MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); + LSTR MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); + LSTR MSG_FLOW = _UxGT("Flux"); + LSTR MSG_FLOW_N = _UxGT("Flux ~"); + LSTR MSG_VTRAV_MIN = _UxGT("VViatge min"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Accel. retracc"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Accel. Viatge"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passos/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passos/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Epassos/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*passos/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Moviment"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. Fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. Fil. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contrast de LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Desa memoria"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Carrega memoria"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restaura valors"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Actualitza"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Pantalla Info."); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Prepara"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Ajusta"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausa impressio"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Repren impressio"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Atura impressio."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprimeix de SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No hi ha targeta"); - PROGMEM Language_Str MSG_DWELL = _UxGT("En repos..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Esperant usuari.."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Imp. cancelada"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sense moviment."); - PROGMEM Language_Str MSG_KILLED = _UxGT("MATAT."); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ATURADA."); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retreu mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Retreure mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retreu V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Aixeca mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet +mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap DesRet +mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto retraccio"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Canvia filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Canvia filament *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Inicialitza SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Canvia SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z fora"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reinicia BLTouch"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s primer"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Decalatge Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropas X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropas Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropas Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Cancel. Endstop"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Error al escalfar"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP REDUNDANT"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MAXIMA"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESSORA PARADA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reinicieu"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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("Escalfant..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Escalfant llit..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibratge Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibra X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibra Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibra Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra el centre"); + LSTR MSG_A_RETRACT = _UxGT("Accel. retracc"); + LSTR MSG_A_TRAVEL = _UxGT("Accel. Viatge"); + LSTR MSG_STEPS_PER_MM = _UxGT("Passos/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passos/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passos/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passos/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passos/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passos/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passos/mm"); + LSTR MSG_E_STEPS = _UxGT("Epassos/mm"); + LSTR MSG_EN_STEPS = _UxGT("*passos/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Moviment"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Diam. Fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diam. Fil. *"); + LSTR MSG_CONTRAST = _UxGT("Contrast de LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Desa memoria"); + LSTR MSG_LOAD_EEPROM = _UxGT("Carrega memoria"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restaura valors"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Actualitza"); + LSTR MSG_INFO_SCREEN = _UxGT("Pantalla Info."); + LSTR MSG_PREPARE = _UxGT("Prepara"); + LSTR MSG_TUNE = _UxGT("Ajusta"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausa impressio"); + LSTR MSG_RESUME_PRINT = _UxGT("Repren impressio"); + LSTR MSG_STOP_PRINT = _UxGT("Atura impressio."); + LSTR MSG_MEDIA_MENU = _UxGT("Imprimeix de SD"); + LSTR MSG_NO_MEDIA = _UxGT("No hi ha targeta"); + LSTR MSG_DWELL = _UxGT("En repos..."); + LSTR MSG_USERWAIT = _UxGT("Esperant usuari.."); + LSTR MSG_PRINT_ABORTED = _UxGT("Imp. cancelada"); + LSTR MSG_NO_MOVE = _UxGT("Sense moviment."); + LSTR MSG_KILLED = _UxGT("MATAT."); + LSTR MSG_STOPPED = _UxGT("ATURADA."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retreu mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Retreure mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retreu V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Aixeca mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet +mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap DesRet +mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto retraccio"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Canvia filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Canvia filament *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Inicialitza SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Canvia SD"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z fora"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reinicia BLTouch"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s primer"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Decalatge Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Micropas X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Micropas Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Micropas Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancel. Endstop"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Error al escalfar"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP REDUNDANT"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MAXIMA"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); + LSTR MSG_HALTED = _UxGT("IMPRESSORA PARADA"); + LSTR MSG_PLEASE_RESET = _UxGT("Reinicieu"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Escalfant..."); + LSTR MSG_BED_HEATING = _UxGT("Escalfant llit..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibratge Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibra X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibra Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibra Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra el centre"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Quant a la impr."); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info Impressora"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estadistiques"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info placa"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistors"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusors"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocol"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Llum"); + LSTR MSG_INFO_MENU = _UxGT("Quant a la impr."); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info Impressora"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Estadistiques"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info placa"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistors"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrusors"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocol"); + LSTR MSG_CASE_LIGHT = _UxGT("Llum"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total impressions"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Acabades"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Temps imprimint"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Treball mes llarg"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total extrudit"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total impressions"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Acabades"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Temps imprimint"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Treball mes llarg"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total extrudit"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impressions"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Acabades"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Mes llarg"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudit"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impressions"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Acabades"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Mes llarg"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudit"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp. mínima"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp. màxima"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Font alimentacio"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp. mínima"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp. màxima"); + LSTR MSG_INFO_PSU = _UxGT("Font alimentacio"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Força motor"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Força motor"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Repren impressió"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Repren impressió"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora incorrecta"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora incorrecta"); // // 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_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperant per", "iniciar el canvi", "de filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Esperant per", "treure filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Poseu filament", "i premeu el boto", "per continuar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premeu boto per", "escalfar nozzle.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Escalfant nozzle", "Espereu...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Esperant carrega", "de filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperant per", "reprendre")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperant per", "iniciar el canvi", "de filament")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Esperant per", "treure filament")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Poseu filament", "i premeu el boto", "per continuar...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premeu boto per", "escalfar nozzle.")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Escalfant nozzle", "Espereu...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Esperant carrega", "de filament")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperant per", "reprendre")); #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Espereu...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Expulsant...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insereix i prem")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Escalfant...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Carregant...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reprenent...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Espereu...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Expulsant...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insereix i prem")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Escalfant...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Carregant...")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reprenent...")); #endif // LCD_HEIGHT < 4 } diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index b58fb05a1d..0e10cd4be0 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -38,576 +38,576 @@ namespace Language_cz { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Czech"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Czech"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" připraven."); - PROGMEM Language_Str MSG_YES = _UxGT("ANO"); - PROGMEM Language_Str MSG_NO = _UxGT("NE"); - PROGMEM Language_Str MSG_BACK = _UxGT("Zpět"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Rušení..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Médium vloženo"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Médium vyjmuto"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Čekání na médium"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Chyba čtení média"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB odstraněno"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Chyba USB"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znaku - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstopy"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Hlavní nabídka"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Další nastavení"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfigurace"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Uvolnit motory"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Nabídka ladění"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" připraven."); + LSTR MSG_YES = _UxGT("ANO"); + LSTR MSG_NO = _UxGT("NE"); + LSTR MSG_BACK = _UxGT("Zpět"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Rušení..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Médium vloženo"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Médium vyjmuto"); + LSTR MSG_MEDIA_WAITING = _UxGT("Čekání na médium"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čtení média"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB odstraněno"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znaku + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstopy"); + LSTR MSG_MAIN = _UxGT("Hlavní nabídka"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Další nastavení"); + LSTR MSG_CONFIGURATION = _UxGT("Konfigurace"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Uvolnit motory"); + LSTR MSG_DEBUG_MENU = _UxGT("Nabídka ladění"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test ukaz. průběhu"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test ukaz. průběhu"); #else - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. průběhu"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. průběhu"); #endif - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Domovská pozice"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Domů osa X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Domů osa Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Domů osa Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto srovnání Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Měření podložky"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknutím spusťte"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Další bod"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Měření hotovo!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Výška srovnávání"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastavit ofsety"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastaveny"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastavit počátek"); + LSTR MSG_AUTO_HOME = _UxGT("Domovská pozice"); + LSTR MSG_AUTO_HOME_X = _UxGT("Domů osa X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Domů osa Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Domů osa Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto srovnání Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Měření podložky"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Kliknutím spusťte"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Další bod"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Měření hotovo!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Výška srovnávání"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Nastavit ofsety"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastaveny"); + LSTR MSG_SET_ORIGIN = _UxGT("Nastavit počátek"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Zahřát ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Zahřát ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" end"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" end ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" vše"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" podlož"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" nast"); + LSTR MSG_PREHEAT_1 = _UxGT("Zahřát ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Zahřát ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" end"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" end ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" vše"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" podlož"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Zahřát ") PREHEAT_1_LABEL _UxGT(" nast"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Zahřát $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Zahřát $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Zahřát $ end"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Zahřát $ end ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Zahřát $ vše"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Zahřát $ podlož"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Zahřát $ nast"); + LSTR MSG_PREHEAT_M = _UxGT("Zahřát $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Zahřát $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Zahřát $ end"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Zahřát $ end ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Zahřát $ vše"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Zahřát $ podlož"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Zahřát $ nast"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Zahřát vlastní"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Zchladit"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Ovládání laseru"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon laseru"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Vřeteno ovládání"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Vřeteno výkon"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Vřeteno opačně"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnout napájení"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Vypnout napájení"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Vytlačit (extr.)"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Zatlačit (retr.)"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunout osy"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnat podložku"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnat podložku"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Vyrovnat rohy"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Další roh"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sítě"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upravit síť bodů"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Konec úprav sítě"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Měření bodu"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Zahřát vlastní"); + LSTR MSG_COOLDOWN = _UxGT("Zchladit"); + LSTR MSG_LASER_MENU = _UxGT("Ovládání laseru"); + LSTR MSG_LASER_POWER = _UxGT("Výkon laseru"); + LSTR MSG_SPINDLE_MENU = _UxGT("Vřeteno ovládání"); + LSTR MSG_SPINDLE_POWER = _UxGT("Vřeteno výkon"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Vřeteno opačně"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Zapnout napájení"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Vypnout napájení"); + LSTR MSG_EXTRUDE = _UxGT("Vytlačit (extr.)"); + LSTR MSG_RETRACT = _UxGT("Zatlačit (retr.)"); + LSTR MSG_MOVE_AXIS = _UxGT("Posunout osy"); + LSTR MSG_BED_LEVELING = _UxGT("Vyrovnat podložku"); + LSTR MSG_LEVEL_BED = _UxGT("Vyrovnat podložku"); + LSTR MSG_BED_TRAMMING = _UxGT("Vyrovnat rohy"); + LSTR MSG_NEXT_CORNER = _UxGT("Další roh"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor sítě"); + LSTR MSG_EDIT_MESH = _UxGT("Upravit síť bodů"); + LSTR MSG_EDITING_STOPPED = _UxGT("Konec úprav sítě"); + LSTR MSG_PROBING_POINT = _UxGT("Měření bodu"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Vlastní příkazy"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 test sondy"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 bod"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylka"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Režim IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Ofsety nástrojů"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikace"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrcadlení"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Vlastní příkazy"); + LSTR MSG_M48_TEST = _UxGT("M48 test sondy"); + LSTR MSG_M48_POINT = _UxGT("M48 bod"); + LSTR MSG_M48_DEVIATION = _UxGT("Odchylka"); + LSTR MSG_IDEX_MENU = _UxGT("Režim IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Ofsety nástrojů"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikace"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrcadlení"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Provádím G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL nástroje"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Vyrovnání bodu"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuální síť bodů"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Vložte kartu, změřte"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Změřte"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Odstraňte a změřte"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Přesun na další"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivovat UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Deaktivovat UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Teplota podložky"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Teplota podložky"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Teplota hotendu"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Teplota hotendu"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Úprava sítě bodů"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Upravit vlastní síť"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Doladit síť bodů"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Konec úprav sítě"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Vlastní síť"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Vytvořit síť"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Provádím G29"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL nástroje"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Vyrovnání bodu"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manuální síť bodů"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Vložte kartu, změřte"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Změřte"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Odstraňte a změřte"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Přesun na další"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivovat UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Deaktivovat UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Teplota podložky"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Teplota podložky"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Teplota hotendu"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Teplota hotendu"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Úprava sítě bodů"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Upravit vlastní síť"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Doladit síť bodů"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Konec úprav sítě"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Vlastní síť"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Vytvořit síť"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Síť bodů $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Kontrola sítě $"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Síť bodů $"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Kontrola sítě $"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Studená síť bodů"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Upravit výšku sítě"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Výška"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Zkontrolovat síť"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Kontrola vlast. sítě"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 zahřívání podl."); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 zařívání trysky"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ruční zavedení..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Pevné zavední"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Done Priming"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Canceled"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Leaving G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Pokračovat v síťi"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Síťové rovnání"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-bodové rovnání"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Mřížkové rovnání"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Srovnat podložku"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Postranní body"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Typ sítě bodu"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Exportovat síť"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Exportovat do PC"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Exportovat do CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Záloha do PC"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Info o UBL do PC"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Hustota mřížky"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ruční hustota"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Chytrá hustota"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Zaplnit mřížku"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Zrušit všechno"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Zrušit poslední"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Upravit všechny"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Upravit poslední"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Uložiště sítí"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Paměťový slot"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Načíst síť bodů"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Uložit síť bodů"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Síť %i načtena"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Síť %i uložena"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nedostatek místa"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Ch.: Uložit UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Ch.: Obnovit UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-ofset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Konec Z-ofsetu"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Postupně"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Studená síť bodů"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Chytrá hustota"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Zkontrolovat síť"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Upravit všechny"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Zkontrolovat síť"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Upravit všechny"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Uložit síť bodů"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Studená síť bodů"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Upravit výšku sítě"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Výška"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Zkontrolovat síť"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Kontrola vlast. sítě"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 zahřívání podl."); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 zařívání trysky"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Ruční zavedení..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Pevné zavední"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Done Priming"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Canceled"); + LSTR MSG_G26_LEAVING = _UxGT("Leaving G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Pokračovat v síťi"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Síťové rovnání"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-bodové rovnání"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Mřížkové rovnání"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Srovnat podložku"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Postranní body"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Typ sítě bodu"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Exportovat síť"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Exportovat do PC"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Exportovat do CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Záloha do PC"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Info o UBL do PC"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Hustota mřížky"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ruční hustota"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Chytrá hustota"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Zaplnit mřížku"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Zrušit všechno"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Zrušit poslední"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Upravit všechny"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Upravit poslední"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Uložiště sítí"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Paměťový slot"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Načíst síť bodů"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Uložit síť bodů"); + LSTR MSG_MESH_LOADED = _UxGT("Síť %i načtena"); + LSTR MSG_MESH_SAVED = _UxGT("Síť %i uložena"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Nedostatek místa"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Ch.: Uložit UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Ch.: Obnovit UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-ofset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Konec Z-ofsetu"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Postupně"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Studená síť bodů"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Chytrá hustota"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Zkontrolovat síť"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Upravit všechny"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Zkontrolovat síť"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Upravit všechny"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Uložit síť bodů"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Nastavení LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Světla"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Světla Předvolby"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Červená"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Oranžová"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Žlutá"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Zelená"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Modrá"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fialová"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Bílá"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Výchozí"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Vlastní světla"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Červená intenzita"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zelená intezita"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Modrá intenzita"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Bílá intenzita"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Jas"); + LSTR MSG_LED_CONTROL = _UxGT("Nastavení LED"); + LSTR MSG_LEDS = _UxGT("Světla"); + LSTR MSG_LED_PRESETS = _UxGT("Světla Předvolby"); + LSTR MSG_SET_LEDS_RED = _UxGT("Červená"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Oranžová"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Žlutá"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Zelená"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Modrá"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Fialová"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Bílá"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Výchozí"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Vlastní světla"); + LSTR MSG_INTENSITY_R = _UxGT("Červená intenzita"); + LSTR MSG_INTENSITY_G = _UxGT("Zelená intezita"); + LSTR MSG_INTENSITY_B = _UxGT("Modrá intenzita"); + LSTR MSG_INTENSITY_W = _UxGT("Bílá intenzita"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Jas"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Posouvání..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Uvolnit XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Posunout X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Posunout Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Posunout Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudér"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudér *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Posunout o %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunout o 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Rychlost"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Tryska ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rychlost vent."); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Rychlost vent. ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Rychlost ex. vent."); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Rychlost ex. vent. ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Průtok"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Průtok ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Ovládaní"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" fakt"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autoteplota"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Zap"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Vyp"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID automatika"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID automatika *"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Vybrat"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Vybrat *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Zrychl"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Odchylka spoje"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Rychlost"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Rychlost"); - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Rychlost"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Akcelerace"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Akcel"); - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Akcel"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-přejezd"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Kroků/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" kroků/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroků/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroků/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Pohyb"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E na mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Prum."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Prum. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Vysunout mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Zavést mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K pro posun"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K pro posun *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Uložit nastavení"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Načíst nastavení"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Obnovit výchozí"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inic. EEPROM"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aktualizace z SD"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset tiskárny"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnovit"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info obrazovka"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Připrava tisku"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Doladění tisku"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Spustit tisk"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Další"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inicializace"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Tisk"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Zrušit"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Hotovo"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Zpět"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Pokračovat"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pozastavit tisk"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Obnovit tisk"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Zastavit tisk"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Tisk objektu"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Zrušit objekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Zrušit objekt ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Obnova výpadku"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tisknout z SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Žádná SD karta"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Uspáno..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Čekání na uživ..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Tisk pozastaven"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Tisknu..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Tisk zrušen"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Žádný pohyb."); - PROGMEM Language_Str MSG_KILLED = _UxGT("PŘERUSENO. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ZASTAVENO. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retrakt mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Výměna Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraktovat V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Zvednuti Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Délka retrakce"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Délka zavedení"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Výměna nástroje"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvih Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Rychlost primár."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Rychlost retrak."); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Tryska standby"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Vyměnit filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Vyměnit filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Zavést filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Zavést filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Vysunout filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Vysunout filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Vysunout vše"); + LSTR MSG_MOVING = _UxGT("Posouvání..."); + LSTR MSG_FREE_XY = _UxGT("Uvolnit XY"); + LSTR MSG_MOVE_X = _UxGT("Posunout X"); + LSTR MSG_MOVE_Y = _UxGT("Posunout Y"); + LSTR MSG_MOVE_Z = _UxGT("Posunout Z"); + LSTR MSG_MOVE_E = _UxGT("Extrudér"); + LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); + LSTR MSG_MOVE_N_MM = _UxGT("Posunout o %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Posunout o 100mm"); + LSTR MSG_SPEED = _UxGT("Rychlost"); + LSTR MSG_BED_Z = _UxGT("Výška podl."); + LSTR MSG_NOZZLE = _UxGT("Tryska"); + LSTR MSG_NOZZLE_N = _UxGT("Tryska ~"); + LSTR MSG_BED = _UxGT("Podložka"); + LSTR MSG_CHAMBER = _UxGT("Komora"); + LSTR MSG_FAN_SPEED = _UxGT("Rychlost vent."); + LSTR MSG_FAN_SPEED_N = _UxGT("Rychlost vent. ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Rychlost ex. vent."); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Rychlost ex. vent. ~"); + LSTR MSG_FLOW = _UxGT("Průtok"); + LSTR MSG_FLOW_N = _UxGT("Průtok ~"); + LSTR MSG_CONTROL = _UxGT("Ovládaní"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" fakt"); + LSTR MSG_AUTOTEMP = _UxGT("Autoteplota"); + LSTR MSG_LCD_ON = _UxGT("Zap"); + LSTR MSG_LCD_OFF = _UxGT("Vyp"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID automatika"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID automatika *"); + LSTR MSG_SELECT = _UxGT("Vybrat"); + LSTR MSG_SELECT_E = _UxGT("Vybrat *"); + LSTR MSG_ACC = _UxGT("Zrychl"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Odchylka spoje"); + LSTR MSG_VELOCITY = _UxGT("Rychlost"); + LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Rychlost"); + LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Rychlost"); + LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Rychlost"); + LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Rychlost"); + LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Rychlost"); + LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Rychlost"); + LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Rychlost"); + LSTR MSG_VMAX_EN = _UxGT("Max * Rychlost"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); + LSTR MSG_ACCELERATION = _UxGT("Akcelerace"); + LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Akcel"); + LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Akcel"); + LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Akcel"); + LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Akcel"); + LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Akcel"); + LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Akcel"); + LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Akcel"); + LSTR MSG_AMAX_EN = _UxGT("Max * Akcel"); + LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); + LSTR MSG_A_TRAVEL = _UxGT("A-přejezd"); + LSTR MSG_STEPS_PER_MM = _UxGT("Kroků/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" kroků/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" kroků/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" kroků/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" kroků/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" kroků/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" kroků/mm"); + LSTR MSG_E_STEPS = _UxGT("E kroků/mm"); + LSTR MSG_EN_STEPS = _UxGT("* kroků/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Teplota"); + LSTR MSG_MOTION = _UxGT("Pohyb"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E na mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Prum."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Prum. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Vysunout mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Zavést mm"); + LSTR MSG_ADVANCE_K = _UxGT("K pro posun"); + LSTR MSG_ADVANCE_K_E = _UxGT("K pro posun *"); + LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Uložit nastavení"); + LSTR MSG_LOAD_EEPROM = _UxGT("Načíst nastavení"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Obnovit výchozí"); + LSTR MSG_INIT_EEPROM = _UxGT("Inic. EEPROM"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Aktualizace z SD"); + LSTR MSG_RESET_PRINTER = _UxGT("Reset tiskárny"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnovit"); + LSTR MSG_INFO_SCREEN = _UxGT("Info obrazovka"); + LSTR MSG_PREPARE = _UxGT("Připrava tisku"); + LSTR MSG_TUNE = _UxGT("Doladění tisku"); + LSTR MSG_START_PRINT = _UxGT("Spustit tisk"); + LSTR MSG_BUTTON_NEXT = _UxGT("Další"); + LSTR MSG_BUTTON_INIT = _UxGT("Inicializace"); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Tisk"); + LSTR MSG_BUTTON_RESET = _UxGT("Reset"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Zrušit"); + LSTR MSG_BUTTON_DONE = _UxGT("Hotovo"); + LSTR MSG_BUTTON_BACK = _UxGT("Zpět"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Pokračovat"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pozastavit tisk"); + LSTR MSG_RESUME_PRINT = _UxGT("Obnovit tisk"); + LSTR MSG_STOP_PRINT = _UxGT("Zastavit tisk"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Tisk objektu"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušit objekt"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušit objekt ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Obnova výpadku"); + LSTR MSG_MEDIA_MENU = _UxGT("Tisknout z SD"); + LSTR MSG_NO_MEDIA = _UxGT("Žádná SD karta"); + LSTR MSG_DWELL = _UxGT("Uspáno..."); + LSTR MSG_USERWAIT = _UxGT("Čekání na uživ..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Tisk pozastaven"); + LSTR MSG_PRINTING = _UxGT("Tisknu..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Tisk zrušen"); + LSTR MSG_NO_MOVE = _UxGT("Žádný pohyb."); + LSTR MSG_KILLED = _UxGT("PŘERUSENO. "); + LSTR MSG_STOPPED = _UxGT("ZASTAVENO. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retrakt mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Výměna Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraktovat V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Zvednuti Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Délka retrakce"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Délka zavedení"); + LSTR MSG_TOOL_CHANGE = _UxGT("Výměna nástroje"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvih Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Rychlost primár."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Rychlost retrak."); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Tryska standby"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Vyměnit filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Vyměnit filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Zavést filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Zavést filament *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Vysunout filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Vysunout filament *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Vysunout vše"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Načíst médium"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Vyměnit médium"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Vysunout médium"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z mimo podl"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Faktor zkosení"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch self-test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("BLTouch reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("BLTouch zasunout"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch vysunout"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW výsun BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("BLTouch 5V režim"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("BLTouch OD režim"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Uložit režim"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Nastavit 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Nastacit OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Vypsat nastavení"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("VAROVANÍ: Špatné nastavení může způsobit škody! Pokračovat?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Inic. TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test Z Ofsetu"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Uložiy"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("vysunout TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Vysunout Z-sondu"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Zasunout Z-sondu"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Domů %s%s%s první"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Celkem"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop abort"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Chyba zahřívání"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEPLOTA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÍ ÚNIK"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPL. ÚNIK PODL."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPL. ÚNIK KOMORA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("VYSOKÁ TEPLOTA"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("NÍZKA TEPLOTA"); - PROGMEM Language_Str MSG_HALTED = _UxGT("TISK. ZASTAVENA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proveďte reset"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Zahřívání..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Chlazení..."); + LSTR MSG_ATTACH_MEDIA = _UxGT("Načíst médium"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Vyměnit médium"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Vysunout médium"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z mimo podl"); + LSTR MSG_SKEW_FACTOR = _UxGT("Faktor zkosení"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch self-test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("BLTouch reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("BLTouch zasunout"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch vysunout"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW výsun BLTouch"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("BLTouch 5V režim"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("BLTouch OD režim"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Uložit režim"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Nastavit 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Nastacit OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Vypsat nastavení"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("VAROVANÍ: Špatné nastavení může způsobit škody! Pokračovat?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Inic. TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test Z Ofsetu"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Uložiy"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("vysunout TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Vysunout Z-sondu"); + LSTR MSG_MANUAL_STOW = _UxGT("Zasunout Z-sondu"); + LSTR MSG_HOME_FIRST = _UxGT("Domů %s%s%s první"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Celkem"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop abort"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba zahřívání"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEPLOTA"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÍ ÚNIK"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPL. ÚNIK PODL."); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPL. ÚNIK KOMORA"); + LSTR MSG_ERR_MAXTEMP = _UxGT("VYSOKÁ TEPLOTA"); + LSTR MSG_ERR_MINTEMP = _UxGT("NÍZKA TEPLOTA"); + LSTR MSG_HALTED = _UxGT("TISK. ZASTAVENA"); + LSTR MSG_PLEASE_RESET = _UxGT("Proveďte reset"); + LSTR MSG_SHORT_DAY = _UxGT("d"); + LSTR MSG_SHORT_HOUR = _UxGT("h"); + LSTR MSG_SHORT_MINUTE = _UxGT("m"); + LSTR MSG_HEATING = _UxGT("Zahřívání..."); + LSTR MSG_COOLING = _UxGT("Chlazení..."); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Zahřívání podložky"); + LSTR MSG_BED_HEATING = _UxGT("Zahřívání podložky"); #else - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Zahřívání podl."); + LSTR MSG_BED_HEATING = _UxGT("Zahřívání podl."); #endif #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chlazení podložky"); + LSTR MSG_BED_COOLING = _UxGT("Chlazení podložky"); #else - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chlazení podl."); + LSTR MSG_BED_COOLING = _UxGT("Chlazení podl."); #endif - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Zahřívání komory..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chlazení komory..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrace"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovat X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovat Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrovat Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovat Střed"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta nastavení"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autokalibrace"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast.výšku delty"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Nast. Z-ofset"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag rameno"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Výška"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Poloměr"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("O tiskárně"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info o tiskárně"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-bodové rovnání"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineárni rovnání"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineární rovnání"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mřížkové rovnání"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statistika"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info o desce"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrudéry"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Rychlost"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Sledování úniku: VYP"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Sledování úniku: ZAP"); + LSTR MSG_CHAMBER_HEATING = _UxGT("Zahřívání komory..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Chlazení komory..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrace"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovat X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovat Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrovat Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovat Střed"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta nastavení"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autokalibrace"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast.výšku delty"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Nast. Z-ofset"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rameno"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Výška"); + LSTR MSG_DELTA_RADIUS = _UxGT("Poloměr"); + LSTR MSG_INFO_MENU = _UxGT("O tiskárně"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info o tiskárně"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-bodové rovnání"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Lineárni rovnání"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilineární rovnání"); + LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_MESH_LEVELING = _UxGT("Mřížkové rovnání"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Statistika"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info o desce"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrudéry"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Rychlost"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokol"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Sledování úniku: VYP"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Sledování úniku: ZAP"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvětlení"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas světla"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("NESPRÁVNÁ TISKÁRNA"); + LSTR MSG_CASE_LIGHT = _UxGT("Osvětlení"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas světla"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("NESPRÁVNÁ TISKÁRNA"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Počet tisků"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončeno"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Nejdelší tisk"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Celkem vytlačeno"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tisků"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončeno"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Nejdelší tisk"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Celkem vytlačeno"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Tisky"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Hotovo"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Čas"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Nejdelší"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačeno"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Tisky"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Hotovo"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Čas"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Nejdelší"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačeno"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Teplota min"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Nap. zdroj"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Buzení motorů"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Motor %"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC uložit EEPROM"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CHYBA SPOJENÍ"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMĚNA FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("TISK POZASTAVEN"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ZAVEDENÍ FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("VYSUNUTÍ FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("MOŽNOSTI OBNOVENÍ:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Vytlačit víc"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Obnovit tisk"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Délka mm senz.fil."); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkování selhalo"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrace selhala"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Teplota min"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); + LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Buzení motorů"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC uložit EEPROM"); + LSTR MSG_ERROR_TMC = _UxGT("TMC CHYBA SPOJENÍ"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMĚNA FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("TISK POZASTAVEN"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ZAVEDENÍ FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("VYSUNUTÍ FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("MOŽNOSTI OBNOVENÍ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Vytlačit víc"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Obnovit tisk"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Délka mm senz.fil."); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Parkování selhalo"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Kalibrace selhala"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktual. MMU firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potř. pozornost."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Obnovit tisk"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Obnovování..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Zavést filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Zavést všechny"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Zavést do trysky"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Vysunout filament"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Vysun. filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Vytáhnout filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Zavádění fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Vytahování fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Vysouvání fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Všechny"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetovat MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetování MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Vytáhněte, klikněte"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktual. MMU firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potř. pozornost."); + LSTR MSG_MMU2_RESUME = _UxGT("Obnovit tisk"); + LSTR MSG_MMU2_RESUMING = _UxGT("Obnovování..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Zavést filament"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Zavést všechny"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Zavést do trysky"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Vysunout filament"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Vysun. filament ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Vytáhnout filament"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Zavádění fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Vytahování fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Vysouvání fil...."); + LSTR MSG_MMU2_ALL = _UxGT("Všechny"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Resetovat MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Resetování MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Vytáhněte, klikněte"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponenta ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mixér"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Přechod"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Celý přechod"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Přepnout mix"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Střídat mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Přechod mix"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Opačný přechod"); + LSTR MSG_MIX = _UxGT("Mix"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponenta ="); + LSTR MSG_MIXER = _UxGT("Mixér"); + LSTR MSG_GRADIENT = _UxGT("Přechod"); + LSTR MSG_FULL_GRADIENT = _UxGT("Celý přechod"); + LSTR MSG_TOGGLE_MIX = _UxGT("Přepnout mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Střídat mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Přechod mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Opačný přechod"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktivní V-nástroj"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Spustit V-nástroj"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Ukončit V-nástroj"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-nástroje"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Resetovat V-nástroj"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Uložit V-nástroj mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-nástroj resetovat"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktivní V-nástroj"); + LSTR MSG_START_VTOOL = _UxGT("Spustit V-nástroj"); + LSTR MSG_END_VTOOL = _UxGT("Ukončit V-nástroj"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-nástroje"); + LSTR MSG_RESET_VTOOLS = _UxGT("Resetovat V-nástroj"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Uložit V-nástroj mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-nástroj resetovat"); #else - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktivní V-nástr."); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Spustit V-nástr."); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Ukončit V-nástr."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-nástr."); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset. V-nástr."); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Uložit V-nás. mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-nástr. reset."); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktivní V-nástr."); + LSTR MSG_START_VTOOL = _UxGT("Spustit V-nástr."); + LSTR MSG_END_VTOOL = _UxGT("Ukončit V-nástr."); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-nástr."); + LSTR MSG_RESET_VTOOLS = _UxGT("Reset. V-nástr."); + LSTR MSG_COMMIT_VTOOL = _UxGT("Uložit V-nás. mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-nástr. reset."); #endif - PROGMEM Language_Str MSG_START_Z = _UxGT("Počáteční Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Koncové Z:"); + LSTR MSG_START_Z = _UxGT("Počáteční Z:"); + LSTR MSG_END_Z = _UxGT(" Koncové Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Hry"); - 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("Bludiště"); + LSTR MSG_GAMES = _UxGT("Hry"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Bludiště"); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlačítko", "pro obnovení tisku")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čekejte prosím", "na zahájení", "výměny filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stiskněte", "tlačítko...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí trysky")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Čekejte prosím", "na nahřátí tr.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Čekejte prosím", "na vysunuti", "filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Čekejte prosím", "na zavedení", "filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Vyčkejte na", "vytlačení")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Klikněte pro", "ukončení", "vytlačování")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Čekejte prosím", "na pokračování", "tisku")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlačítko", "pro obnovení tisku")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čekejte prosím", "na zahájení", "výměny filamentu")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stiskněte", "tlačítko...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí trysky")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Čekejte prosím", "na nahřátí tr.")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Čekejte prosím", "na vysunuti", "filamentu")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Čekejte prosím", "na zavedení", "filamentu")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Vyčkejte na", "vytlačení")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Klikněte pro", "ukončení", "vytlačování")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Čekejte prosím", "na pokračování", "tisku")); #else // LCD_HEIGHT < 4 // Up to 2 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlač.", "pro obnovení")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čekejte...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte, klikněte")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Nahřívání...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Vysouvání...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Zavádění...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Vytlačování...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klikněte pro", "ukončení")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Pokračování...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stikněte tlač.", "pro obnovení")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkování...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čekejte...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte, klikněte")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klikněte pro", "nahřátí")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Nahřívání...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Vysouvání...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Zavádění...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Vytlačování...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klikněte pro", "ukončení")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Pokračování...")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC budiče"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Proud budičů"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybridní práh"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Domů bez senzorů"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Režim kroků"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop povolen"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" za:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Vůle"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekce"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Vyhlazení"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC budiče"); + LSTR MSG_TMC_CURRENT = _UxGT("Proud budičů"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybridní práh"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Domů bez senzorů"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Režim kroků"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop povolen"); + LSTR MSG_SERVICE_RESET = _UxGT("Reset"); + LSTR MSG_SERVICE_IN = _UxGT(" za:"); + LSTR MSG_BACKLASH = _UxGT("Vůle"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekce"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Vyhlazení"); } diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index ef312f1334..4ce6089442 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -33,174 +33,174 @@ namespace Language_da { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Danish"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Danish"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" er klar"); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Kort isat"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Kort fjernet"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Slå alle steppere fra"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); // G28 - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klik når du er klar"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Næste punkt"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Bed level er færdig!"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Sæt forsk. af home"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Forsk. er nu aktiv"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sæt origin"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" er klar"); + LSTR MSG_MEDIA_INSERTED = _UxGT("Kort isat"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Kort fjernet"); + LSTR MSG_MAIN = _UxGT("Menu"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Slå alle steppere fra"); + LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); // G28 + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klik når du er klar"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Næste punkt"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Bed level er færdig!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Sæt forsk. af home"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Forsk. er nu aktiv"); + LSTR MSG_SET_ORIGIN = _UxGT("Sæt origin"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Forvarm ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Forvarm ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Alle"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Bed"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Forvarm ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Forvarm ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Alle"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Bed"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Forvarm $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Forvarm $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Forvarm $ end"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Forvarm $ end ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Forvarm $ Alle"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Forvarm $ Bed"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Forvarm $ conf"); + LSTR MSG_PREHEAT_M = _UxGT("Forvarm $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Forvarm $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Forvarm $ end"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Forvarm $ end ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Forvarm $ Alle"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Forvarm $ Bed"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Forvarm $ conf"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Afkøl"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Slå strøm til"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Slå strøm fra"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Flyt akser"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Juster bed"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Juster bed"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Flyt X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Flyt Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Flyt Z"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Flyt %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flyt 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flyt 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flyt 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighed"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Plade Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dyse"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dyse ~"); + LSTR MSG_COOLDOWN = _UxGT("Afkøl"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Slå strøm til"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Slå strøm fra"); + LSTR MSG_EXTRUDE = _UxGT("Extruder"); + LSTR MSG_MOVE_AXIS = _UxGT("Flyt akser"); + LSTR MSG_BED_LEVELING = _UxGT("Juster bed"); + LSTR MSG_LEVEL_BED = _UxGT("Juster bed"); + LSTR MSG_MOVE_X = _UxGT("Flyt X"); + LSTR MSG_MOVE_Y = _UxGT("Flyt Y"); + LSTR MSG_MOVE_Z = _UxGT("Flyt Z"); + LSTR MSG_MOVE_N_MM = _UxGT("Flyt %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Flyt 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Flyt 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Flyt 100mm"); + LSTR MSG_SPEED = _UxGT("Hastighed"); + LSTR MSG_BED_Z = _UxGT("Plade Z"); + LSTR MSG_NOZZLE = _UxGT("Dyse"); + LSTR MSG_NOZZLE_N = _UxGT("Dyse ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Plade"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Blæser hastighed"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Blæser hastighed ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontrol"); - PROGMEM Language_Str MSG_MIN = _UxGT(" \002 Min"); - PROGMEM Language_Str MSG_MAX = _UxGT(" \002 Max"); - PROGMEM Language_Str MSG_FACTOR = _UxGT(" \002 Fact"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Til"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Fra"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Vælg"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Vælg *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retract"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-rejse"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Bevægelse"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gem i EEPROM"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Hent fra EEPROM"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Gendan Defaults"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Genopfrisk"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info skærm"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Forbered"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause printet"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Forsæt printet"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop printet"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Print fra SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Intet SD kort"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Dvale..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Venter på bruger..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Print annulleret"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Ingen bevægelse."); - PROGMEM Language_Str MSG_KILLED = _UxGT("DRÆBT. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPET. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Tilbagetræk mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Skift Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Tilbagetræk V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Skift Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Skift filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Skift filament *"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Skift SD kort"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Probe udenfor plade"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Selv-Test"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s først"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Opvarmning fejlet"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Fejl: reserve temp"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Temp løber løbsk"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Fejl: Maks temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Fejl: Min temp"); - PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER STOPPET"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reset Venligst"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // Kun et bogstav - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // Kun et bogstav - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // Kun et bogstav - PROGMEM Language_Str MSG_HEATING = _UxGT("Opvarmer..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Opvarmer plade..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrer X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrer Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrer Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrerings Center"); + LSTR MSG_BED = _UxGT("Plade"); + LSTR MSG_FAN_SPEED = _UxGT("Blæser hastighed"); + LSTR MSG_FAN_SPEED_N = _UxGT("Blæser hastighed ~"); + LSTR MSG_CONTROL = _UxGT("Kontrol"); + LSTR MSG_MIN = _UxGT(" \002 Min"); + LSTR MSG_MAX = _UxGT(" \002 Max"); + LSTR MSG_FACTOR = _UxGT(" \002 Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("Til"); + LSTR MSG_LCD_OFF = _UxGT("Fra"); + LSTR MSG_SELECT = _UxGT("Vælg"); + LSTR MSG_SELECT_E = _UxGT("Vælg *"); + LSTR MSG_A_RETRACT = _UxGT("A-retract"); + LSTR MSG_A_TRAVEL = _UxGT("A-rejse"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); + LSTR MSG_MOTION = _UxGT("Bevægelse"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_CONTRAST = _UxGT("LCD kontrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Gem i EEPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Hent fra EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Gendan Defaults"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Genopfrisk"); + LSTR MSG_INFO_SCREEN = _UxGT("Info skærm"); + LSTR MSG_PREPARE = _UxGT("Forbered"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pause printet"); + LSTR MSG_RESUME_PRINT = _UxGT("Forsæt printet"); + LSTR MSG_STOP_PRINT = _UxGT("Stop printet"); + LSTR MSG_MEDIA_MENU = _UxGT("Print fra SD"); + LSTR MSG_NO_MEDIA = _UxGT("Intet SD kort"); + LSTR MSG_DWELL = _UxGT("Dvale..."); + LSTR MSG_USERWAIT = _UxGT("Venter på bruger..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Print annulleret"); + LSTR MSG_NO_MOVE = _UxGT("Ingen bevægelse."); + LSTR MSG_KILLED = _UxGT("DRÆBT. "); + LSTR MSG_STOPPED = _UxGT("STOPPET. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Tilbagetræk mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Skift Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Tilbagetræk V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Skift Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Skift filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Skift filament *"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Skift SD kort"); + LSTR MSG_ZPROBE_OUT = _UxGT("Probe udenfor plade"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Selv-Test"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s først"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Opvarmning fejlet"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Fejl: reserve temp"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("Temp løber løbsk"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Fejl: Maks temp"); + LSTR MSG_ERR_MINTEMP = _UxGT("Fejl: Min temp"); + LSTR MSG_HALTED = _UxGT("PRINTER STOPPET"); + LSTR MSG_PLEASE_RESET = _UxGT("Reset Venligst"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // Kun et bogstav + LSTR MSG_SHORT_HOUR = _UxGT("h"); // Kun et bogstav + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // Kun et bogstav + LSTR MSG_HEATING = _UxGT("Opvarmer..."); + LSTR MSG_BED_HEATING = _UxGT("Opvarmer plade..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrer X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrer Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrer Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrerings Center"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Om Printer"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); + LSTR MSG_INFO_MENU = _UxGT("Om Printer"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Ant. Prints"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Færdige"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total print tid"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Længste print"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruderet"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Ant. Prints"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Færdige"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total print tid"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Længste print"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruderet"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Prints"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Færdige"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Længste"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderet"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Prints"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Færdige"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Længste"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderet"); #endif - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Strømfors."); + LSTR MSG_INFO_PSU = _UxGT("Strømfors."); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driv Styrke"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driv %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driv %"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrke"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driv %"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Forsæt print"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Forsæt print"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Forkert printer"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Forkert printer"); #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vent på start", "af filament", "skift")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Vent på", "filament udskyd.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Indsæt filament", "og tryk på knap", "for at fortsætte...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Vent på", "filament indtag")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Vent på at print", "fortsætter")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vent på start", "af filament", "skift")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Vent på", "filament udskyd.")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Indsæt filament", "og tryk på knap", "for at fortsætte...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Vent på", "filament indtag")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Vent på at print", "fortsætter")); #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Vent venligst...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Udskyder...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Indsæt og klik")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Indtager...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Fortsætter...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Vent venligst...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Udskyder...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Indsæt og klik")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Indtager...")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Fortsætter...")); #endif // LCD_HEIGHT < 4 } diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 318f00315b..4c8b5e5af9 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -31,620 +31,620 @@ namespace Language_de { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Deutsch"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Deutsch"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" bereit"); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("JA"); - PROGMEM Language_Str MSG_NO = _UxGT("NEIN"); - PROGMEM Language_Str MSG_BACK = _UxGT("Zurück"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Abbruch..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD Init fehlgesch."); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge."); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Hauptmenü"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguration"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug-Menü"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Statusbalken-Test"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivellieren fertig!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Ausblendhöhe"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Setze Homeversatz"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Homeversatz aktiv"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in marlinui.cpp + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" bereit"); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("JA"); + LSTR MSG_NO = _UxGT("NEIN"); + LSTR MSG_BACK = _UxGT("Zurück"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abbruch..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); + LSTR MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); + LSTR MSG_SD_INIT_FAIL = _UxGT("SD Init fehlgesch."); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge."); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); + LSTR MSG_MAIN = _UxGT("Hauptmenü"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); + LSTR MSG_CONFIGURATION = _UxGT("Konfiguration"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters + LSTR MSG_DEBUG_MENU = _UxGT("Debug-Menü"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Statusbalken-Test"); + LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); + LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivellieren fertig!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Ausblendhöhe"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Setze Homeversatz"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Homeversatz aktiv"); + LSTR MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in marlinui.cpp #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" Vorwärmen ~"); - PROGMEM Language_Str MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" Extr. Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" Extr. Vorwärm. ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" Alles Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" Bett Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" Einstellungen"); + LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" Vorwärmen"); + LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" Vorwärmen ~"); + LSTR MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" Extr. Vorwärmen"); + LSTR MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" Extr. Vorwärm. ~"); + LSTR MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" Alles Vorwärmen"); + LSTR MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" Bett Vorwärmen"); + LSTR MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" Einstellungen"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("$ Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("$ Vorwärmen") " ~"; - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("$ Extr. Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("$ Extr. Vorwärm. ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("$ Alles Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("$ Bett Vorwärmen"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("$ Einstellungen"); + LSTR MSG_PREHEAT_M = _UxGT("$ Vorwärmen"); + LSTR MSG_PREHEAT_M_H = _UxGT("$ Vorwärmen") " ~"; + LSTR MSG_PREHEAT_M_END = _UxGT("$ Extr. Vorwärmen"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("$ Extr. Vorwärm. ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("$ Alles Vorwärmen"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("$ Bett Vorwärmen"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("$ Einstellungen"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("benutzerdef. Heizen"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Abkühlen"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenz"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laserleistung"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindel-Steuerung"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindelleistung"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindelrichtung"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Netzteil ein"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Netzteil aus"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudieren"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Einzug"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Achsen bewegen"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bett-Nivellierung"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Bett nivellieren"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bett ausrichten"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nächste Ecke"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Netz Editor"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Netzbearb. angeh."); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Messpunkt"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Benutzer-Menü"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Sondentest"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punkt"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Zu weit draußen"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Abweichung"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX-Modus"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Werkzeugversätze"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Autom. parken"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplizieren"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Spiegelkopie"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("vollstä. Kontrolle"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. Düse X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. Düse Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. Düse Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 ausführen"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL-Werkzeuge"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Netz manuell erst."); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Unterlegen & messen"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Messen"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Entfernen & messen"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Nächster Punkt..."); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktivieren"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktivieren"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Betttemperatur"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Betttemperatur"); - 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("Netz bearbeiten"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Eigenes Netz bearb."); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Feineinstellung..."); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Bearbeitung beendet"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Eigenes Netz erst."); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Netz erstellen"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("benutzerdef. Heizen"); + LSTR MSG_COOLDOWN = _UxGT("Abkühlen"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frequenz"); + LSTR MSG_LASER_MENU = _UxGT("Laser"); + LSTR MSG_LASER_POWER = _UxGT("Laserleistung"); + LSTR MSG_SPINDLE_MENU = _UxGT("Spindel-Steuerung"); + LSTR MSG_SPINDLE_POWER = _UxGT("Spindelleistung"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindelrichtung"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Netzteil ein"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Netzteil aus"); + LSTR MSG_EXTRUDE = _UxGT("Extrudieren"); + LSTR MSG_RETRACT = _UxGT("Einzug"); + LSTR MSG_MOVE_AXIS = _UxGT("Achsen bewegen"); + LSTR MSG_BED_LEVELING = _UxGT("Bett-Nivellierung"); + LSTR MSG_LEVEL_BED = _UxGT("Bett nivellieren"); + LSTR MSG_BED_TRAMMING = _UxGT("Bett ausrichten"); + LSTR MSG_NEXT_CORNER = _UxGT("Nächste Ecke"); + LSTR MSG_MESH_EDITOR = _UxGT("Netz Editor"); + LSTR MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); + LSTR MSG_EDITING_STOPPED = _UxGT("Netzbearb. angeh."); + LSTR MSG_PROBING_POINT = _UxGT("Messpunkt"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Benutzer-Menü"); + LSTR MSG_M48_TEST = _UxGT("M48 Sondentest"); + LSTR MSG_M48_POINT = _UxGT("M48 Punkt"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Zu weit draußen"); + LSTR MSG_M48_DEVIATION = _UxGT("Abweichung"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX-Modus"); + LSTR MSG_OFFSETS_MENU = _UxGT("Werkzeugversätze"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Autom. parken"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplizieren"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Spiegelkopie"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("vollstä. Kontrolle"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. Düse X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. Düse Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. Düse Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("G29 ausführen"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL-Werkzeuge"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Netz manuell erst."); + LSTR MSG_UBL_BC_INSERT = _UxGT("Unterlegen & messen"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Messen"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Entfernen & messen"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Nächster Punkt..."); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktivieren"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktivieren"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Betttemperatur"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Betttemperatur"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hotend-Temp."); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend-Temp."); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Netz bearbeiten"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Eigenes Netz bearb."); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Feineinstellung..."); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Bearbeitung beendet"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Eigenes Netz erst."); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Netz erstellen"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("$ Netz erstellen"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("$ Netz validieren"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("$ Netz erstellen"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("$ Netz validieren"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Netz erstellen kalt"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Netzhöhe einst."); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höhe"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Netz validieren"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Eig. Netz validieren"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 heizt Bett"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Düse aufheizen"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Manuell Prime..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Feste Länge Prime"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Priming fertig"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 abgebrochen"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("G26 verlassen"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Netzerst. forts."); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Netz-Nivellierung"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkt-Nivell."); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Gitternetz-Nivell."); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Netz nivellieren"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Eckpunkte"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Kartentyp"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Karte ausgeben"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Ausgabe für Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Ausgabe für CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Externe Sicherung"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL-Info ausgeben"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Menge an Füllung"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manuelles Füllen"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Cleveres Füllen"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Netz Füllen"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Alles annullieren"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Nächstlieg. ann."); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Feineinst. Alles"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Feineinst. Nächstl."); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Netz-Speicherplatz"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Speicherort"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Bettnetz laden"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Bettnetz speichern"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Netz %i geladen"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Netz %i gespeichert"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Kein Speicher"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err:UBL speichern"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err:UBL wiederherst."); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Versatz: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Versatz angehalten"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Schrittweises UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Netz erstellen kalt"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Cleveres Füllen"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Netz validieren"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Feineinst. Alles"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Netz validieren"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Feineinst. Alles"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Bettnetz speichern"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Netz erstellen kalt"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Netzhöhe einst."); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höhe"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Netz validieren"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Eig. Netz validieren"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 heizt Bett"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Düse aufheizen"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manuell Prime..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Feste Länge Prime"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Priming fertig"); + LSTR MSG_G26_CANCELED = _UxGT("G26 abgebrochen"); + LSTR MSG_G26_LEAVING = _UxGT("G26 verlassen"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Netzerst. forts."); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Netz-Nivellierung"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkt-Nivell."); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Gitternetz-Nivell."); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Netz nivellieren"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Eckpunkte"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Kartentyp"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Karte ausgeben"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Ausgabe für Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Ausgabe für CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Externe Sicherung"); + LSTR MSG_UBL_INFO_UBL = _UxGT("UBL-Info ausgeben"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Menge an Füllung"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuelles Füllen"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Cleveres Füllen"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Netz Füllen"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Alles annullieren"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Nächstlieg. ann."); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Feineinst. Alles"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Feineinst. Nächstl."); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Netz-Speicherplatz"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Speicherort"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Bettnetz laden"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Bettnetz speichern"); + LSTR MSG_MESH_LOADED = _UxGT("Netz %i geladen"); + LSTR MSG_MESH_SAVED = _UxGT("Netz %i gespeichert"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Kein Speicher"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err:UBL speichern"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err:UBL wiederherst."); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Versatz: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Versatz angehalten"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Schrittweises UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Netz erstellen kalt"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Cleveres Füllen"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Netz validieren"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Feineinst. Alles"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Netz validieren"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Feineinst. Alles"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Bettnetz speichern"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Licht-Steuerung"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Licht"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Licht-Einstellung"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rot"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Gelb"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Grün"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blau"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violett"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Weiß"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Benutzerdefiniert"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensität Rot"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensität Grün"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensität Blau"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensität Weiß"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Helligkeit"); + LSTR MSG_LED_CONTROL = _UxGT("Licht-Steuerung"); + LSTR MSG_LEDS = _UxGT("Licht"); + LSTR MSG_LED_PRESETS = _UxGT("Licht-Einstellung"); + LSTR MSG_SET_LEDS_RED = _UxGT("Rot"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Gelb"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Grün"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Blau"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violett"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Weiß"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Benutzerdefiniert"); + LSTR MSG_INTENSITY_R = _UxGT("Intensität Rot"); + LSTR MSG_INTENSITY_G = _UxGT("Intensität Grün"); + LSTR MSG_INTENSITY_B = _UxGT("Intensität Blau"); + LSTR MSG_INTENSITY_W = _UxGT("Intensität Weiß"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Helligkeit"); - PROGMEM Language_Str MSG_MOVING = _UxGT("In Bewegung..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Abstand XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Bewege X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Bewege Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Bewege Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Bewege Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Bewege Extruder *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT(" %s mm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10,0 mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100,0 mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Geschw."); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bett Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Düse ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Düse geparkt"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düse bereit"); - PROGMEM Language_Str MSG_BED = _UxGT("Bett"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Gehäuse"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Lüfter"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Lüfter ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Gespeich. Lüfter ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Geschw. Extralüfter"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Geschw. Extralüfter ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Lüfter Kontroller"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Lüfter Leerlauf"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Motorlast Modus"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Lüfter Motorlast"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Ausschalt Delay"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flussrate"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flussrate ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Einstellungen"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Faktor"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto Temperatur"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("an"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("aus"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Auswählen"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Auswählen *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Beschleunigung"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Geschwindigkeit"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("V max ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("V max ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("V max ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("V max ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("V max ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("V max ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("V max ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("V max *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("V min "); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Beschleunigung"); - PROGMEM Language_Str MSG_AMAX = _UxGT("A max "); // space intentional - PROGMEM Language_Str MSG_AMAX_A = _UxGT("A max ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("A max ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("A max ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("A max ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("A max ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("A max ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("A max ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("A max *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A Einzug"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A Leerfahrt"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("max. Frequenz"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("min. Vorschub"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_E_STEPS = LCD_STR_E _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Bewegung"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Filamentdurchmesser"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Filamentdurchmesser *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Entladen mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Laden mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Vorschubfaktor"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Vorschubfaktor *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD-Kontrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Konfig. speichern"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Standardwerte laden"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Werkseinstellungen"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fehler"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fehler"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fehler"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Einstell. gespei."); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("FW Update vom Medium"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Drucker neustarten"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aktualisieren"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Vorbereitung"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Justierung"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power Monitor"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Strom"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Spannung"); - PROGMEM Language_Str MSG_POWER = _UxGT("Power"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Starte Druck"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Weiter"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Bestätigen"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drucken"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reseten"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorieren"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Abbrechen"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fertig"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Zurück"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Weiter"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Pause..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("SD-Druck fortsetzen"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("SD-Druck abbrechen"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objekt drucken"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Druck vom Medium"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Kein Medium"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Warten..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Klick zum Fortsetzen"); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druck pausiert..."); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Druckt..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druck abgebrochen"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druck fertig"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Motoren angeschaltet"); - PROGMEM Language_Str MSG_KILLED = _UxGT("ABGEBROCHEN"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ANGEHALTEN"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Einzug mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Wechs. Einzug mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("V Einzug"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Z-Sprung mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Wechs. Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Autom. Einzug"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Einzugslänge"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Einzug"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Entladelänge"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Werkzeugwechsel"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z anheben"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime-Geschwin."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Einzug-Geschwin."); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Kopf parken"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Rückzugsgeschwindigkeit"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Lüfter Geschwindigkeit"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Lüfter Zeit"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto AN"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AUS"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Werkzeugmigration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-Migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Letzter Extruder"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrieren zu *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filament wechseln"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filament wechseln *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Filament laden"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Filament laden *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Filament entladen"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Filament entladen *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Alles entladen"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Medium initial."); // Manually initialize the SD-card via user interface - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Medium getauscht"); // SD-card changed by user. For machines with no autocarddetect. Both send "M21" - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Medium freigeben"); // if Marlin gets confused - M22 - 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("Selbsttest"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Zurücksetzen"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Einfahren"); - 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_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."); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test Z-Versatz"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Speichern"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI ausfahren"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Sonde ausfahren"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Sonde einfahren"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Vorher %s%s%s homen"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Sondenversatz"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Sondenversatz X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Sondenversatz Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Sondenversatz Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Abbr. mit Endstopp"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("HEIZEN ERFOLGLOS"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEMP-ABWEI."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BETT") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("GEH.") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = " " LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MINTEMP = " " LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); - PROGMEM Language_Str MSG_HALTED = _UxGT("DRUCKER GESTOPPT"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Bitte neustarten"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("t"); // One character only - 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("heizt..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("kühlt..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Bett heizt..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Bett kühlt..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Gehäuse heizt..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Gehäuse kühlt..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrieren"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibriere X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibriere Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibriere Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriere Mitte"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Einst. anzeig."); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autom. Kalibrierung"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Höhe setzen"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sondenversatz Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Höhe"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radius"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Über den Drucker"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Drucker-Info"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Punkt-Nivellierung"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineare Nivellierung"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineare Nivell."); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Netz-Nivellierung"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Drucker-Statistik"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Board-Info"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistoren"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruder"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudrate"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: AUS"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: AN"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Beleuchtung"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); + LSTR MSG_MOVING = _UxGT("In Bewegung..."); + LSTR MSG_FREE_XY = _UxGT("Abstand XY"); + LSTR MSG_MOVE_X = _UxGT("Bewege X"); + LSTR MSG_MOVE_Y = _UxGT("Bewege Y"); + LSTR MSG_MOVE_Z = _UxGT("Bewege Z"); + LSTR MSG_MOVE_E = _UxGT("Bewege Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Bewege Extruder *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); + LSTR MSG_MOVE_N_MM = _UxGT(" %s mm"); + LSTR MSG_MOVE_01MM = _UxGT(" 0,1 mm"); + LSTR MSG_MOVE_1MM = _UxGT(" 1,0 mm"); + LSTR MSG_MOVE_10MM = _UxGT(" 10,0 mm"); + LSTR MSG_MOVE_100MM = _UxGT("100,0 mm"); + LSTR MSG_SPEED = _UxGT("Geschw."); + LSTR MSG_BED_Z = _UxGT("Bett Z"); + LSTR MSG_NOZZLE = _UxGT("Düse"); + LSTR MSG_NOZZLE_N = _UxGT("Düse ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Düse geparkt"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Düse bereit"); + LSTR MSG_BED = _UxGT("Bett"); + LSTR MSG_CHAMBER = _UxGT("Gehäuse"); + LSTR MSG_FAN_SPEED = _UxGT("Lüfter"); + LSTR MSG_FAN_SPEED_N = _UxGT("Lüfter ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Gespeich. Lüfter ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Geschw. Extralüfter"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Geschw. Extralüfter ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Lüfter Kontroller"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Lüfter Leerlauf"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Motorlast Modus"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Lüfter Motorlast"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Ausschalt Delay"); + LSTR MSG_FLOW = _UxGT("Flussrate"); + LSTR MSG_FLOW_N = _UxGT("Flussrate ~"); + LSTR MSG_CONTROL = _UxGT("Einstellungen"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Faktor"); + LSTR MSG_AUTOTEMP = _UxGT("Auto Temperatur"); + LSTR MSG_LCD_ON = _UxGT("an"); + LSTR MSG_LCD_OFF = _UxGT("aus"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); + LSTR MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); + LSTR MSG_SELECT = _UxGT("Auswählen"); + LSTR MSG_SELECT_E = _UxGT("Auswählen *"); + LSTR MSG_ACC = _UxGT("Beschleunigung"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + LSTR MSG_VELOCITY = _UxGT("Geschwindigkeit"); + LSTR MSG_VMAX_A = _UxGT("V max ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("V max ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("V max ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("V max ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("V max ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("V max ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("V max ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("V max *"); + LSTR MSG_VMIN = _UxGT("V min "); + LSTR MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); + LSTR MSG_ACCELERATION = _UxGT("Beschleunigung"); + LSTR MSG_AMAX = _UxGT("A max "); // space intentional + LSTR MSG_AMAX_A = _UxGT("A max ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("A max ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("A max ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("A max ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("A max ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("A max ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("A max ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("A max *"); + LSTR MSG_A_RETRACT = _UxGT("A Einzug"); + LSTR MSG_A_TRAVEL = _UxGT("A Leerfahrt"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("max. Frequenz"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("min. Vorschub"); + LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); + LSTR MSG_E_STEPS = LCD_STR_E _UxGT(" Steps/mm"); + LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); + LSTR MSG_MOTION = _UxGT("Bewegung"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Filamentdurchmesser"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Filamentdurchmesser *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Entladen mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Laden mm"); + LSTR MSG_ADVANCE_K = _UxGT("Vorschubfaktor"); + LSTR MSG_ADVANCE_K_E = _UxGT("Vorschubfaktor *"); + LSTR MSG_CONTRAST = _UxGT("LCD-Kontrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Konfig. speichern"); + LSTR MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Standardwerte laden"); + LSTR MSG_INIT_EEPROM = _UxGT("Werkseinstellungen"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fehler"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fehler"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fehler"); + LSTR MSG_SETTINGS_STORED = _UxGT("Einstell. gespei."); + LSTR MSG_MEDIA_UPDATE = _UxGT("FW Update vom Medium"); + LSTR MSG_RESET_PRINTER = _UxGT("Drucker neustarten"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aktualisieren"); + LSTR MSG_INFO_SCREEN = _UxGT("Info"); + LSTR MSG_PREPARE = _UxGT("Vorbereitung"); + LSTR MSG_TUNE = _UxGT("Justierung"); + LSTR MSG_POWER_MONITOR = _UxGT("Power Monitor"); + LSTR MSG_CURRENT = _UxGT("Strom"); + LSTR MSG_VOLTAGE = _UxGT("Spannung"); + LSTR MSG_POWER = _UxGT("Power"); + LSTR MSG_START_PRINT = _UxGT("Starte Druck"); + LSTR MSG_BUTTON_NEXT = _UxGT("Weiter"); + LSTR MSG_BUTTON_INIT = _UxGT("Bestätigen"); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Drucken"); + LSTR MSG_BUTTON_RESET = _UxGT("Reseten"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorieren"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Abbrechen"); + LSTR MSG_BUTTON_DONE = _UxGT("Fertig"); + LSTR MSG_BUTTON_BACK = _UxGT("Zurück"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Weiter"); + LSTR MSG_PAUSING = _UxGT("Pause..."); + LSTR MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); + LSTR MSG_RESUME_PRINT = _UxGT("SD-Druck fortsetzen"); + LSTR MSG_STOP_PRINT = _UxGT("SD-Druck abbrechen"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Objekt drucken"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); + LSTR MSG_MEDIA_MENU = _UxGT("Druck vom Medium"); + LSTR MSG_NO_MEDIA = _UxGT("Kein Medium"); + LSTR MSG_DWELL = _UxGT("Warten..."); + LSTR MSG_USERWAIT = _UxGT("Klick zum Fortsetzen"); + LSTR MSG_PRINT_PAUSED = _UxGT("Druck pausiert..."); + LSTR MSG_PRINTING = _UxGT("Druckt..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Druck abgebrochen"); + LSTR MSG_PRINT_DONE = _UxGT("Druck fertig"); + LSTR MSG_NO_MOVE = _UxGT("Motoren angeschaltet"); + LSTR MSG_KILLED = _UxGT("ABGEBROCHEN"); + LSTR MSG_STOPPED = _UxGT("ANGEHALTEN"); + LSTR MSG_CONTROL_RETRACT = _UxGT("Einzug mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Wechs. Einzug mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("V Einzug"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Z-Sprung mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Wechs. Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Autom. Einzug"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Einzugslänge"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Einzug"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Entladelänge"); + LSTR MSG_TOOL_CHANGE = _UxGT("Werkzeugwechsel"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z anheben"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime-Geschwin."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Einzug-Geschwin."); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Kopf parken"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Rückzugsgeschwindigkeit"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Lüfter Geschwindigkeit"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Lüfter Zeit"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto AN"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AUS"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Werkzeugmigration"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-Migration"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Letzter Extruder"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrieren zu *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Filament wechseln"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Filament wechseln *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Filament laden"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Filament laden *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Filament entladen"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Filament entladen *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Alles entladen"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Medium initial."); // Manually initialize the SD-card via user interface + LSTR MSG_CHANGE_MEDIA = _UxGT("Medium getauscht"); // SD-card changed by user. For machines with no autocarddetect. Both send "M21" + LSTR MSG_RELEASE_MEDIA = _UxGT("Medium freigeben"); // if Marlin gets confused - M22 + LSTR MSG_ZPROBE_OUT = _UxGT("Z-Sonde außerhalb"); + LSTR MSG_SKEW_FACTOR = _UxGT("Korrekturfaktor"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Selbsttest"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Zurücksetzen"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Einfahren"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Ausfahren"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modus"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modus"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Modus"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Setze auf 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Setze auf OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Modus: "); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("ACHTUNG: Falsche Einstellung - kann zu Beschädigung führen! Fortfahren?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("TouchMI initial."); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test Z-Versatz"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Speichern"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI ausfahren"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Z-Sonde ausfahren"); + LSTR MSG_MANUAL_STOW = _UxGT("Z-Sonde einfahren"); + LSTR MSG_HOME_FIRST = _UxGT("Vorher %s%s%s homen"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Sondenversatz"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Sondenversatz X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Sondenversatz Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Sondenversatz Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Abbr. mit Endstopp"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("HEIZEN ERFOLGLOS"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEMP-ABWEI."); + LSTR MSG_THERMAL_RUNAWAY = " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BETT") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("GEH.") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); + LSTR MSG_ERR_MAXTEMP = " " LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); + LSTR MSG_ERR_MINTEMP = " " LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); + LSTR MSG_HALTED = _UxGT("DRUCKER GESTOPPT"); + LSTR MSG_PLEASE_RESET = _UxGT("Bitte neustarten"); + LSTR MSG_SHORT_DAY = _UxGT("t"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("heizt..."); + LSTR MSG_COOLING = _UxGT("kühlt..."); + LSTR MSG_BED_HEATING = _UxGT("Bett heizt..."); + LSTR MSG_BED_COOLING = _UxGT("Bett kühlt..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Gehäuse heizt..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Gehäuse kühlt..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrieren"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibriere X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibriere Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibriere Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriere Mitte"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Einst. anzeig."); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autom. Kalibrierung"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Höhe setzen"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sondenversatz Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Höhe"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); + LSTR MSG_INFO_MENU = _UxGT("Über den Drucker"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Drucker-Info"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-Punkt-Nivellierung"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Lineare Nivellierung"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilineare Nivell."); + LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_MESH_LEVELING = _UxGT("Netz-Nivellierung"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Drucker-Statistik"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Board-Info"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistoren"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extruder"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baudrate"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: AUS"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: AN"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_CASE_LIGHT = _UxGT("Beleuchtung"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette Drucke"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Gesamte Druckzeit"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längste Druckzeit"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Gesamt Extrudiert"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette Drucke"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte Druckzeit"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste Druckzeit"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Gesamt Extrudiert"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Drucke"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Gesamte"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längste"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Drucke"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Netzteil"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Motorleistung"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Treiber %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Treiber %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC Verbindungsfehler"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Werte speichern"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT WECHSEL"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("DRUCK PAUSIERT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("FILAMENT LADEN"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("FILAMENT ENTLADEN"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FORTS. OPTIONEN:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Mehr entladen"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Druck weiter"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Düse: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Runout-Sensor"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + LSTR MSG_INFO_PSU = _UxGT("Netzteil"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Motorleistung"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Treiber %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC Verbindungsfehler"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Werte speichern"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT WECHSEL"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("DRUCK PAUSIERT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("FILAMENT LADEN"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("FILAMENT ENTLADEN"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FORTS. OPTIONEN:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Mehr entladen"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Druck weiter"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Düse: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout-Sensor"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMENT WÄHLEN"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU handeln erfor."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Druck fortsetzen"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Fortfahren..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Filament laden"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Lade alle"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Düse laden"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Filament auswerfen"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Filament ~ auswerfen"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Filament entladen "); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Lade Fila. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Fila. auswerfen..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Fila. entladen..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Alle"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("setze MMU zurück"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU zurücksetzen..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Entfernen, klicken"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMENT WÄHLEN"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU handeln erfor."); + LSTR MSG_MMU2_RESUME = _UxGT("Druck fortsetzen"); + LSTR MSG_MMU2_RESUMING = _UxGT("Fortfahren..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Filament laden"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Lade alle"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Düse laden"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Filament auswerfen"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Filament ~ auswerfen"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Filament entladen "); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Lade Fila. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Fila. auswerfen..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Fila. entladen..."); + LSTR MSG_MMU2_ALL = _UxGT("Alle"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("setze MMU zurück"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU zurücksetzen..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Entfernen, klicken"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponente ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mixer"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); // equal Farbverlauf - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Volle Gradient"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Mix umschalten"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Zyklus Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Umgekehrte Gradient"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktives V-Tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("V-Tool Start"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("V-Tool Ende"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("V-Tool Alias"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("V-Tools Reseten"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("V-Tool Mix sichern"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-Tools ist resetet"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Z Start:"); - PROGMEM Language_Str MSG_END_Z = _UxGT("Z Ende:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Spiele"); - 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"); + LSTR MSG_MIX = _UxGT("Mix"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponente ="); + LSTR MSG_MIXER = _UxGT("Mixer"); + LSTR MSG_GRADIENT = _UxGT("Gradient"); // equal Farbverlauf + LSTR MSG_FULL_GRADIENT = _UxGT("Volle Gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Mix umschalten"); + LSTR MSG_CYCLE_MIX = _UxGT("Zyklus Mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Umgekehrte Gradient"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktives V-Tool"); + LSTR MSG_START_VTOOL = _UxGT("V-Tool Start"); + LSTR MSG_END_VTOOL = _UxGT("V-Tool Ende"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("V-Tool Alias"); + LSTR MSG_RESET_VTOOLS = _UxGT("V-Tools Reseten"); + LSTR MSG_COMMIT_VTOOL = _UxGT("V-Tool Mix sichern"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-Tools ist resetet"); + LSTR MSG_START_Z = _UxGT("Z Start:"); + LSTR MSG_END_Z = _UxGT("Z Ende:"); + LSTR MSG_GAMES = _UxGT("Spiele"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("ungült. Seitenzahl"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("ungült. Seitengeschw."); + LSTR MSG_BAD_PAGE = _UxGT("ungült. Seitenzahl"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("ungült. Seitengeschw."); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Passwort bearbeiten"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login erforderlich"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Passwort Einstellungen"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("PIN eingeben"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Passwort ändern"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Passwort löschen"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Passwort ist "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("von vorn beginnen"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Bald speichern!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Passwort gelöscht"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Passwort bearbeiten"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Login erforderlich"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Passwort Einstellungen"); + LSTR MSG_ENTER_DIGIT = _UxGT("PIN eingeben"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Passwort ändern"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Passwort löschen"); + LSTR MSG_PASSWORD_SET = _UxGT("Passwort ist "); + LSTR MSG_START_OVER = _UxGT("von vorn beginnen"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Bald speichern!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Passwort gelöscht"); // // Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen // ...oder 2 Zeilen auf einem 3-Zeilen-Display. #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Knopf drücken um", "Druck fortzusetzen")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_2_LINE("Druck ist", "pausiert...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Warte auf den", "Start des", "Filamentwechsels...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filament einlegen", "und Knopf drücken", "um fortzusetzen")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Knopf drücken um", "Düse aufzuheizen")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Düse heizt auf", "bitte warten...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Warte auf", "Entnahme", "des Filaments...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Warte auf", "Laden des", "Filaments...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Warte auf", "Spülung", "der Düse...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Klicke um", "die Düsenspülung", "zu beenden")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Warte auf", "Fortsetzen des", "Drucks...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Knopf drücken um", "Druck fortzusetzen")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_2_LINE("Druck ist", "pausiert...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Warte auf den", "Start des", "Filamentwechsels...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filament einlegen", "und Knopf drücken", "um fortzusetzen")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Knopf drücken um", "Düse aufzuheizen")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Düse heizt auf", "bitte warten...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Warte auf", "Entnahme", "des Filaments...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Warte auf", "Laden des", "Filaments...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Warte auf", "Spülung", "der Düse...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Klicke um", "die Düsenspülung", "zu beenden")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Warte auf", "Fortsetzen des", "Drucks...")); #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick zum Fortsetzen")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Pausiert...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Bitte warten...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Laden und Klick")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klick zum Heizen")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Heizen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Entnehmen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Laden...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spülen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klick zum beenden", "der Düsenspülung")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Fortsetzen...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick zum Fortsetzen")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Pausiert...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Bitte warten...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Laden und Klick")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klick zum Heizen")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Heizen...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Entnehmen...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Laden...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spülen...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klick zum beenden", "der Düsenspülung")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Fortsetzen...")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Treiber"); // Max length 18 characters - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Treiber Strom"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid threshold"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorloses Homing"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Schrittmodus"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop einsch."); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" im:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Spiel"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto. Kalibiren"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC Treiber"); // Max length 18 characters + LSTR MSG_TMC_CURRENT = _UxGT("Treiber Strom"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid threshold"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorloses Homing"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Schrittmodus"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop einsch."); + LSTR MSG_SERVICE_RESET = _UxGT("Reset"); + LSTR MSG_SERVICE_IN = _UxGT(" im:"); + LSTR MSG_BACKLASH = _UxGT("Spiel"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto. Kalibiren"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle Timeout, Temperatur fällt. Drücke Okay, um erneut aufzuheizen und fortzufahren."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle Timeout, Temperatur fällt. Drücke Okay, um erneut aufzuheizen und fortzufahren."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heizungs Timeout"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Heizungs Timeout"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Erneut aufheizen"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Erneut aufhei. ..."); + LSTR MSG_REHEAT = _UxGT("Erneut aufheizen"); + LSTR MSG_REHEATING = _UxGT("Erneut aufhei. ..."); } diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 824b90a232..625c3840d0 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -33,173 +33,185 @@ namespace Language_el { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Greek"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Greek"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" έτοιμο."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Εισαγωγή κάρτας"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Βασική Οθόνη"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση Μοτέρ"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); //SHORTEN - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Αρχικό σημείο X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Αρχικό σημείο Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Αρχικό σημείο Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Επαναφορά Επ. Εκτύπωσης"); //SHORTEN - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Επιπεδοποίηση επ. Εκτύπωσης περιμενει"); //SHORTEN - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Επόμενο σημείο"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Ολοκλήρωση επιπεδοποίησης!"); //SHORTEN - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός βασικών μετατοπίσεων"); //SHORTEN - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμόστηκαν οι μετατοπίσεις"); //SHORTEN - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" έτοιμος."); + LSTR MSG_YES = _UxGT("ΝΑΙ"); + LSTR MSG_NO = _UxGT("ΟΧΙ"); + LSTR MSG_BACK = _UxGT("Πίσω"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Προχωρημένες ρυθμίσεις"); + LSTR MSG_CONFIGURATION = _UxGT("Διαμόρφωση"); + + LSTR MSG_MEDIA_INSERTED = _UxGT("Κάρτα εισήχθη"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Κάρτα αφαιρέθη"); + LSTR MSG_MEDIA_WAITING = _UxGT("Αναμονή για κάρτα"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Ματαίωση..."); + LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB αφαιρέθη"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD"); + LSTR MSG_MAIN = _UxGT("Αρχική Οθόνη"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση μοτέρ"); + LSTR MSG_AUTO_HOME = _UxGT("Αυτόμ. επαναφορά XYZ"); + LSTR MSG_AUTO_HOME_X = _UxGT("Επαναφορά X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Επαναφορά Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Επαναφορά Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Αυτόμ. επαναφορά XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Πιέστε για έναρξη"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Επόμενο σημείο"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Τέλος επιπεδοποίησης!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός μετατοπίσεων"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμογή μετατοπίσεων"); + LSTR MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" όλα"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" bed"); //SHORTEN - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" επιβεβαίωση"); //SHORTEN + LSTR MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" όλα"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" bed"); //SHORTEN + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" επιβεβαίωση"); //SHORTEN - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Προθέρμανση $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Προθέρμανση $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Προθέρμανση $ End"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Προθέρμανση $ End ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Προθέρμανση $ όλα"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Προθέρμανση $ bed"); //SHORTEN - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Προθέρμανση $ επιβεβαίωση"); //SHORTEN + LSTR MSG_PREHEAT_M = _UxGT("Προθέρμανση $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Προθέρμανση $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Προθέρμανση $ End"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Προθέρμανση $ End ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Προθέρμανση $ όλα"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Προθέρμανση $ bed"); //SHORTEN + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Προθέρμανση $ επιβεβαίωση"); //SHORTEN #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Μειωση θερμοκρασιας"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Ενεργοποίηση"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Απενεργοποίηση"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Εξώθηση"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Ανάσυρση"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Μετακίνηση άξονα"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Επιπεδοποίηση Επ. Εκτύπωσης"); //SHORTEN - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Επιπεδοποίηση Επ. Εκτύπωσης"); //SHORTEN - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Μετακίνηση X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Εξωθητήρας"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Επ. Εκτύπωσης Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Ακροφύσιο ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Κλίνη"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Ταχύτητα ανεμιστήρα"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Ταχύτητα ανεμιστήρα ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Ροή"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Ροή ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Έλεγχος"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Αυτομ ρύθμιση θερ/σίας"); //SHORTEN - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Ενεργοποιημένο"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); - PROGMEM Language_Str MSG_ACC = _UxGT("Επιτάχυνση"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Vαντίδραση E"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("V Μέγιστο") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("V Μέγιστο") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("V Μέγιστο") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("V Μέγιστο") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("V Μέγιστο") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("V Μέγιστο") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("V Μέγιστο") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("V Μέγιστο *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("V Ελάχιστο"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Aμεγ *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Κίνηση"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Νήμα"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Κοντράστ LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Αποθήκευση"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Φόρτωση"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Επαναφορά ασφαλούς αντιγράφου"); //SHORTEN - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ανανέωση"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Οθόνη πληροφόρησης"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Προετοιμασία"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Συντονισμός"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Παύση εκτύπωσης"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Συνέχιση εκτύπωσης"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Διακοπή εκτύπωσης"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Εκτύπωση από SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Δεν βρέθηκε SD"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Αναστολή λειτουργίας"); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Αναμονή για χρήστη"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Διακόπτεται η εκτύπωση"); //SHORTEN - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Καμία κίνηση."); - PROGMEM Language_Str MSG_KILLED = _UxGT("ΤΕΡΜΑΤΙΣΜΟΣ. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ΔΙΑΚΟΠΗ. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Ανάσυρση μμ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Εναλλαγή ανάσυρσης μμ"); //SHORTEN - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Ανάσυρση V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Μεταπήδηση μμ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Αυτόματη ανάσυρση"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Αλλαγή νήματος"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Αλλαγή νήματος *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Προετοιμασία κάρτας SD"); //SHORTEN - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Αλλαγή κάρτας SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Διερεύνηση Z εκτός Επ.Εκτύπωσης"); //SHORTEN - PROGMEM Language_Str MSG_YX_UNHOMED = _UxGT("Επαναφορά Χ/Υ πριν από Ζ"); //SHORTEN - PROGMEM Language_Str MSG_XYZ_UNHOMED = _UxGT("Επαναφορά ΧΥΖ πρώτα"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Μετατόπιση Ζ"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Μικρό βήμα Χ"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Μικρό βήμα Υ"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Μικρό βήμα Ζ"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Ακύρωση endstop "); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Ανεπιτυχής θέρμανση"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("ΠΛΕΟΝΑΖΟΥΣΑ ΘΕΡΜΟΤΗΤΑ"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ΔΙΑΦΥΓΗ ΘΕΡΜΟΚΡΑΣΙΑΣ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("ΠΕΡΙΤΗ ΘΕΡΜΟΚΡΑΣΙΑ"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("ΜΗ ΕΠΑΡΚΗΣ ΘΕΡΜΟΚΡΑΣΙΑΣ"); //SHORTEN - PROGMEM Language_Str MSG_HALTED = _UxGT("H εκτύπωση διακόπηκε"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση ΕΠ. Εκτύπωσης"); //SHORTEN - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Βαθμονόμηση X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Βαθμονόμηση Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); + LSTR MSG_COOLDOWN = _UxGT("Αποθέρμανση"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Ενεργοποίηση"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Απενεργοποίηση"); + LSTR MSG_EXTRUDE = _UxGT("Εξώθηση"); + LSTR MSG_RETRACT = _UxGT("Ανάσυρση"); + LSTR MSG_MOVE_AXIS = _UxGT("Μετακίνηση άξονα"); + LSTR MSG_BED_LEVELING = _UxGT("Επιπεδοποίηση κλίνης"); + LSTR MSG_LEVEL_BED = _UxGT("Επιπεδοποίηση κλίνης"); + LSTR MSG_MOVE_X = _UxGT("Μετακίνηση X"); + LSTR MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); + LSTR MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); + LSTR MSG_MOVE_E = _UxGT("Εξωθητής"); + LSTR MSG_MOVE_EN = _UxGT("Εξωθητής *"); + LSTR MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); + LSTR MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); + LSTR MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); + LSTR MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + LSTR MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); + LSTR MSG_SPEED = _UxGT("Ταχύτητα"); + LSTR MSG_BED_Z = _UxGT("Επ. Εκτύπωσης Z"); + LSTR MSG_NOZZLE = _UxGT("Ακροφύσιο"); + LSTR MSG_NOZZLE_N = _UxGT("Ακροφύσιο ~"); + LSTR MSG_BED = _UxGT("Επ. Εκτύπωσης"); + LSTR MSG_FAN_SPEED = _UxGT("Ταχύτητα ανεμιστήρα"); + LSTR MSG_FAN_SPEED_N = _UxGT("Ταχύτητα ανεμιστήρα ~"); + LSTR MSG_FLOW = _UxGT("Ροή"); + LSTR MSG_FLOW_N = _UxGT("Ροή ~"); + LSTR MSG_CONTROL = _UxGT("Έλεγχος"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Αυτορρύθμιση θερ/σίας"); + LSTR MSG_LCD_ON = _UxGT("Ενεργοποιημένο"); + LSTR MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); + LSTR MSG_ACC = _UxGT("Επιτάχυνση"); + LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; + LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); + LSTR MSG_VMAX_A = _UxGT("V Μέγιστο") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("V Μέγιστο") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("V Μέγιστο") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("V Μέγιστο") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("V Μέγιστο") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("V Μέγιστο") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("V Μέγιστο") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("V Μέγιστο *"); + LSTR MSG_VMIN = _UxGT("V Ελάχιστο"); + LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); + LSTR MSG_ACCELERATION = _UxGT("Accel"); + LSTR MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); + LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); + LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); + LSTR MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); + LSTR MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); + LSTR MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); + LSTR MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); + LSTR MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); + LSTR MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); + LSTR MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); + LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); + LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); + LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); + LSTR MSG_MOTION = _UxGT("Κίνηση"); + LSTR MSG_FILAMENT = _UxGT("Νήμα"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); + LSTR MSG_CONTRAST = _UxGT("Αντίθεση LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Αποθήκευση σε EEPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Φόρτωση από EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Επαναφορά προεπιλογών"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ανανέωση"); + LSTR MSG_INFO_SCREEN = _UxGT("Οθόνη πληροφόρησης"); + LSTR MSG_PREPARE = _UxGT("Προετοιμασία"); + LSTR MSG_TUNE = _UxGT("Συντονισμός"); + LSTR MSG_PAUSE_PRINT = _UxGT("Παύση εκτύπωσης"); + LSTR MSG_RESUME_PRINT = _UxGT("Συνέχιση εκτύπωσης"); + LSTR MSG_STOP_PRINT = _UxGT("Διακοπή εκτύπωσης"); + LSTR MSG_MEDIA_MENU = _UxGT("Εκτύπωση από SD"); + LSTR MSG_NO_MEDIA = _UxGT("Δεν βρέθηκε SD"); + LSTR MSG_DWELL = _UxGT("Αναστολή λειτουργίας"); + LSTR MSG_USERWAIT = _UxGT("Αναμονή για χρήστη"); + LSTR MSG_PRINT_ABORTED = _UxGT("Εκτύπωση διεκόπη"); + LSTR MSG_NO_MOVE = _UxGT("Καμία κίνηση."); + LSTR MSG_KILLED = _UxGT("ΤΕΡΜΑΤΙΣΜΟΣ. "); + LSTR MSG_STOPPED = _UxGT("ΔΙΑΚΟΠΗ. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Ανάσυρση μμ"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Εναλλαγή ανάσυρσης mm"); //SHORTEN + LSTR MSG_CONTROL_RETRACTF = _UxGT("Ανάσυρση V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Μεταπήδηση mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_AUTORETRACT = _UxGT("Αυτόματη ανάσυρση"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Αλλαγή νήματος"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Αλλαγή νήματος *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Προετοιμασία SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Αλλαγή κάρτας SD"); + LSTR MSG_ZPROBE_OUT = _UxGT("Διερεύνηση Z εκτός Επ.Εκτύπωσης"); //SHORTEN + LSTR MSG_YX_UNHOMED = _UxGT("Επαναφορά Χ/Υ πρώτα"); + LSTR MSG_XYZ_UNHOMED = _UxGT("Επαναφορά ΧΥΖ πρώτα"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Μετατόπιση Ζ"); + LSTR MSG_BABYSTEP_X = _UxGT("Μικρό βήμα Χ"); + LSTR MSG_BABYSTEP_Y = _UxGT("Μικρό βήμα Υ"); + LSTR MSG_BABYSTEP_Z = _UxGT("Μικρό βήμα Ζ"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Ακύρωση endstop"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Αποτυχία θέρμανσης"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("ΠΛΕΟΝΑΖΟΥΣΑ ΘΕΡΜΟΤΗΤΑ"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ΘΕΡΜΙΚΗ ΔΙΑΦΥΓΗ"); + LSTR MSG_ERR_MAXTEMP = _UxGT("ΠΕΡΙΤΤΗ ΘΕΡΜΟΚΡΑΣΙΑ"); + LSTR MSG_ERR_MINTEMP = _UxGT("ΑΝΕΠΑΡΚΗΣ ΘΕΡΜΟΚΡΑΣΙΑ"); + LSTR MSG_HALTED = _UxGT("Εκτυπωτής διεκόπη"); + LSTR MSG_HEATING = _UxGT("Θερμαίνεται…"); + LSTR MSG_BED_HEATING = _UxGT("Θέρμανση κλίνης"); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Βαθμονόμηση X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Βαθμονόμηση Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); } diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index e5c169446b..5259962f02 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -33,174 +33,174 @@ namespace Language_el_gr { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Greek (Greece)"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Greek (Greece)"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" έτοιμο."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Εισαγωγή κάρτας"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Βασική Οθόνη"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση βηματιστή"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Αρχικό σημείο X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Αρχικό σημείο Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Αρχικό σημείο Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Επαναφορά στο αρχικό σημείο ΧΥΖ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Κάντε κλικ για να ξεκινήσετε"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Επόμενο σημείο"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Ολοκλήρωση επιπεδοποίησης!"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός βασικών μετατοπίσεων"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμόστηκαν οι μετατοπίσεις"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" έτοιμο."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Εισαγωγή κάρτας"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Βασική Οθόνη"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση βηματιστή"); + LSTR MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); + LSTR MSG_AUTO_HOME_X = _UxGT("Αρχικό σημείο X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Αρχικό σημείο Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Αρχικό σημείο Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Επαναφορά στο αρχικό σημείο ΧΥΖ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Κάντε κλικ για να ξεκινήσετε"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Επόμενο σημείο"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Ολοκλήρωση επιπεδοποίησης!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ορισμός βασικών μετατοπίσεων"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Εφαρμόστηκαν οι μετατοπίσεις"); + LSTR MSG_SET_ORIGIN = _UxGT("Ορισμός προέλευσης"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" όλα"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" κλίνη"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" επιβεβαίωση"); + LSTR MSG_PREHEAT_1 = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" End ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" όλα"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" κλίνη"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Προθέρμανση ") PREHEAT_1_LABEL _UxGT(" επιβεβαίωση"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Προθέρμανση $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Προθέρμανση $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Προθέρμανση $ End"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Προθέρμανση $ End ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Προθέρμανση $ όλα"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Προθέρμανση $ κλίνη"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Προθέρμανση $ επιβεβαίωση"); + LSTR MSG_PREHEAT_M = _UxGT("Προθέρμανση $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Προθέρμανση $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Προθέρμανση $ End"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Προθέρμανση $ End ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Προθέρμανση $ όλα"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Προθέρμανση $ κλίνη"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Προθέρμανση $ επιβεβαίωση"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Μειωση θερμοκρασιας"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Ενεργοποίηση"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Απενεργοποίηση"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Εξώθηση"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Ανάσυρση"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Μετακίνηση άξονα"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Επιπεδοποίηση κλίνης"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Επιπεδοποίηση κλίνης"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Μετακίνηση X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Εξωθητήρας"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Κλίνη Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Ακροφύσιο ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Κλίνη"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Ταχύτητα ανεμιστήρα"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Ταχύτητα ανεμιστήρα ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Ροή"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Ροή ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Έλεγχος"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Αυτομ. ρύθμιση θερμοκρασίας"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Ενεργοποιημένο"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); - PROGMEM Language_Str MSG_ACC = _UxGT("Επιτάχυνση"); - PROGMEM Language_Str MSG_JERK = _UxGT("Vαντίδραση"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Vαντίδραση E"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vμεγ ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vμεγ ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vμεγ ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vμεγ ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vμεγ ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vμεγ ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vμεγ ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vμεγ *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vελαχ"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accel"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Aμεγ *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Κίνηση"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Νήμα"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Κοντράστ LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Αποθήκευση"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Φόρτωση"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Επαναφορά ασφαλούς αντιγράφου"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ανανέωση"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Οθόνη πληροφόρησης"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Προετοιμασία"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Συντονισμός"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Παύση εκτύπωσης"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Συνέχιση εκτύπωσης"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Διακοπή εκτύπωσης"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Εκτύπωση από SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Δεν βρέθηκε SD"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Αναστολή λειτουργίας…"); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Αναμονή για χρήστη…"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Διακόπτεται η εκτύπωση"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Καμία κίνηση."); - PROGMEM Language_Str MSG_KILLED = _UxGT("ΤΕΡΜΑΤΙΣΜΟΣ. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ΔΙΑΚΟΠΗ. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Ανάσυρση μμ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Εναλλαγή ανάσυρσης μμ"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Ανάσυρση V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Μεταπήδηση μμ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Αυτόματη ανάσυρση"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Αλλαγή νήματος"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Αλλαγή νήματος *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Προετοιμασία κάρτας SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Αλλαγή κάρτας SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Διερεύνηση Z εκτός κλίνης"); - PROGMEM Language_Str MSG_YX_UNHOMED = _UxGT("Επαναφορά Χ/Υ πριν από Ζ"); - PROGMEM Language_Str MSG_XYZ_UNHOMED = _UxGT("Επαναφορά ΧΥΖ πρώτα"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Μετατόπιση Ζ"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Μικρό βήμα Χ"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Μικρό βήμα Υ"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Μικρό βήμα Ζ"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Ματαίωση endstop "); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Ανεπιτυχής θέρμανση"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Λάθος: ΠΛΕΟΝΑΖΟΥΣΑ ΘΕΡΜΟΤΗΤΑ"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ΔΙΑΦΥΓΗ ΘΕΡΜΟΤΗΤΑΣ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Λάθος: ΜΕΓΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Λάθος: ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση κλίνης…"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Βαθμονόμηση X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Βαθμονόμηση Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); + LSTR MSG_COOLDOWN = _UxGT("Μειωση θερμοκρασιας"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Ενεργοποίηση"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Απενεργοποίηση"); + LSTR MSG_EXTRUDE = _UxGT("Εξώθηση"); + LSTR MSG_RETRACT = _UxGT("Ανάσυρση"); + LSTR MSG_MOVE_AXIS = _UxGT("Μετακίνηση άξονα"); + LSTR MSG_BED_LEVELING = _UxGT("Επιπεδοποίηση κλίνης"); + LSTR MSG_LEVEL_BED = _UxGT("Επιπεδοποίηση κλίνης"); + LSTR MSG_MOVE_X = _UxGT("Μετακίνηση X"); + LSTR MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); + LSTR MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); + LSTR MSG_MOVE_E = _UxGT("Εξωθητήρας"); + LSTR MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); + LSTR MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); + LSTR MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); + LSTR MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); + LSTR MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + LSTR MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); + LSTR MSG_SPEED = _UxGT("Ταχύτητα"); + LSTR MSG_BED_Z = _UxGT("Κλίνη Z"); + LSTR MSG_NOZZLE = _UxGT("Ακροφύσιο"); + LSTR MSG_NOZZLE_N = _UxGT("Ακροφύσιο ~"); + LSTR MSG_BED = _UxGT("Κλίνη"); + LSTR MSG_FAN_SPEED = _UxGT("Ταχύτητα ανεμιστήρα"); + LSTR MSG_FAN_SPEED_N = _UxGT("Ταχύτητα ανεμιστήρα ~"); + LSTR MSG_FLOW = _UxGT("Ροή"); + LSTR MSG_FLOW_N = _UxGT("Ροή ~"); + LSTR MSG_CONTROL = _UxGT("Έλεγχος"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Αυτομ. ρύθμιση θερμοκρασίας"); + LSTR MSG_LCD_ON = _UxGT("Ενεργοποιημένο"); + LSTR MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); + LSTR MSG_ACC = _UxGT("Επιτάχυνση"); + LSTR MSG_JERK = _UxGT("Vαντίδραση"); + LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; + LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); + LSTR MSG_VMAX_A = _UxGT("Vμεγ ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vμεγ ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vμεγ ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vμεγ ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vμεγ ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vμεγ ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vμεγ ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vμεγ *"); + LSTR MSG_VMIN = _UxGT("Vελαχ"); + LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); + LSTR MSG_ACCELERATION = _UxGT("Accel"); + LSTR MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); + LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); + LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); + LSTR MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); + LSTR MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); + LSTR MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); + LSTR MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); + LSTR MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); + LSTR MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); + LSTR MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); + LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); + LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); + LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); + LSTR MSG_MOTION = _UxGT("Κίνηση"); + LSTR MSG_FILAMENT = _UxGT("Νήμα"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("Ε σε μμ") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Διάμετρος νήματος"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Διάμετρος νήματος *"); + LSTR MSG_CONTRAST = _UxGT("Κοντράστ LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Αποθήκευση"); + LSTR MSG_LOAD_EEPROM = _UxGT("Φόρτωση"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Επαναφορά ασφαλούς αντιγράφου"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ανανέωση"); + LSTR MSG_INFO_SCREEN = _UxGT("Οθόνη πληροφόρησης"); + LSTR MSG_PREPARE = _UxGT("Προετοιμασία"); + LSTR MSG_TUNE = _UxGT("Συντονισμός"); + LSTR MSG_PAUSE_PRINT = _UxGT("Παύση εκτύπωσης"); + LSTR MSG_RESUME_PRINT = _UxGT("Συνέχιση εκτύπωσης"); + LSTR MSG_STOP_PRINT = _UxGT("Διακοπή εκτύπωσης"); + LSTR MSG_MEDIA_MENU = _UxGT("Εκτύπωση από SD"); + LSTR MSG_NO_MEDIA = _UxGT("Δεν βρέθηκε SD"); + LSTR MSG_DWELL = _UxGT("Αναστολή λειτουργίας…"); + LSTR MSG_USERWAIT = _UxGT("Αναμονή για χρήστη…"); + LSTR MSG_PRINT_ABORTED = _UxGT("Διακόπτεται η εκτύπωση"); + LSTR MSG_NO_MOVE = _UxGT("Καμία κίνηση."); + LSTR MSG_KILLED = _UxGT("ΤΕΡΜΑΤΙΣΜΟΣ. "); + LSTR MSG_STOPPED = _UxGT("ΔΙΑΚΟΠΗ. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Ανάσυρση μμ"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Εναλλαγή ανάσυρσης μμ"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Ανάσυρση V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Μεταπήδηση μμ"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_AUTORETRACT = _UxGT("Αυτόματη ανάσυρση"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Αλλαγή νήματος"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Αλλαγή νήματος *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Προετοιμασία κάρτας SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Αλλαγή κάρτας SD"); + LSTR MSG_ZPROBE_OUT = _UxGT("Διερεύνηση Z εκτός κλίνης"); + LSTR MSG_YX_UNHOMED = _UxGT("Επαναφορά Χ/Υ πριν από Ζ"); + LSTR MSG_XYZ_UNHOMED = _UxGT("Επαναφορά ΧΥΖ πρώτα"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Μετατόπιση Ζ"); + LSTR MSG_BABYSTEP_X = _UxGT("Μικρό βήμα Χ"); + LSTR MSG_BABYSTEP_Y = _UxGT("Μικρό βήμα Υ"); + LSTR MSG_BABYSTEP_Z = _UxGT("Μικρό βήμα Ζ"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Ματαίωση endstop "); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Ανεπιτυχής θέρμανση"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Λάθος: ΠΛΕΟΝΑΖΟΥΣΑ ΘΕΡΜΟΤΗΤΑ"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ΔΙΑΦΥΓΗ ΘΕΡΜΟΤΗΤΑΣ"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Λάθος: ΜΕΓΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); + LSTR MSG_ERR_MINTEMP = _UxGT("Λάθος: ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); + LSTR MSG_HEATING = _UxGT("Θερμαίνεται…"); + LSTR MSG_BED_HEATING = _UxGT("Θέρμανση κλίνης…"); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Βαθμονόμηση X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Βαθμονόμηση Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Βαθμονόμηση Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Βαθμονόμηση κέντρου"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Εσφαλμένος εκτυπωτής"); } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 11c976ee41..520b5f7b21 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -44,726 +44,726 @@ #define MEDIA_TYPE_EN "Media" namespace Language_en { - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("English"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("English"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Ready."); - 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 = MEDIA_TYPE_EN _UxGT(" Inserted"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Waiting for card"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD Init Fail"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); - 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_RUN_AUTO_FILES = _UxGT("Run Auto Files"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Progress Bar Test"); - PROGMEM Language_Str MSG_HOMING = _UxGT("Homing"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; - PROGMEM Language_Str MSG_FILAMENT_SET = _UxGT("Filament Settings"); - PROGMEM Language_Str MSG_FILAMENT_MAN = _UxGT("Filament Management"); - PROGMEM Language_Str MSG_LEVBED_FL = _UxGT("Front Left"); - PROGMEM Language_Str MSG_LEVBED_FR = _UxGT("Front Right"); - PROGMEM Language_Str MSG_LEVBED_C = _UxGT("Center"); - PROGMEM Language_Str MSG_LEVBED_BL = _UxGT("Back Left"); - PROGMEM Language_Str MSG_LEVBED_BR = _UxGT("Back Right"); - PROGMEM Language_Str MSG_MANUAL_MESH = _UxGT("Manual Mesh"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Accuracy Achieved"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Homing XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Click to Begin"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Next Point"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Leveling Done!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Set Home Offsets"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Select Origin"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Last value "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Ready."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("YES"); + LSTR MSG_NO = _UxGT("NO"); + LSTR MSG_BACK = _UxGT("Back"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Aborting..."); + LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_EN _UxGT(" Inserted"); + LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); + LSTR MSG_MEDIA_WAITING = _UxGT("Waiting for card"); + LSTR MSG_SD_INIT_FAIL = _UxGT("SD Init Fail"); + LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); + LSTR MSG_MAIN = _UxGT("Main"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advanced Settings"); + LSTR MSG_CONFIGURATION = _UxGT("Configuration"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Run Auto Files"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); + LSTR MSG_DEBUG_MENU = _UxGT("Debug Menu"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Progress Bar Test"); + LSTR MSG_HOMING = _UxGT("Homing"); + LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); + LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); + LSTR MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; + LSTR MSG_FILAMENT_SET = _UxGT("Filament Settings"); + LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); + LSTR MSG_LEVBED_FL = _UxGT("Front Left"); + LSTR MSG_LEVBED_FR = _UxGT("Front Right"); + LSTR MSG_LEVBED_C = _UxGT("Center"); + LSTR MSG_LEVBED_BL = _UxGT("Back Left"); + LSTR MSG_LEVBED_BR = _UxGT("Back Right"); + LSTR MSG_MANUAL_MESH = _UxGT("Manual Mesh"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); + LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Accuracy Achieved"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Homing XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Click to Begin"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Next Point"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Leveling Done!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Set Home Offsets"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); + LSTR MSG_SET_ORIGIN = _UxGT("Set Origin"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Select Origin"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Last value "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" All"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Bed"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" End ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" All"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Bed"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Preheat $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Preheat $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Preheat $ End"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Preheat $ End ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Preheat $ All"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Preheat $ Bed"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Preheat $ Conf"); + LSTR MSG_PREHEAT_M = _UxGT("Preheat $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Preheat $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preheat $ End"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preheat $ End ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preheat $ All"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preheat $ Bed"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preheat $ Conf"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preheat Custom"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Cooldown"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Preheat Custom"); + LSTR MSG_COOLDOWN = _UxGT("Cooldown"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequency"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser Control"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindle Control"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laser Power"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Pwr"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); - 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"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retract"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Move Axis"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bed Leveling"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Level Bed"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bed Tramming"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Adjust bed until the probe triggers."); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Corners within tolerance. Bed trammed."); - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); - 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_PROBING_POINT = _UxGT("Probing Point"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Value"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Custom Commands"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Test"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Point"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); - 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_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); - 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("Doing G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Tools"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("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_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Measure"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Moving to next"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activate UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Deactivate UBL"); - 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"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Done Editing Mesh"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Build Custom Mesh"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Build Mesh"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Build Mesh ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Build Cold Mesh"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Adjust Mesh Height"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Height Amount"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validate Mesh"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Validate Mesh ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validate Custom Mesh"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Heating Bed"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("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 Canceled"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("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"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Grid Mesh Leveling"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Level Mesh"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Side Points"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Map Type"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Output Mesh Map"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Output for Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Output for CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Off Printer Backup"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Output UBL Info"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Fill-in Amount"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manual Fill-in"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Smart Fill-in"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Fill-in Mesh"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidate All"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidate Closest"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Fine Tune All"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Fine Tune Closest"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Storage"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("No Storage"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stopped"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Step-By-Step UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Build Cold Mesh"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Fill-in"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validate Mesh"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Fine Tune All"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validate Mesh"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Fine Tune All"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Save Bed Mesh"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frequency"); + LSTR MSG_LASER_MENU = _UxGT("Laser Control"); + LSTR MSG_SPINDLE_MENU = _UxGT("Spindle Control"); + LSTR MSG_LASER_POWER = _UxGT("Laser Power"); + LSTR MSG_SPINDLE_POWER = _UxGT("Spindle Pwr"); + LSTR MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindle Reverse"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Switch Power On"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Switch Power Off"); + LSTR MSG_EXTRUDE = _UxGT("Extrude"); + LSTR MSG_RETRACT = _UxGT("Retract"); + LSTR MSG_MOVE_AXIS = _UxGT("Move Axis"); + LSTR MSG_BED_LEVELING = _UxGT("Bed Leveling"); + LSTR MSG_LEVEL_BED = _UxGT("Level Bed"); + LSTR MSG_BED_TRAMMING = _UxGT("Bed Tramming"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Adjust bed until the probe triggers."); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Corners within tolerance. Bed trammed."); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Next Corner"); + LSTR MSG_MESH_EDITOR = _UxGT("Mesh Editor"); + LSTR MSG_EDIT_MESH = _UxGT("Edit Mesh"); + LSTR MSG_EDITING_STOPPED = _UxGT("Mesh Editing Stopped"); + LSTR MSG_PROBING_POINT = _UxGT("Probing Point"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z Value"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Custom Commands"); + LSTR MSG_M48_TEST = _UxGT("M48 Probe Test"); + LSTR MSG_M48_POINT = _UxGT("M48 Point"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); + LSTR MSG_M48_DEVIATION = _UxGT("Deviation"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX Mode"); + LSTR MSG_OFFSETS_MENU = _UxGT("Tool Offsets"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Doing G29"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL Tools"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Tilting Point"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manually Build Mesh"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Measure"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Moving to next"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Activate UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Deactivate UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Bed Temp"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hotend Temp"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Mesh Edit"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit Custom Mesh"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Fine Tuning Mesh"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Done Editing Mesh"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Build Custom Mesh"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Build Mesh"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Build Mesh ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Build Cold Mesh"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Adjust Mesh Height"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Height Amount"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validate Mesh"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validate Mesh ($)"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validate Custom Mesh"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Heating Bed"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Heating Nozzle"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manual priming..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fixed Length Prime"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Done Priming"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Canceled"); + LSTR MSG_G26_LEAVING = _UxGT("Leaving G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continue Bed Mesh"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Mesh Leveling"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Point Leveling"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Grid Mesh Leveling"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Level Mesh"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Side Points"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Map Type"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Output Mesh Map"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Output for Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Output for CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Off Printer Backup"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Output UBL Info"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Fill-in Amount"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manual Fill-in"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart Fill-in"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Fill-in Mesh"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidate All"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidate Closest"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Fine Tune All"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Fine Tune Closest"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Storage"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); + LSTR MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); + LSTR MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("No Storage"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stopped"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Step-By-Step UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Build Cold Mesh"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Fill-in"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validate Mesh"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Fine Tune All"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validate Mesh"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Fine Tune All"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Save Bed Mesh"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Control"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Lights"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Light Presets"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Red"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Yellow"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Green"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blue"); - 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_LED_CHANNEL_N = _UxGT("Channel ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Brightness"); - 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"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Blue Intensity"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("White Intensity"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brightness"); + LSTR MSG_LED_CONTROL = _UxGT("LED Control"); + LSTR MSG_LEDS = _UxGT("Lights"); + LSTR MSG_LED_PRESETS = _UxGT("Light Presets"); + LSTR MSG_SET_LEDS_RED = _UxGT("Red"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Yellow"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Green"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Blue"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("White"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Default"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Channel ="); + LSTR MSG_LEDS2 = _UxGT("Lights #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Brightness"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Custom Lights"); + LSTR MSG_INTENSITY_R = _UxGT("Red Intensity"); + LSTR MSG_INTENSITY_G = _UxGT("Green Intensity"); + LSTR MSG_INTENSITY_B = _UxGT("Blue Intensity"); + LSTR MSG_INTENSITY_W = _UxGT("White Intensity"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brightness"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Moving..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Free XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Move Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Move E*"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Move %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); - PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Move 1.0in"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); - PROGMEM Language_Str MSG_MAXSPEED = _UxGT("Max Speed (mm/s)"); - PROGMEM Language_Str MSG_MAXSPEED_X = _UxGT("Max ") LCD_STR_A _UxGT(" Speed"); - PROGMEM Language_Str MSG_MAXSPEED_Y = _UxGT("Max ") LCD_STR_B _UxGT(" Speed"); - PROGMEM Language_Str MSG_MAXSPEED_Z = _UxGT("Max ") LCD_STR_C _UxGT(" Speed"); - PROGMEM Language_Str MSG_MAXSPEED_E = _UxGT("Max ") LCD_STR_E _UxGT(" Speed"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); - PROGMEM Language_Str MSG_BED = _UxGT("Bed"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Enclosure"); - PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); - PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan Speed"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fan Speed ~"); - 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("Extra Fan Speed ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller Fan"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flow"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flow ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 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_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); - PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("PID Cycles"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - 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("Select"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Select *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Min Velocity"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Travel Vel"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleration"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Retract Accel"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Travel Accel"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("XY Freq Limit"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min FR Factor"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Motion"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Unload mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("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 Contrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Store Settings"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Load Settings"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initialize EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = MEDIA_TYPE_EN _UxGT(" Update"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset Printer"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_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_POWER_MONITOR = _UxGT("Power monitor"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Current"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Voltage"); - PROGMEM Language_Str MSG_POWER = _UxGT("Power"); - 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_IGNORE = _UxGT("Ignore"); - 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_BUTTON_SKIP = _UxGT("Skip"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Start Host Print"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop Print"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); - 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("Power Outage"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Print from ") MEDIA_TYPE_EN; - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No ") MEDIA_TYPE_EN; - 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_PRINT_DONE = _UxGT("Print Done"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("No Move."); - PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPED. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retract mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Swap Length"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); - 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 Raise"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Retract Speed"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Change Filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Load Filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Load *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Unload Filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Unload *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Unload All"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Attach ") MEDIA_TYPE_EN; - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Change ") MEDIA_TYPE_EN; - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Release ") MEDIA_TYPE_EN; - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Probe Past Bed"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Skew Factor"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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("Home %s%s%s First"); - PROGMEM Language_Str MSG_ZPROBE_SETTINGS = _UxGT("Probe Settings"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Probe Z Offset"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Move Nozzle to Bed"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; - 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("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_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); - PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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_PROBE_HEATING = _UxGT("Probe Heating..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Chamber Heating..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chamber Cooling..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Calibration"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrate X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrate Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrate Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); - 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("Probe Z-offset"); - 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"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("About Printer"); - 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_UBL_LEVELING = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mesh Leveling"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); - 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_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_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_MOVING = _UxGT("Moving..."); + LSTR MSG_FREE_XY = _UxGT("Free XY"); + LSTR MSG_MOVE_X = _UxGT("Move X"); + LSTR MSG_MOVE_Y = _UxGT("Move Y"); + LSTR MSG_MOVE_Z = _UxGT("Move Z"); + LSTR MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Move Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Move E*"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); + LSTR MSG_MOVE_N_MM = _UxGT("Move %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Move 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Move 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Move 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Move 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Move 0.001in"); + LSTR MSG_MOVE_001IN = _UxGT("Move 0.01in"); + LSTR MSG_MOVE_01IN = _UxGT("Move 0.1in"); + LSTR MSG_MOVE_1IN = _UxGT("Move 1.0in"); + LSTR MSG_SPEED = _UxGT("Speed"); + LSTR MSG_MAXSPEED = _UxGT("Max Speed (mm/s)"); + LSTR MSG_MAXSPEED_X = _UxGT("Max ") LCD_STR_A _UxGT(" Speed"); + LSTR MSG_MAXSPEED_Y = _UxGT("Max ") LCD_STR_B _UxGT(" Speed"); + LSTR MSG_MAXSPEED_Z = _UxGT("Max ") LCD_STR_C _UxGT(" Speed"); + LSTR MSG_MAXSPEED_E = _UxGT("Max ") LCD_STR_E _UxGT(" Speed"); + LSTR MSG_BED_Z = _UxGT("Bed Z"); + LSTR MSG_NOZZLE = _UxGT("Nozzle"); + LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); + LSTR MSG_BED = _UxGT("Bed"); + LSTR MSG_CHAMBER = _UxGT("Enclosure"); + LSTR MSG_COOLER = _UxGT("Laser Coolant"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + LSTR MSG_LASER = _UxGT("Laser"); + LSTR MSG_FAN_SPEED = _UxGT("Fan Speed"); + LSTR MSG_FAN_SPEED_N = _UxGT("Fan Speed ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fan Speed"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fan Speed ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Controller Fan"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); + LSTR MSG_FLOW = _UxGT("Flow"); + LSTR MSG_FLOW_N = _UxGT("Flow ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("On"); + LSTR MSG_LCD_OFF = _UxGT("Off"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_CYCLE = _UxGT("PID Cycles"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + LSTR MSG_PID_P = _UxGT("PID-P"); + LSTR MSG_PID_P_E = _UxGT("PID-P *"); + LSTR MSG_PID_I = _UxGT("PID-I"); + LSTR MSG_PID_I_E = _UxGT("PID-I *"); + LSTR MSG_PID_D = _UxGT("PID-D"); + LSTR MSG_PID_D_E = _UxGT("PID-D *"); + LSTR MSG_PID_C = _UxGT("PID-C"); + LSTR MSG_PID_C_E = _UxGT("PID-C *"); + LSTR MSG_PID_F = _UxGT("PID-F"); + LSTR MSG_PID_F_E = _UxGT("PID-F *"); + LSTR MSG_SELECT = _UxGT("Select"); + LSTR MSG_SELECT_E = _UxGT("Select *"); + LSTR MSG_ACC = _UxGT("Accel"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + LSTR MSG_VELOCITY = _UxGT("Velocity"); + LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_VMIN = _UxGT("Min Velocity"); + LSTR MSG_VTRAV_MIN = _UxGT("Min Travel Vel"); + LSTR MSG_ACCELERATION = _UxGT("Acceleration"); + LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); + LSTR MSG_A_RETRACT = _UxGT("Retract Accel"); + LSTR MSG_A_TRAVEL = _UxGT("Travel Accel"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("XY Freq Limit"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min FR Factor"); + LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); + LSTR MSG_E_STEPS = _UxGT("E steps/mm"); + LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperature"); + LSTR MSG_MOTION = _UxGT("Motion"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Unload mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Load mm"); + LSTR MSG_ADVANCE_K = _UxGT("Advance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); + LSTR MSG_CONTRAST = _UxGT("LCD Contrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Store Settings"); + LSTR MSG_LOAD_EEPROM = _UxGT("Load Settings"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); + LSTR MSG_INIT_EEPROM = _UxGT("Initialize EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + LSTR MSG_SETTINGS_STORED = _UxGT("Settings Stored"); + LSTR MSG_MEDIA_UPDATE = MEDIA_TYPE_EN _UxGT(" Update"); + LSTR MSG_RESET_PRINTER = _UxGT("Reset Printer"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Refresh"); + LSTR MSG_INFO_SCREEN = _UxGT("Info Screen"); + LSTR MSG_PREPARE = _UxGT("Prepare"); + LSTR MSG_TUNE = _UxGT("Tune"); + LSTR MSG_POWER_MONITOR = _UxGT("Power monitor"); + LSTR MSG_CURRENT = _UxGT("Current"); + LSTR MSG_VOLTAGE = _UxGT("Voltage"); + LSTR MSG_POWER = _UxGT("Power"); + LSTR MSG_START_PRINT = _UxGT("Start Print"); + LSTR MSG_BUTTON_NEXT = _UxGT("Next"); + LSTR MSG_BUTTON_INIT = _UxGT("Init"); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Print"); + LSTR MSG_BUTTON_RESET = _UxGT("Reset"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignore"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Cancel"); + LSTR MSG_BUTTON_DONE = _UxGT("Done"); + LSTR MSG_BUTTON_BACK = _UxGT("Back"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Proceed"); + LSTR MSG_BUTTON_SKIP = _UxGT("Skip"); + LSTR MSG_PAUSING = _UxGT("Pausing..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); + LSTR MSG_RESUME_PRINT = _UxGT("Resume Print"); + LSTR MSG_HOST_START_PRINT = _UxGT("Start Host Print"); + LSTR MSG_STOP_PRINT = _UxGT("Stop Print"); + LSTR MSG_END_LOOPS = _UxGT("End Repeat Loops"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Printing Object"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Power Outage"); + LSTR MSG_MEDIA_MENU = _UxGT("Print from ") MEDIA_TYPE_EN; + LSTR MSG_NO_MEDIA = _UxGT("No ") MEDIA_TYPE_EN; + LSTR MSG_DWELL = _UxGT("Sleep..."); + LSTR MSG_USERWAIT = _UxGT("Click to Resume..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Print Paused"); + LSTR MSG_PRINTING = _UxGT("Printing..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Print Aborted"); + LSTR MSG_PRINT_DONE = _UxGT("Print Done"); + LSTR MSG_NO_MOVE = _UxGT("No Move."); + LSTR MSG_KILLED = _UxGT("KILLED. "); + LSTR MSG_STOPPED = _UxGT("STOPPED. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retract mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retract V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Swap Length"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purge Length"); + LSTR MSG_TOOL_CHANGE = _UxGT("Tool Change"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime Speed"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Retract Speed"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Change Filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Load Filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Load *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Unload Filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Unload *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Unload All"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Attach ") MEDIA_TYPE_EN; + LSTR MSG_CHANGE_MEDIA = _UxGT("Change ") MEDIA_TYPE_EN; + LSTR MSG_RELEASE_MEDIA = _UxGT("Release ") MEDIA_TYPE_EN; + LSTR MSG_ZPROBE_OUT = _UxGT("Z Probe Past Bed"); + LSTR MSG_SKEW_FACTOR = _UxGT("Skew Factor"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("DANGER: Bad settings can cause damage! Proceed anyway?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Save"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + LSTR MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s First"); + LSTR MSG_ZPROBE_SETTINGS = _UxGT("Probe Settings"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Probe Z Offset"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Move Nozzle to Bed"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: REDUNDANT TEMP"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + LSTR MSG_COOLING_FAILED = _UxGT("Cooling Failed"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); + LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); + LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Heating..."); + LSTR MSG_COOLING = _UxGT("Cooling..."); + LSTR MSG_BED_HEATING = _UxGT("Bed Heating..."); + LSTR MSG_BED_COOLING = _UxGT("Bed Cooling..."); + LSTR MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + LSTR MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Chamber Heating..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Chamber Cooling..."); + LSTR MSG_LASER_COOLING = _UxGT("Laser Cooling..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Calibration"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrate X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrate Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrate Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Settings"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibration"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Set Delta Height"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Probe Z-offset"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Height"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); + LSTR MSG_INFO_MENU = _UxGT("About Printer"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Printer Info"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-Point Leveling"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Linear Leveling"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilinear Leveling"); + LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_MESH_LEVELING = _UxGT("Mesh Leveling"); + LSTR MSG_MESH_DONE = _UxGT("Mesh probing done"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Printer Stats"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Board Info"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extruders"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocol"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: ON"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case Light"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); + LSTR MSG_CASE_LIGHT = _UxGT("Case Light"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total Print Time"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded Total"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total Print Time"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded Total"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Prints"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Longest"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Prints"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("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"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("RESUME OPTIONS:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purge more"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continue"); - 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("Runout Dist mm"); - PROGMEM Language_Str MSG_RUNOUT_ENABLE = _UxGT("Enable Runout"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT CHANGE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("PRINT PAUSED"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LOAD FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("UNLOAD FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("RESUME OPTIONS:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purge more"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continue"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout Sensor"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); + LSTR MSG_RUNOUT_ENABLE = _UxGT("Enable Runout"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Resume"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Resuming..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Load"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Load All"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Load to Nozzle"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Eject"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Eject ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Unload"); - 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("MMU Resetting..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); + LSTR MSG_MMU2_RESUME = _UxGT("MMU Resume"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU Resuming..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Load"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Load All"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Load to Nozzle"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Eject"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Eject ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Unload"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Loading Fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejecting Fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Unloading Fil...."); + LSTR MSG_MMU2_ALL = _UxGT("All"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Reset MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU Resetting..."); + LSTR 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:"); + LSTR MSG_MIX = _UxGT("Mix"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Component ="); + LSTR MSG_MIXER = _UxGT("Mixer"); + LSTR MSG_GRADIENT = _UxGT("Gradient"); + LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Toggle Mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Reverse Gradient"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + LSTR MSG_START_VTOOL = _UxGT("Start V-tool"); + LSTR MSG_END_VTOOL = _UxGT(" End V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + LSTR MSG_START_Z = _UxGT("Start Z:"); + LSTR 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"); + LSTR MSG_GAMES = _UxGT("Games"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + LSTR MSG_BAD_PAGE = _UxGT("Bad page index"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Edit Password"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login Required"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Password Settings"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Enter Digit"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Set/Edit Password"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Remove Password"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Password is "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Start Over"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Remember to Save!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Password Removed"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Edit Password"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Login Required"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Password Settings"); + LSTR MSG_ENTER_DIGIT = _UxGT("Enter Digit"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Set/Edit Password"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Remove Password"); + LSTR MSG_PASSWORD_SET = _UxGT("Password is "); + LSTR MSG_START_OVER = _UxGT("Start Over"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Remember to Save!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Password Removed"); // // 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_PARKING = _UxGT(MSG_1_LINE("Parking...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Wait for", "filament change", "to start")); - 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_HEATING = _UxGT(MSG_2_LINE("Nozzle heating", "Please wait...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wait for", "filament unload")); - 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("Click to finish", "filament purge")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wait for print", "to resume...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Press Button", "to resume print")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Wait for", "filament change", "to start")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insert filament", "and press button", "to continue")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Press button", "to heat nozzle")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozzle heating", "Please wait...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wait for", "filament unload")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Wait for", "filament load")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Wait for", "filament purge")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Click to finish", "filament purge")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wait for print", "to resume...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Click to continue")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Please wait...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insert and Click")); - 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_CONT_PURGE = _UxGT(MSG_1_LINE("Click to finish")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Resuming...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Click to continue")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Please wait...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insert and Click")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Click to heat")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Heating...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Ejecting...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Loading...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purging...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Click to finish")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Resuming...")); #endif - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); + LSTR MSG_TMC_CURRENT = _UxGT("Driver Current"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorless Homing"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + LSTR MSG_SERVICE_RESET = _UxGT("Reset"); + LSTR MSG_SERVICE_IN = _UxGT(" in:"); + LSTR MSG_BACKLASH = _UxGT("Backlash"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correction"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); - PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Reheat Done"); + LSTR MSG_REHEAT = _UxGT("Reheat"); + LSTR MSG_REHEATING = _UxGT("Reheating..."); + LSTR MSG_REHEATDONE = _UxGT("Reheat Done"); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + LSTR MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Sound"); + LSTR MSG_SOUND = _UxGT("Sound"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibration Completed"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibration Failed"); + LSTR MSG_TOP_LEFT = _UxGT("Top Left"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + LSTR MSG_TOP_RIGHT = _UxGT("Top Right"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibration Completed"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibration Failed"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Card"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Disk"); + LSTR MSG_SD_CARD = _UxGT("SD Card"); + LSTR MSG_USB_DISK = _UxGT("USB Disk"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 1213d9e1fe..65930e6564 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -31,575 +31,575 @@ namespace Language_es { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Spanish"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Spanish"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Lista"); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("SI"); - PROGMEM Language_Str MSG_NO = _UxGT("NO"); - PROGMEM Language_Str MSG_BACK = _UxGT("Atrás"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD/USB insertado"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD/USB retirado"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Esperando al SD/USB"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Fallo al iniciar SD"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/USB"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); - 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("Menú principal"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Ajustes avanzados"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Inicio automático"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Prob. barra progreso"); - PROGMEM Language_Str MSG_HOMING = _UxGT("Origen"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Llevar al origen"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origen X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origen Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origen Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto alineado Z"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteración: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("¡Precisión disminuyendo!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Precisión conseguida"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Pulsar para comenzar"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Siguiente punto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("¡Nivelación lista!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compen. Altura"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ajustar desfases"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Establecer origen"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Lista"); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("SI"); + LSTR MSG_NO = _UxGT("NO"); + LSTR MSG_BACK = _UxGT("Atrás"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD/USB insertado"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD/USB retirado"); + LSTR MSG_MEDIA_WAITING = _UxGT("Esperando al SD/USB"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Fallo al iniciar SD"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/USB"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); + LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Ajustes avanzados"); + LSTR MSG_CONFIGURATION = _UxGT("Configuración"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Inicio automático"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); + LSTR MSG_DEBUG_MENU = _UxGT("Menú depuración"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Prob. barra progreso"); + LSTR MSG_HOMING = _UxGT("Origen"); + LSTR MSG_AUTO_HOME = _UxGT("Llevar al origen"); + LSTR MSG_AUTO_HOME_X = _UxGT("Origen X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Origen Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Origen Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto alineado Z"); + LSTR MSG_ITERATION = _UxGT("G34 Iteración: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("¡Precisión disminuyendo!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Precisión conseguida"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Pulsar para comenzar"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Siguiente punto"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("¡Nivelación lista!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Compen. Altura"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ajustar desfases"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); + LSTR MSG_SET_ORIGIN = _UxGT("Establecer origen"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Precal. ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Precal. ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Todo"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Cama"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Ajuste"); + LSTR MSG_PREHEAT_1 = _UxGT("Precal. ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Precal. ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Fusor ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Todo"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Cama"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Precal. ") PREHEAT_1_LABEL _UxGT(" Ajuste"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Precal. $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Precal. $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Precal. $ Fusor"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Precal. $ Fusor ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Precal. $ Todo"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Precal. $ Cama"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Precal. $ Ajuste"); + LSTR MSG_PREHEAT_M = _UxGT("Precal. $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Precal. $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Precal. $ Fusor"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Precal. $ Fusor ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Precal. $ Todo"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Precal. $ Cama"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Precal. $ Ajuste"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Precal. manual"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Enfriar"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Mandrino"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Mandrino"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Invertir giro"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Encender Fuente"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Apagar Fuente"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruir"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retraer"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover ejes"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Recorrido Cama"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado parada"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sondear Punto"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Com. Personalizados"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Desfase Herramienta"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Aparcado"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicar"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Reflejada"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ª Fusor X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ª Fusor Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ª Fusor Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Hacer G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Herramientas UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Nivelado UBL"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Crear Mallado man."); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Colocar cuña y Medir"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Medir"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Retirar y Medir Cama"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover al Siguente"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Cama"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Cama perso."); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Fusor"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Fusor perso."); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Mallado"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Mallado perso."); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste fino Mallado"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Term. edici. Mallado"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Mallado Pers."); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Mallado"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Precal. manual"); + LSTR MSG_COOLDOWN = _UxGT("Enfriar"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); + LSTR MSG_LASER_MENU = _UxGT("Control Láser"); + LSTR MSG_LASER_POWER = _UxGT("Potencia Láser"); + LSTR MSG_SPINDLE_MENU = _UxGT("Control Mandrino"); + LSTR MSG_SPINDLE_POWER = _UxGT("Potencia Mandrino"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Invertir giro"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Encender Fuente"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Apagar Fuente"); + LSTR MSG_EXTRUDE = _UxGT("Extruir"); + LSTR MSG_RETRACT = _UxGT("Retraer"); + LSTR MSG_MOVE_AXIS = _UxGT("Mover ejes"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelando Cama"); + LSTR MSG_LEVEL_BED = _UxGT("Nivelar Cama"); + LSTR MSG_BED_TRAMMING = _UxGT("Recorrido Cama"); + LSTR MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor Mallado"); + LSTR MSG_EDIT_MESH = _UxGT("Editar Mallado"); + LSTR MSG_EDITING_STOPPED = _UxGT("Ed. Mallado parada"); + LSTR MSG_PROBING_POINT = _UxGT("Sondear Punto"); + LSTR MSG_MESH_X = _UxGT("Índice X"); + LSTR MSG_MESH_Y = _UxGT("Índice Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valor Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Com. Personalizados"); + LSTR MSG_M48_TEST = _UxGT("M48 Probar Sonda"); + LSTR MSG_M48_POINT = _UxGT("M48 Punto"); + LSTR MSG_M48_DEVIATION = _UxGT("Desviación"); + LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Desfase Herramienta"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Aparcado"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicar"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Reflejada"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2ª Fusor X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2ª Fusor Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2ª Fusor Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Hacer G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Herramientas UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Nivelado UBL"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Crear Mallado man."); + LSTR MSG_UBL_BC_INSERT = _UxGT("Colocar cuña y Medir"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Medir"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Retirar y Medir Cama"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover al Siguente"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Cama"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Cama perso."); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Fusor"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Fusor perso."); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Editar Mallado"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Mallado perso."); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste fino Mallado"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Term. edici. Mallado"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Mallado Pers."); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Mallado"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Crear Mallado ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Valid. Mall. ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Crear Mallado ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Valid. Mall. ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Mallado Frío"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajustar alt. Mallado"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Cantidad de altura"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Valid. Mallado"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valid. Mall. perso."); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Calentando Cama"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Calent. Boquilla"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Imprimado manual..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Impri. longit. fija"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Imprimación Lista"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Cancelado"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Dejando G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Contin. Mallado cama"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelando Mallado"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelando 3Puntos"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Niv. Mall. cuadri"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivel de Mallado"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterales"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de mapa "); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Salida Mapa mallado"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Salida para el host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Salida para CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Cópia de seg. ext"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Salida Info. UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidad de relleno"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Relleno manual"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Relleno inteligente"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Mallado de relleno"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar proximos"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Ajustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ajustar Fino proxi."); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacen de Mallado"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Huecos memoria"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Mall. cama"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Guardar Mall. cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malla %i Guardada"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Error: Guardar UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Error: Restaurar UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Parado"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crear Mall. Frío"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Relleno intelig."); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Valid. Mallado"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Valid. Mallado"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Guardar Mall. cama"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Mallado Frío"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajustar alt. Mallado"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Cantidad de altura"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Valid. Mallado"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valid. Mall. perso."); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Calentando Cama"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Calent. Boquilla"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Imprimado manual..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Impri. longit. fija"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Imprimación Lista"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Cancelado"); + LSTR MSG_G26_LEAVING = _UxGT("Dejando G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Contin. Mallado cama"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Nivelando Mallado"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelando 3Puntos"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Niv. Mall. cuadri"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Nivel de Mallado"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterales"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Tipo de mapa "); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Salida Mapa mallado"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Salida para el host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Salida para CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Cópia de seg. ext"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Salida Info. UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidad de relleno"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Relleno manual"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Relleno inteligente"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Mallado de relleno"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar proximos"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Ajustar Fino Todo"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ajustar Fino proxi."); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacen de Mallado"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Huecos memoria"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Cargar Mall. cama"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Guardar Mall. cama"); + LSTR MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); + LSTR MSG_MESH_SAVED = _UxGT("Malla %i Guardada"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Sin guardar"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Error: Guardar UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Error: Restaurar UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Parado"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crear Mall. Frío"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Relleno intelig."); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Valid. Mallado"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajustar Fino Todo"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Valid. Mallado"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajustar Fino Todo"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Guardar Mall. cama"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("LEDS"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Color predefinido"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rojo"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Naranja"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Amarillo"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Verde"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Azul"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Blanco"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Color personalizado"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidad Rojo"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidad Verde"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidad Azul"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensidad Blanco"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brillo"); + LSTR MSG_LED_CONTROL = _UxGT("Control LED"); + LSTR MSG_LEDS = _UxGT("LEDS"); + LSTR MSG_LED_PRESETS = _UxGT("Color predefinido"); + LSTR MSG_SET_LEDS_RED = _UxGT("Rojo"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Naranja"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Amarillo"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Verde"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Azul"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Blanco"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Color personalizado"); + LSTR MSG_INTENSITY_R = _UxGT("Intensidad Rojo"); + LSTR MSG_INTENSITY_G = _UxGT("Intensidad Verde"); + LSTR MSG_INTENSITY_B = _UxGT("Intensidad Azul"); + LSTR MSG_INTENSITY_W = _UxGT("Intensidad Blanco"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brillo"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Moviendo..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Libre XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend muy frio"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidad"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Boquilla ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Boquilla Aparcada"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Boquilla en Espera"); - PROGMEM Language_Str MSG_BED = _UxGT("Cama"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Recinto"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Ventilador"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Ventilador ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Vent. almacenado ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Ext. ventil."); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Ext. ventil. ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidad en reposo"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidad Activa"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Periodo de reposo"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flujo"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flujo ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Factor"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temp. Autom."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Enc"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apg"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Seleccionar"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleccionar *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Aceleración"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidad"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleración"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Acel. max") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Acel. max") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Acel. max") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Acel. max") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Acel. max *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acel. retrac."); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acel. Viaje"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pasos/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pasos/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movimiento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diámetro Fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diámetro Fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carga mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avance K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Guardar EEPROM"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar EEPROM"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. fábrica"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Índice EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versión EEPROM"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetear Impresora"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Pantalla de Inf."); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Ajustar"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Iniciar impresión"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Siguinte"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Iniciar"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Parar"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimir"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Retroceder"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Reanudar impresión"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Detener impresión"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimiendo Objeto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Rec. Fallo electrico"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/USB"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD/USB no presente"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Reposo..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Pulsar para Reanudar"); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimiendo..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión cancelada"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Impresión Completada"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sin movimiento"); - PROGMEM Language_Str MSG_KILLED = _UxGT("MUERTA"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("DETENIDA"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Interc. Retraer mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Levantar mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Interc. DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Retracción Auto."); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Inter. longitud"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purgar longitud"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Herramienta"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Aumentar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vel. de Cebado"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de retracción"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamento *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar filamento"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Cargar filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Descargar filamento"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Descargar fil. *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar todo"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z fuera cama"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Factor de desviación"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Auto-Prueba"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Subir pistón"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Bajar pistón"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Modo Software"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Modo 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Modo OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Modo almacenar"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Poner BLTouch a 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Poner BLTouch a OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Informe de drenaje"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PELIGRO: ¡Una mala configuración puede producir daños! ¿Proceder igualmente?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test de desfase Z"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Guardar"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Subir TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Subir Sonda Z"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Bajar Sonda Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Origen %s%s%s Prim."); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desf. Sonda"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desf. Sonda X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desf. Sonda Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desf. Sonda Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Calent. fallido"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP. REDUN."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CAMARA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err:TEMP. MÁX"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err:TEMP. MIN"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA DETENIDA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Por favor, reinicie"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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("Calentando..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Enfriando..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Calentando Cama..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Enfriando Cama..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Calentando Cámara..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Enfriando Cámara..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibración Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Est. Altura Delta"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ajustar Sonda Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Info. Impresora"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info. Impresora"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelando 3puntos"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelando Lineal"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelando Bilineal"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelando UBL"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelando en Mallado"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estadísticas Imp."); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. Controlador"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Vig. Fuga Térm.: OFF"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Vig. Fuga Térm.: ON"); + LSTR MSG_MOVING = _UxGT("Moviendo..."); + LSTR MSG_FREE_XY = _UxGT("Libre XY"); + LSTR MSG_MOVE_X = _UxGT("Mover X"); + LSTR MSG_MOVE_Y = _UxGT("Mover Y"); + LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_E = _UxGT("Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend muy frio"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mover 100mm"); + LSTR MSG_SPEED = _UxGT("Velocidad"); + LSTR MSG_BED_Z = _UxGT("Cama Z"); + LSTR MSG_NOZZLE = _UxGT("Boquilla"); + LSTR MSG_NOZZLE_N = _UxGT("Boquilla ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Boquilla Aparcada"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Boquilla en Espera"); + LSTR MSG_BED = _UxGT("Cama"); + LSTR MSG_CHAMBER = _UxGT("Recinto"); + LSTR MSG_FAN_SPEED = _UxGT("Ventilador"); + LSTR MSG_FAN_SPEED_N = _UxGT("Ventilador ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Vent. almacenado ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Ext. ventil."); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Ext. ventil. ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidad en reposo"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidad Activa"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Periodo de reposo"); + LSTR MSG_FLOW = _UxGT("Flujo"); + LSTR MSG_FLOW_N = _UxGT("Flujo ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Factor"); + LSTR MSG_AUTOTEMP = _UxGT("Temp. Autom."); + LSTR MSG_LCD_ON = _UxGT("Enc"); + LSTR MSG_LCD_OFF = _UxGT("Apg"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); + LSTR MSG_SELECT = _UxGT("Seleccionar"); + LSTR MSG_SELECT_E = _UxGT("Seleccionar *"); + LSTR MSG_ACC = _UxGT("Aceleración"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); + LSTR MSG_VELOCITY = _UxGT("Velocidad"); + LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); + LSTR MSG_ACCELERATION = _UxGT("Acceleración"); + LSTR MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Acel. max") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Acel. max") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Acel. max") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Acel. max") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); + LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); + LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); + LSTR MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); + LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); + LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movimiento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Diámetro Fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diámetro Fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Carga mm"); + LSTR MSG_ADVANCE_K = _UxGT("Avance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); + LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Guardar EEPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Cargar EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Rest. fábrica"); + LSTR MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Err: Índice EEPROM"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versión EEPROM"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + LSTR MSG_RESET_PRINTER = _UxGT("Resetear Impresora"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); + LSTR MSG_INFO_SCREEN = _UxGT("Pantalla de Inf."); + LSTR MSG_PREPARE = _UxGT("Preparar"); + LSTR MSG_TUNE = _UxGT("Ajustar"); + LSTR MSG_START_PRINT = _UxGT("Iniciar impresión"); + LSTR MSG_BUTTON_NEXT = _UxGT("Siguinte"); + LSTR MSG_BUTTON_INIT = _UxGT("Iniciar"); + LSTR MSG_BUTTON_STOP = _UxGT("Parar"); + LSTR MSG_BUTTON_PRINT = _UxGT("Imprimir"); + LSTR MSG_BUTTON_RESET = _UxGT("Reiniciar"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Cancelar"); + LSTR MSG_BUTTON_DONE = _UxGT("Listo"); + LSTR MSG_BUTTON_BACK = _UxGT("Retroceder"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Proceder"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); + LSTR MSG_RESUME_PRINT = _UxGT("Reanudar impresión"); + LSTR MSG_STOP_PRINT = _UxGT("Detener impresión"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimiendo Objeto"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Rec. Fallo electrico"); + LSTR MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/USB"); + LSTR MSG_NO_MEDIA = _UxGT("SD/USB no presente"); + LSTR MSG_DWELL = _UxGT("Reposo..."); + LSTR MSG_USERWAIT = _UxGT("Pulsar para Reanudar"); + LSTR MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); + LSTR MSG_PRINTING = _UxGT("Imprimiendo..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Impresión cancelada"); + LSTR MSG_PRINT_DONE = _UxGT("Impresión Completada"); + LSTR MSG_NO_MOVE = _UxGT("Sin movimiento"); + LSTR MSG_KILLED = _UxGT("MUERTA"); + LSTR MSG_STOPPED = _UxGT("DETENIDA"); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Interc. Retraer mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Levantar mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Interc. DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("DesRet V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Retracción Auto."); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Inter. longitud"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purgar longitud"); + LSTR MSG_TOOL_CHANGE = _UxGT("Cambiar Herramienta"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Aumentar Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vel. de Cebado"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de retracción"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Cambiar filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamento *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Cargar filamento"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Cargar filamento *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Descargar filamento"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Descargar fil. *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar todo"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z fuera cama"); + LSTR MSG_SKEW_FACTOR = _UxGT("Factor de desviación"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Auto-Prueba"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reiniciar"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Subir pistón"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Bajar pistón"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Modo Software"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Modo 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Modo OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Modo almacenar"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Poner BLTouch a 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Poner BLTouch a OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Informe de drenaje"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("PELIGRO: ¡Una mala configuración puede producir daños! ¿Proceder igualmente?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test de desfase Z"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Guardar"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Subir TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Subir Sonda Z"); + LSTR MSG_MANUAL_STOW = _UxGT("Bajar Sonda Z"); + LSTR MSG_HOME_FIRST = _UxGT("Origen %s%s%s Prim."); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Desf. Sonda"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Desf. Sonda X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Desf. Sonda Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Desf. Sonda Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Calent. fallido"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP. REDUN."); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CAMARA"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err:TEMP. MÁX"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err:TEMP. MIN"); + LSTR MSG_HALTED = _UxGT("IMPRESORA DETENIDA"); + LSTR MSG_PLEASE_RESET = _UxGT("Por favor, reinicie"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Calentando..."); + LSTR MSG_COOLING = _UxGT("Enfriando..."); + LSTR MSG_BED_HEATING = _UxGT("Calentando Cama..."); + LSTR MSG_BED_COOLING = _UxGT("Enfriando Cama..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Calentando Cámara..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Enfriando Cámara..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibración Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Est. Altura Delta"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ajustar Sonda Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radio"); + LSTR MSG_INFO_MENU = _UxGT("Info. Impresora"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info. Impresora"); + LSTR MSG_3POINT_LEVELING = _UxGT("Nivelando 3puntos"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Nivelando Lineal"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Nivelando Bilineal"); + LSTR MSG_UBL_LEVELING = _UxGT("Nivelando UBL"); + LSTR MSG_MESH_LEVELING = _UxGT("Nivelando en Mallado"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Estadísticas Imp."); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info. Controlador"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baudios"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocolo"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Vig. Fuga Térm.: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Vig. Fuga Térm.: ON"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz cabina"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); + LSTR MSG_CASE_LIGHT = _UxGT("Luz cabina"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Cont. de impresión"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tiempo total de imp."); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impresión más larga"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruido"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Cont. de impresión"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tiempo total de imp."); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Impresión más larga"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruido"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impresiones"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Más larga"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impresiones"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Más larga"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp. Mínima"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("F. Aliment."); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERROR CONEX. TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPC. REINICIO:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar más"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar imp."); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Boquilla: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sens. filamento"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Ir a origen Fallado"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp. Mínima"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); + LSTR MSG_INFO_PSU = _UxGT("F. Aliment."); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_ERROR_TMC = _UxGT("ERROR CONEX. TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPC. REINICIO:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar más"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar imp."); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Boquilla: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens. filamento"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Ir a origen Fallado"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ELIJE FILAMENTO"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("¡Actu. MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Necesita Cuidado"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuar imp."); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resumiendo..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar hasta boqui."); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Todo"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Retirar, y pulsar"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ELIJE FILAMENTO"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("¡Actu. MMU Firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Necesita Cuidado"); + LSTR MSG_MMU2_RESUME = _UxGT("Continuar imp."); + LSTR MSG_MMU2_RESUMING = _UxGT("Resumiendo..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar hasta boqui."); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil...."); + LSTR MSG_MMU2_ALL = _UxGT("Todo"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + LSTR MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Retirar, y pulsar"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mezcla"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Componente ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Miezclador"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Degradado"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Degradado Total"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Mezcla Conmutada"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Mezcla Cíclica"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Mezcla de Degradado"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Degradado inverso"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Activar Herr.V"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Inicio Herr.V"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Fin Herr.V"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias Herr.V"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reiniciar Herr.V"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Cometer mezc. Herr.V"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("Herr.V reiniciados"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Inicio Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); + LSTR MSG_MIX = _UxGT("Mezcla"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente ="); + LSTR MSG_MIXER = _UxGT("Miezclador"); + LSTR MSG_GRADIENT = _UxGT("Degradado"); + LSTR MSG_FULL_GRADIENT = _UxGT("Degradado Total"); + LSTR MSG_TOGGLE_MIX = _UxGT("Mezcla Conmutada"); + LSTR MSG_CYCLE_MIX = _UxGT("Mezcla Cíclica"); + LSTR MSG_GRADIENT_MIX = _UxGT("Mezcla de Degradado"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Degradado inverso"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Activar Herr.V"); + LSTR MSG_START_VTOOL = _UxGT("Inicio Herr.V"); + LSTR MSG_END_VTOOL = _UxGT(" Fin Herr.V"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias Herr.V"); + LSTR MSG_RESET_VTOOLS = _UxGT("Reiniciar Herr.V"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Cometer mezc. Herr.V"); + LSTR MSG_VTOOLS_RESET = _UxGT("Herr.V reiniciados"); + LSTR MSG_START_Z = _UxGT("Inicio Z:"); + LSTR MSG_END_Z = _UxGT(" Fin Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Juegos"); - 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"); + LSTR MSG_GAMES = _UxGT("Juegos"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Pulsar el botón para", "reanudar impresión")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperando para", "iniciar el cambio", "de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserte el filamento", "y pulse el botón", "para continuar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pulse el botón para", "calentar la boquilla")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Calentando boquilla", "Espere por favor...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Espere para", "liberar el filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Espere para", "cargar el filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere para", "purgar el filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Pulse para finalizar", "la purga de filamen.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impresora", "para reanudar...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Pulsar el botón para", "reanudar impresión")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperando para", "iniciar el cambio", "de filamento")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserte el filamento", "y pulse el botón", "para continuar...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pulse el botón para", "calentar la boquilla")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Calentando boquilla", "Espere por favor...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Espere para", "liberar el filamento")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Espere para", "cargar el filamento")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere para", "purgar el filamento")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Pulse para finalizar", "la purga de filamen.")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impresora", "para reanudar...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Pulse para continuar")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Por Favor espere...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Inserte y Pulse")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Pulse para Calentar")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Calentando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Liberando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Pulse para finalizar")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reanudando...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Pulse para continuar")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Aparcando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Por Favor espere...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Inserte y Pulse")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Pulse para Calentar")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Calentando...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Liberando...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Pulse para finalizar")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reanudando...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Amperaje Controlador"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Límite Hibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Origen sin sensores"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dentro:"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); + LSTR MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Amperaje Controlador"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Límite Hibrido"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Origen sin sensores"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); + LSTR MSG_SERVICE_RESET = _UxGT("Reiniciar"); + LSTR MSG_SERVICE_IN = _UxGT(" dentro:"); + LSTR MSG_BACKLASH = _UxGT("Backlash"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivel Eje X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("T. de esp. Calent."); - PROGMEM Language_Str MSG_REHEAT = _UxGT("Recalentar"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Recalentando..."); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivel Eje X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("T. de esp. Calent."); + LSTR MSG_REHEAT = _UxGT("Recalentar"); + LSTR MSG_REHEATING = _UxGT("Recalentando..."); } diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 30cc4931d8..a7e5bb2c58 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -34,298 +34,298 @@ namespace Language_eu { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Basque-Euskera"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Basque-Euskera"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" prest."); - PROGMEM Language_Str MSG_BACK = _UxGT("Atzera"); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Txartela sartuta"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Txartela kenduta"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu nagusia"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto hasiera"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Itzali motoreak"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Arazketa Menua"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Prog. Barra Proba"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Hasierara joan"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X jatorrira"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y jatorrira"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z jatorrira"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ hasieraratzen"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klik egin hasteko"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Hurrengo Puntua"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Berdintzea eginda"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Etxe. offset eza."); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsetak ezarrita"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Hasiera ipini"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" prest."); + LSTR MSG_BACK = _UxGT("Atzera"); + LSTR MSG_MEDIA_INSERTED = _UxGT("Txartela sartuta"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Txartela kenduta"); + LSTR MSG_MAIN = _UxGT("Menu nagusia"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto hasiera"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Itzali motoreak"); + LSTR MSG_DEBUG_MENU = _UxGT("Arazketa Menua"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Prog. Barra Proba"); + LSTR MSG_AUTO_HOME = _UxGT("Hasierara joan"); + LSTR MSG_AUTO_HOME_X = _UxGT("X jatorrira"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Y jatorrira"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Z jatorrira"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("XYZ hasieraratzen"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klik egin hasteko"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Hurrengo Puntua"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Berdintzea eginda"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Etxe. offset eza."); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsetak ezarrita"); + LSTR MSG_SET_ORIGIN = _UxGT("Hasiera ipini"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Berotu ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Berotu ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Amaia"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Amaia ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Guztia"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Ohea"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Ezarp."); + LSTR MSG_PREHEAT_1 = _UxGT("Berotu ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Berotu ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Amaia"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Amaia ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Guztia"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Ohea"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Berotu ") PREHEAT_1_LABEL _UxGT(" Ezarp."); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Berotu $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Berotu $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Berotu $ Amaia"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Berotu $ Amaia ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Berotu $ Guztia"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Berotu $ Ohea"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Berotu $ Ezarp."); + LSTR MSG_PREHEAT_M = _UxGT("Berotu $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Berotu $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Berotu $ Amaia"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Berotu $ Amaia ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Berotu $ Guztia"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Berotu $ Ohea"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Berotu $ Ezarp."); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Hoztu"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Energia piztu"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Energia itzali"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Estruitu"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Atzera eragin"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ardatzak mugitu"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ohe berdinketa"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ohea berdindu"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Ertzak berdindu"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Hurrengo ertza"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Sarea editatu"); + LSTR MSG_COOLDOWN = _UxGT("Hoztu"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Energia piztu"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Energia itzali"); + LSTR MSG_EXTRUDE = _UxGT("Estruitu"); + LSTR MSG_RETRACT = _UxGT("Atzera eragin"); + LSTR MSG_MOVE_AXIS = _UxGT("Ardatzak mugitu"); + LSTR MSG_BED_LEVELING = _UxGT("Ohe berdinketa"); + LSTR MSG_LEVEL_BED = _UxGT("Ohea berdindu"); + LSTR MSG_BED_TRAMMING = _UxGT("Ertzak berdindu"); + LSTR MSG_NEXT_CORNER = _UxGT("Hurrengo ertza"); + LSTR MSG_EDIT_MESH = _UxGT("Sarea editatu"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 exekutatzen"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Tresnak"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Sarea eskuz sortu"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Neurtu"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktibatu"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL desaktibatu"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ohearen tenperatura"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Mutur beroaren tenp."); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Sarea editatu"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Sarea editatzea eginda"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Sarea sortu"); + LSTR MSG_UBL_DOING_G29 = _UxGT("G29 exekutatzen"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL Tresnak"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Sarea eskuz sortu"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Neurtu"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktibatu"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL desaktibatu"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Ohearen tenperatura"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Mutur beroaren tenp."); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Sarea editatu"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Sarea editatzea eginda"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Sarea sortu"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("$ sarea sortu"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("$ sarea balioetsi"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("$ sarea sortu"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("$ sarea balioetsi"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Sare hotza sortu"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Sarearen altuera doitu"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sarea balioetsi"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Ohe sarea balioetsi"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Sare berdinketa"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3 puntuko berdinketa"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Lauki-sare berdinketa"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Sarea berdindu"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Mapa mota"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED ezarpenak"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Argiak"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Argi aurrehautaketak"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Gorria"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Laranja"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Horia"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Berdea"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Urdina"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Bioleta"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Zuria"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Lehenetsia"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Argi pertsonalizatuak"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intentsitate gorria"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intentsitate berdea"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intentsitate urdina"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intentsitate zuria"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Distira"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Sare hotza sortu"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Sarearen altuera doitu"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sarea balioetsi"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Ohe sarea balioetsi"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Sare berdinketa"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3 puntuko berdinketa"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Lauki-sare berdinketa"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Sarea berdindu"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Mapa mota"); + LSTR MSG_LED_CONTROL = _UxGT("LED ezarpenak"); + LSTR MSG_LEDS = _UxGT("Argiak"); + LSTR MSG_LED_PRESETS = _UxGT("Argi aurrehautaketak"); + LSTR MSG_SET_LEDS_RED = _UxGT("Gorria"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Laranja"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Horia"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Berdea"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Urdina"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Bioleta"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Zuria"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Lehenetsia"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Argi pertsonalizatuak"); + LSTR MSG_INTENSITY_R = _UxGT("Intentsitate gorria"); + LSTR MSG_INTENSITY_G = _UxGT("Intentsitate berdea"); + LSTR MSG_INTENSITY_B = _UxGT("Intentsitate urdina"); + LSTR MSG_INTENSITY_W = _UxGT("Intentsitate zuria"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Distira"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Mugitzen..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Askatu XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mugitu X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mugitu Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mugitu Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusorea"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusorea *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mugitu %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mugitu 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Abiadura"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Ohea"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Pita"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Pita ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Ohea"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Haizagailu abiadura"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Haizagailu abiadura ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Haiz.gehig. abiadura"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Haiz.gehig. abiadura ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxua"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxua ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontrola"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto tenperatura"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Aukeratu"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Aukeratu *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Azelerazioa"); - PROGMEM Language_Str MSG_JERK = _UxGT("Astindua"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-astindua"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-astindua"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-astindua"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-astindua"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-astindua"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-astindua"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-astindua"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VBidaia min"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-bidaia"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pausoak/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pausoak/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pausoak/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pausoak/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Tenperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Mugimendua"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Harizpia"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E mm3-tan"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Hariz. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Hariz. Dia. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Deskargatu mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Kargatu mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K Aurrerapena"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K Aurrerapena *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontrastea"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gorde memoria"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Kargatu memoria"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Larri. berriz."); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM-a hasieratu"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Berriz kargatu"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Pantaila info"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Prestatu"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Doitu"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausatu inprimak."); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Jarraitu inprima."); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Gelditu inprima."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("SD-tik inprimatu"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Ez dago SD-rik"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Lo egin..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Aginduak zain..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Inprim. geldi."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Inprim. deusezta."); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Mugimendu gabe."); - PROGMEM Language_Str MSG_KILLED = _UxGT("AKABATUTA. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("GELDITUTA. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Atzera egin mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Atzera mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Atzera egin V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Igo mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Atzera egin mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap Atzera mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Atzera egin V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Atzera egin"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Aldatu harizpia"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Aldatu harizpia *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Harizpia kargatu"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Harizpia kargatu *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Harizpia deskargatu"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Harizpia deskargatu *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Erabat deskargatu"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Hasieratu SD-a"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Aldatu txartela"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z zunda kanpora"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Okertze faktorea"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch AutoProba"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("BLTouch berrabia."); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch jaitsi/luzatu"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("BLTouch igo/jaso"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Etxera %s%s%s lehenengo"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Konpentsatu"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Mikro-urratsa X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Mikro-urratsa Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Mikro-urratsa Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop deusezta."); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Err: Beroketa"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: Tenperatura"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TENP. KONTROL EZA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: Tenp Maximoa"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: Tenp Minimoa"); - PROGMEM Language_Str MSG_HALTED = _UxGT("INPRIMA. GELDIRIK"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Berrabia. Mesedez"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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("Berotzen..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Ohea Berotzen..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibraketa"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibratu X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibratu Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibratu Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibratu Zentrua"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta ezarpenak"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibraketa"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Alt. Ezar."); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra diagonala"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altuera"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Erradioa"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Inprimagailu Inf."); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Inprimagailu Inf."); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3 puntuko berdinketa"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Berdinketa lineala"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Berdinketa bilinearra"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Sare berdinketa"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Inprima. estatis."); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Txartelaren Info."); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistoreak"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Estrusoreak"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudioak"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoloa"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Kabina Argia"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Argiaren Distira"); + LSTR MSG_MOVING = _UxGT("Mugitzen..."); + LSTR MSG_FREE_XY = _UxGT("Askatu XY"); + LSTR MSG_MOVE_X = _UxGT("Mugitu X"); + LSTR MSG_MOVE_Y = _UxGT("Mugitu Y"); + LSTR MSG_MOVE_Z = _UxGT("Mugitu Z"); + LSTR MSG_MOVE_E = _UxGT("Estrusorea"); + LSTR MSG_MOVE_EN = _UxGT("Estrusorea *"); + LSTR MSG_MOVE_N_MM = _UxGT("Mugitu %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mugitu 100mm"); + LSTR MSG_SPEED = _UxGT("Abiadura"); + LSTR MSG_BED_Z = _UxGT("Z Ohea"); + LSTR MSG_NOZZLE = _UxGT("Pita"); + LSTR MSG_NOZZLE_N = _UxGT("Pita ~"); + LSTR MSG_BED = _UxGT("Ohea"); + LSTR MSG_FAN_SPEED = _UxGT("Haizagailu abiadura"); + LSTR MSG_FAN_SPEED_N = _UxGT("Haizagailu abiadura ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Haiz.gehig. abiadura"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Haiz.gehig. abiadura ~"); + LSTR MSG_FLOW = _UxGT("Fluxua"); + LSTR MSG_FLOW_N = _UxGT("Fluxua ~"); + LSTR MSG_CONTROL = _UxGT("Kontrola"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); + LSTR MSG_AUTOTEMP = _UxGT("Auto tenperatura"); + LSTR MSG_SELECT = _UxGT("Aukeratu"); + LSTR MSG_SELECT_E = _UxGT("Aukeratu *"); + LSTR MSG_ACC = _UxGT("Azelerazioa"); + LSTR MSG_JERK = _UxGT("Astindua"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-astindua"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-astindua"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-astindua"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-astindua"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-astindua"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-astindua"); + LSTR MSG_VE_JERK = _UxGT("Ve-astindua"); + LSTR MSG_VTRAV_MIN = _UxGT("VBidaia min"); + LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); + LSTR MSG_A_TRAVEL = _UxGT("A-bidaia"); + LSTR MSG_STEPS_PER_MM = _UxGT("Pausoak/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pausoak/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pausoak/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pausoak/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pausoak/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pausoak/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pausoak/mm"); + LSTR MSG_E_STEPS = _UxGT("E pausoak/mm"); + LSTR MSG_EN_STEPS = _UxGT("* pausoak/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Tenperatura"); + LSTR MSG_MOTION = _UxGT("Mugimendua"); + LSTR MSG_FILAMENT = _UxGT("Harizpia"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E mm3-tan"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Hariz. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Hariz. Dia. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Deskargatu mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Kargatu mm"); + LSTR MSG_ADVANCE_K = _UxGT("K Aurrerapena"); + LSTR MSG_ADVANCE_K_E = _UxGT("K Aurrerapena *"); + LSTR MSG_CONTRAST = _UxGT("LCD kontrastea"); + LSTR MSG_STORE_EEPROM = _UxGT("Gorde memoria"); + LSTR MSG_LOAD_EEPROM = _UxGT("Kargatu memoria"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Larri. berriz."); + LSTR MSG_INIT_EEPROM = _UxGT("EEPROM-a hasieratu"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Berriz kargatu"); + LSTR MSG_INFO_SCREEN = _UxGT("Pantaila info"); + LSTR MSG_PREPARE = _UxGT("Prestatu"); + LSTR MSG_TUNE = _UxGT("Doitu"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausatu inprimak."); + LSTR MSG_RESUME_PRINT = _UxGT("Jarraitu inprima."); + LSTR MSG_STOP_PRINT = _UxGT("Gelditu inprima."); + LSTR MSG_MEDIA_MENU = _UxGT("SD-tik inprimatu"); + LSTR MSG_NO_MEDIA = _UxGT("Ez dago SD-rik"); + LSTR MSG_DWELL = _UxGT("Lo egin..."); + LSTR MSG_USERWAIT = _UxGT("Aginduak zain..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Inprim. geldi."); + LSTR MSG_PRINT_ABORTED = _UxGT("Inprim. deusezta."); + LSTR MSG_NO_MOVE = _UxGT("Mugimendu gabe."); + LSTR MSG_KILLED = _UxGT("AKABATUTA. "); + LSTR MSG_STOPPED = _UxGT("GELDITUTA. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Atzera egin mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Atzera mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Atzera egin V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Igo mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Atzera egin mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Swap Atzera mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Atzera egin V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Atzera egin"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Aldatu harizpia"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Aldatu harizpia *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Harizpia kargatu"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Harizpia kargatu *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Harizpia deskargatu"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Harizpia deskargatu *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Erabat deskargatu"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Hasieratu SD-a"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Aldatu txartela"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z zunda kanpora"); + LSTR MSG_SKEW_FACTOR = _UxGT("Okertze faktorea"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch AutoProba"); + LSTR MSG_BLTOUCH_RESET = _UxGT("BLTouch berrabia."); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch jaitsi/luzatu"); + LSTR MSG_BLTOUCH_STOW = _UxGT("BLTouch igo/jaso"); + LSTR MSG_HOME_FIRST = _UxGT("Etxera %s%s%s lehenengo"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z Konpentsatu"); + LSTR MSG_BABYSTEP_X = _UxGT("Mikro-urratsa X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Mikro-urratsa Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Mikro-urratsa Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop deusezta."); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Err: Beroketa"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: Tenperatura"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TENP. KONTROL EZA"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: Tenp Maximoa"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: Tenp Minimoa"); + LSTR MSG_HALTED = _UxGT("INPRIMA. GELDIRIK"); + LSTR MSG_PLEASE_RESET = _UxGT("Berrabia. Mesedez"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Berotzen..."); + LSTR MSG_BED_HEATING = _UxGT("Ohea Berotzen..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibraketa"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibratu X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibratu Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibratu Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibratu Zentrua"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta ezarpenak"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibraketa"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Alt. Ezar."); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra diagonala"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Altuera"); + LSTR MSG_DELTA_RADIUS = _UxGT("Erradioa"); + LSTR MSG_INFO_MENU = _UxGT("Inprimagailu Inf."); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Inprimagailu Inf."); + LSTR MSG_3POINT_LEVELING = _UxGT("3 puntuko berdinketa"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Berdinketa lineala"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Berdinketa bilinearra"); + LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_MESH_LEVELING = _UxGT("Sare berdinketa"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Inprima. estatis."); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Txartelaren Info."); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistoreak"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Estrusoreak"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baudioak"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokoloa"); + LSTR MSG_CASE_LIGHT = _UxGT("Kabina Argia"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Argiaren Distira"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Inprim. Zenbaketa"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Inprim. denbora"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Imprimatze luzeena"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Estruituta guztira"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Inprim. Zenbaketa"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Inprim. denbora"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Imprimatze luzeena"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Estruituta guztira"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Inprimatze"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Guztira"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Luzeena"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Estrusio"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Inprimatze"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Guztira"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Luzeena"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Estrusio"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Tenp. Minimoa"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Tenp. Maximoa"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Elikadura-iturria"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driver-aren potentzia"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Idatzi DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("HARIZPIA ALDATU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("HARIZPIA KARGATU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("HARIZPIA DESKARGATU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ALDAKETA AUKERAK:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Inprima. jarraitu"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Pita: "); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Hasi. huts egin du"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Neurketak huts egin du"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Tenp. Minimoa"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Tenp. Maximoa"); + LSTR MSG_INFO_PSU = _UxGT("Elikadura-iturria"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Driver-aren potentzia"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Idatzi DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("HARIZPIA ALDATU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("HARIZPIA KARGATU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("HARIZPIA DESKARGATU"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ALDAKETA AUKERAK:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Inprima. jarraitu"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Pita: "); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Hasi. huts egin du"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Neurketak huts egin du"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Inprimagailu okerra"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Inprimagailu okerra"); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Mesedez, itxaron...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Deskargatzen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Sartu eta click egin")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Berotzen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Kargatzen...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Mesedez, itxaron...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Deskargatzen...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Sartu eta click egin")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Berotzen...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Kargatzen...")); } diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 0d3b97cc44..075b5b2744 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -33,99 +33,99 @@ namespace Language_fi { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Finnish"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Finnish"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" valmis."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Kortti asetettu"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Kortti poistettu"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Palaa"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Automaatti"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Vapauta moottorit"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Aja referenssiin"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Aseta origo"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" valmis."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Kortti asetettu"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Kortti poistettu"); + LSTR MSG_MAIN = _UxGT("Palaa"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Automaatti"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Vapauta moottorit"); + LSTR MSG_AUTO_HOME = _UxGT("Aja referenssiin"); + LSTR MSG_SET_ORIGIN = _UxGT("Aseta origo"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Esilämmitä ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Esilämmitä ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT("Suutin"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT("Suutin ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT(" Kaikki"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT(" Alusta"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Esilämm. ") PREHEAT_1_LABEL _UxGT(" konf"); + LSTR MSG_PREHEAT_1 = _UxGT("Esilämmitä ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Esilämmitä ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT("Suutin"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT("Suutin ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT(" Kaikki"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Esilä. ") PREHEAT_1_LABEL _UxGT(" Alusta"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Esilämm. ") PREHEAT_1_LABEL _UxGT(" konf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Esilämmitä $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Esilämmitä $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Esilä. $Suutin"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Esilä. $Suutin ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Esilä. $ Kaikki"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Esilä. $ Alusta"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Esilämm. $ konf"); + LSTR MSG_PREHEAT_M = _UxGT("Esilämmitä $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Esilämmitä $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Esilä. $Suutin"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Esilä. $Suutin ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Esilä. $ Kaikki"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Esilä. $ Alusta"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Esilämm. $ konf"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Jäähdytä"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Virta päälle"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Virta pois"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Pursota"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Vedä takaisin"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Liikuta akseleita"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Liikuta X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Liikuta Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Liikuta Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Liikuta %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Liikuta 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Nopeus"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Suutin"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Suutin ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Alusta"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Tuul. nopeus"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Tuul. nopeus ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Virtaus"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Virtaus ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontrolli"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Kerr"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); - PROGMEM Language_Str MSG_ACC = _UxGT("Kiihtyv"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VLiike min"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-peruuta"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Lämpötila"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Liike"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontrasti"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Tallenna muistiin"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Lataa muistista"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Palauta oletus"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Päivitä"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Seuraa"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Valmistele"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Säädä"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Keskeytä tulostus"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Jatka tulostusta"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Pysäytä tulostus"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Korttivalikko"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Ei korttia"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Nukkumassa..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Odotet. valintaa"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Ei liiketta."); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Vedä mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Va. Vedä mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Vedä V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Va. Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoVeto."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrointi"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibroi X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibroi Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibroi Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibroi Center"); + LSTR MSG_COOLDOWN = _UxGT("Jäähdytä"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Virta päälle"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Virta pois"); + LSTR MSG_EXTRUDE = _UxGT("Pursota"); + LSTR MSG_RETRACT = _UxGT("Vedä takaisin"); + LSTR MSG_MOVE_AXIS = _UxGT("Liikuta akseleita"); + LSTR MSG_MOVE_X = _UxGT("Liikuta X"); + LSTR MSG_MOVE_Y = _UxGT("Liikuta Y"); + LSTR MSG_MOVE_Z = _UxGT("Liikuta Z"); + LSTR MSG_MOVE_E = _UxGT("Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Extruder *"); + LSTR MSG_MOVE_N_MM = _UxGT("Liikuta %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Liikuta 100mm"); + LSTR MSG_SPEED = _UxGT("Nopeus"); + LSTR MSG_NOZZLE = _UxGT("Suutin"); + LSTR MSG_NOZZLE_N = _UxGT("Suutin ~"); + LSTR MSG_BED = _UxGT("Alusta"); + LSTR MSG_FAN_SPEED = _UxGT("Tuul. nopeus"); + LSTR MSG_FAN_SPEED_N = _UxGT("Tuul. nopeus ~"); + LSTR MSG_FLOW = _UxGT("Virtaus"); + LSTR MSG_FLOW_N = _UxGT("Virtaus ~"); + LSTR MSG_CONTROL = _UxGT("Kontrolli"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Kerr"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_ACC = _UxGT("Kiihtyv"); + LSTR MSG_VTRAV_MIN = _UxGT("VLiike min"); + LSTR MSG_A_RETRACT = _UxGT("A-peruuta"); + LSTR MSG_TEMPERATURE = _UxGT("Lämpötila"); + LSTR MSG_MOTION = _UxGT("Liike"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_CONTRAST = _UxGT("LCD kontrasti"); + LSTR MSG_STORE_EEPROM = _UxGT("Tallenna muistiin"); + LSTR MSG_LOAD_EEPROM = _UxGT("Lataa muistista"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Palauta oletus"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Päivitä"); + LSTR MSG_INFO_SCREEN = _UxGT("Seuraa"); + LSTR MSG_PREPARE = _UxGT("Valmistele"); + LSTR MSG_TUNE = _UxGT("Säädä"); + LSTR MSG_PAUSE_PRINT = _UxGT("Keskeytä tulostus"); + LSTR MSG_RESUME_PRINT = _UxGT("Jatka tulostusta"); + LSTR MSG_STOP_PRINT = _UxGT("Pysäytä tulostus"); + LSTR MSG_MEDIA_MENU = _UxGT("Korttivalikko"); + LSTR MSG_NO_MEDIA = _UxGT("Ei korttia"); + LSTR MSG_DWELL = _UxGT("Nukkumassa..."); + LSTR MSG_USERWAIT = _UxGT("Odotet. valintaa"); + LSTR MSG_NO_MOVE = _UxGT("Ei liiketta."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Vedä mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Va. Vedä mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Vedä V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Va. Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_AUTORETRACT = _UxGT("AutoVeto."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrointi"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibroi X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibroi Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibroi Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibroi Center"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Väärä tulostin"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Väärä tulostin"); } diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index ef15d069dc..46dd712ec2 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -33,630 +33,630 @@ namespace Language_fr { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Français"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Français"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" prête."); - PROGMEM Language_Str MSG_YES = _UxGT("Oui"); - PROGMEM Language_Str MSG_NO = _UxGT("Non"); - PROGMEM Language_Str MSG_BACK = _UxGT("Retour"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Annulation..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Média inséré"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Média retiré"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Attente média"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err lecture média"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB débranché"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Erreur média USB"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Butées"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butées SW"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Config. avancée"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuration"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Exéc. auto.gcode"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Arrêter moteurs"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); - PROGMEM Language_Str MSG_HOMING = _UxGT("Origine"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Origine auto"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Origine X auto"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Origine Z auto"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Origine ") LCD_STR_I _UxGT(" auto"); - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Origine ") LCD_STR_J _UxGT(" auto"); - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Origine ") LCD_STR_K _UxGT(" auto"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Align. Z auto"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Origine XYZ..."); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Clic pour commencer"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Point suivant"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Mise à niveau OK!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Hauteur lissée"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Régl. décal origine"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Régler origine"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Molette du lit"); // Not a selection of the origin - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ecart origine "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" prête."); + LSTR MSG_YES = _UxGT("Oui"); + LSTR MSG_NO = _UxGT("Non"); + LSTR MSG_BACK = _UxGT("Retour"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Annulation..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Média inséré"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Média retiré"); + LSTR MSG_MEDIA_WAITING = _UxGT("Attente média"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err lecture média"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB débranché"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur média USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Butées"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butées SW"); + LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Config. avancée"); + LSTR MSG_CONFIGURATION = _UxGT("Configuration"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Exéc. auto.gcode"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Arrêter moteurs"); + LSTR MSG_DEBUG_MENU = _UxGT("Menu debug"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); + LSTR MSG_HOMING = _UxGT("Origine"); + LSTR MSG_AUTO_HOME = _UxGT("Origine auto"); + LSTR MSG_AUTO_HOME_X = _UxGT("Origine X auto"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Origine Z auto"); + LSTR MSG_AUTO_HOME_I = _UxGT("Origine ") LCD_STR_I _UxGT(" auto"); + LSTR MSG_AUTO_HOME_J = _UxGT("Origine ") LCD_STR_J _UxGT(" auto"); + LSTR MSG_AUTO_HOME_K = _UxGT("Origine ") LCD_STR_K _UxGT(" auto"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Align. Z auto"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Origine XYZ..."); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Clic pour commencer"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Point suivant"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Mise à niveau OK!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Hauteur lissée"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Régl. décal origine"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); + LSTR MSG_SET_ORIGIN = _UxGT("Régler origine"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Molette du lit"); // Not a selection of the origin + LSTR MSG_LAST_VALUE_SP = _UxGT("Ecart origine "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Préchauffage ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Préchauffage ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" buse"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" buse ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" Tout"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" lit"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Régler préch. ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1 = _UxGT("Préchauffage ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Préchauffage ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" buse"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" buse ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" Tout"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Préch. ") PREHEAT_1_LABEL _UxGT(" lit"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Régler préch. ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Préchauffage $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Préchauffage $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Préch. $ buse"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Préch. $ buse ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Préch. $ Tout"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Préch. $ lit"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Régler préch. $"); + LSTR MSG_PREHEAT_M = _UxGT("Préchauffage $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Préchauffage $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Préch. $ buse"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Préch. $ buse ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Préch. $ Tout"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Préch. $ lit"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Régler préch. $"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Préchauf. perso"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Refroidir"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Contrôle Laser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Puissance"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverser broches"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Allumer alim."); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Eteindre alim."); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrusion"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Rétractation"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Niveau des coins"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Coin suivant"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Modif. maille"); // 13 car. max - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifier grille"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Modification arrêtée"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Mesure point"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valeur Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Commandes perso"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Préchauf. perso"); + LSTR MSG_COOLDOWN = _UxGT("Refroidir"); + LSTR MSG_LASER_MENU = _UxGT("Contrôle Laser"); + LSTR MSG_LASER_POWER = _UxGT("Puissance"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Inverser broches"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Allumer alim."); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Eteindre alim."); + LSTR MSG_EXTRUDE = _UxGT("Extrusion"); + LSTR MSG_RETRACT = _UxGT("Rétractation"); + LSTR MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); + LSTR MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); + LSTR MSG_LEVEL_BED = _UxGT("Niveau du lit"); + LSTR MSG_BED_TRAMMING = _UxGT("Niveau des coins"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Relever le coin jusqu'à la sonde"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Coins dans la tolérance. Niveau lit "); + LSTR MSG_NEXT_CORNER = _UxGT("Coin suivant"); + LSTR MSG_MESH_EDITOR = _UxGT("Modif. maille"); // 13 car. max + LSTR MSG_EDIT_MESH = _UxGT("Modifier grille"); + LSTR MSG_EDITING_STOPPED = _UxGT("Modification arrêtée"); + LSTR MSG_PROBING_POINT = _UxGT("Mesure point"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valeur Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Commandes perso"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Mesure point"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("Ecart sonde Z M48"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Ecart"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("Point M48"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Mode IDEX"); - 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("Copie miroir"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Contrôle complet"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Offsets Outil"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("Buse 2 X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("Buse 2 Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("Buse 2 Z"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26: Chauffage du lit"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("Buse en chauffe..."); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Amorce manuelle..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Amorce longueur fixe"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Amorce terminée"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 annulé"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Sortie G26"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 en cours"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Outils UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Niveau lit unifié"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Maillage manuel"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Poser câle & mesurer"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mesure"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("ôter et mesurer lit"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Aller au suivant"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activer l'UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Désactiver l'UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Température lit"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Température lit"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Température buse"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Température buse"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Modifier grille"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Modif. grille perso"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Réglage fin"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Terminer"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Créer la grille"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Mesure point"); + LSTR MSG_M48_TEST = _UxGT("Ecart sonde Z M48"); + LSTR MSG_M48_DEVIATION = _UxGT("Ecart"); + LSTR MSG_M48_POINT = _UxGT("Point M48"); + LSTR MSG_IDEX_MENU = _UxGT("Mode IDEX"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copie miroir"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Contrôle complet"); + LSTR MSG_OFFSETS_MENU = _UxGT("Offsets Outil"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("Buse 2 X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("Buse 2 Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("Buse 2 Z"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26: Chauffage du lit"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("Buse en chauffe..."); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Amorce manuelle..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Amorce longueur fixe"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Amorce terminée"); + LSTR MSG_G26_CANCELED = _UxGT("G26 annulé"); + LSTR MSG_G26_LEAVING = _UxGT("Sortie G26"); + LSTR MSG_UBL_DOING_G29 = _UxGT("G29 en cours"); + LSTR MSG_UBL_TOOLS = _UxGT("Outils UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Niveau lit unifié"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Maillage manuel"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Poser câle & mesurer"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Mesure"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("ôter et mesurer lit"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Aller au suivant"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Activer l'UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Désactiver l'UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Température lit"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Température lit"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Température buse"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Température buse"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Modifier grille"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Modif. grille perso"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Réglage fin"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Terminer"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Créer la grille"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Créer grille $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Impr. grille $"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Créer grille $"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Impr. grille $"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Créer grille ..."); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Mesure à froid"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajuster haut. couche"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Hauteur (x0.1mm)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Vérifier grille"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Impr. grille ..."); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continuer grille"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Niveau par mailles"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Niveau à 3 points"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Niveau par grille"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Effectuer mesures"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Points latéraux"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Type de carte"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Exporter grille"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Export pour hôte"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Export en CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Export sauvegarde"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Infos debug UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Nombre de points"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Remplissage manuel"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Remplissage auto"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Remplissage grille"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Tout effacer"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Effacer le + près"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Réglage fin (tous)"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Réglage fin + près"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Stockage grille"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot mémoire"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Charger la grille"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Stocker la grille"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Grille %i chargée"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Grille %i enreg."); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Pas de mémoire"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: Enreg. UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: Ouvrir UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Décal. Z arrêté"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Assistant UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Mesure à froid"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Compléter auto."); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Vérifier grille"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Réglage fin"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Vérifier grille"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Réglage fin"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Stocker grille"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Créer grille ..."); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Mesure à froid"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajuster haut. couche"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Hauteur (x0.1mm)"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Vérifier grille"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Impr. grille ..."); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continuer grille"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Niveau par mailles"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Niveau à 3 points"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Niveau par grille"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Effectuer mesures"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Points latéraux"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Type de carte"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Exporter grille"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Export pour hôte"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Export en CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Export sauvegarde"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Infos debug UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Nombre de points"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Remplissage manuel"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Remplissage auto"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Remplissage grille"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Tout effacer"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Effacer le + près"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Réglage fin (tous)"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Réglage fin + près"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Stockage grille"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot mémoire"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Charger la grille"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Stocker la grille"); + LSTR MSG_MESH_LOADED = _UxGT("Grille %i chargée"); + LSTR MSG_MESH_SAVED = _UxGT("Grille %i enreg."); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Pas de mémoire"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err: Enreg. UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err: Ouvrir UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Décal. Z arrêté"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Assistant UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Mesure à froid"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Compléter auto."); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Vérifier grille"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Réglage fin"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Vérifier grille"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Réglage fin"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Stocker grille"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Contrôle LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Lumière"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Préregl. LED"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rouge"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Jaune"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Vert"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Bleu"); - 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("Blanc"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Defaut"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("LEDs perso."); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensité rouge"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensité vert"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensité bleu"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensité blanc"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Luminosité"); + LSTR MSG_LED_CONTROL = _UxGT("Contrôle LED"); + LSTR MSG_LEDS = _UxGT("Lumière"); + LSTR MSG_LED_PRESETS = _UxGT("Préregl. LED"); + LSTR MSG_SET_LEDS_RED = _UxGT("Rouge"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Jaune"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Vert"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Bleu"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Blanc"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Defaut"); + LSTR MSG_CUSTOM_LEDS = _UxGT("LEDs perso."); + LSTR MSG_INTENSITY_R = _UxGT("Intensité rouge"); + LSTR MSG_INTENSITY_G = _UxGT("Intensité vert"); + LSTR MSG_INTENSITY_B = _UxGT("Intensité bleu"); + LSTR MSG_INTENSITY_W = _UxGT("Intensité blanc"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Luminosité"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Déplacement..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Débloquer XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Déplacer X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Déplacer Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Déplacer Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Déplacer ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Déplacer ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Déplacer ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Déplacer %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Déplacer 0.001\""); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Déplacer 0.01\""); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Déplacer 0.1\""); - PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Déplacer 1\""); - PROGMEM Language_Str MSG_SPEED = _UxGT("Vitesse"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Lit Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Buse"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Buse ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Lit"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Caisson"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vit. ventil. "); // 15 car. max - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vit. ventil. ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Vit. enreg. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra ventil. "); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra ventil. ~"); + LSTR MSG_MOVING = _UxGT("Déplacement..."); + LSTR MSG_FREE_XY = _UxGT("Débloquer XY"); + LSTR MSG_MOVE_X = _UxGT("Déplacer X"); + LSTR MSG_MOVE_Y = _UxGT("Déplacer Y"); + LSTR MSG_MOVE_Z = _UxGT("Déplacer Z"); + LSTR MSG_MOVE_I = _UxGT("Déplacer ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Déplacer ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Déplacer ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Extruder *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); + LSTR MSG_MOVE_N_MM = _UxGT("Déplacer %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Déplacer 0.001\""); + LSTR MSG_MOVE_001IN = _UxGT("Déplacer 0.01\""); + LSTR MSG_MOVE_01IN = _UxGT("Déplacer 0.1\""); + LSTR MSG_MOVE_1IN = _UxGT("Déplacer 1\""); + LSTR MSG_SPEED = _UxGT("Vitesse"); + LSTR MSG_BED_Z = _UxGT("Lit Z"); + LSTR MSG_NOZZLE = _UxGT("Buse"); + LSTR MSG_NOZZLE_N = _UxGT("Buse ~"); + LSTR MSG_BED = _UxGT("Lit"); + LSTR MSG_CHAMBER = _UxGT("Caisson"); + LSTR MSG_FAN_SPEED = _UxGT("Vit. ventil. "); // 15 car. max + LSTR MSG_FAN_SPEED_N = _UxGT("Vit. ventil. ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Vit. enreg. ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra ventil. "); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra ventil. ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flux"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flux ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Contrôler"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Facteur"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temp. Auto."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Marche"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Arrêt"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Tuning PID terminé"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Echec Autotune! E incorrect"); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Echec Autotune! Temp. trop haute"); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Echec Autotune! Opér. expirée"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Sélectionner"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Sélectionner *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Accélération"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT(" jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT(" jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT(" jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT(" jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT(" jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT(" jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve jerk"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Vélocité"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vit. Max ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vit. Max ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vit. Max ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vit. Max ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vit. Max ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vit. Max ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vit. Max ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vit. Max *"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vit. Min"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vmin course"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accélération"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Accél. ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Accél. ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Accél. ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max Accél. ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max Accél. ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max Accél. ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Accél. ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Accél. *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Acc.rétraction"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Acc.course"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Vitesse min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pas/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pas/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pas/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pas/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Température"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Mouvement"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite en mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diamètre fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diamètre fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Retrait mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Charger mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avance K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Enregistrer config."); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Charger config."); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restaurer défauts"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initialiser EEPROM"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Config. enregistrée"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("MaJ Firmware SD"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("RaZ imprimante"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Actualiser"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Surveiller"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Préparer"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Régler"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Démarrer impression"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Suivant"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Init."); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimer"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorer"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Annuler"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Terminé"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Retour"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procéder"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Passer"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Mise en pause..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause impression"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Reprendre impr."); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Arrêter impr."); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Impression objet"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Annuler objet"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Annuler objet ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Récup. coup."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Impression SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Pas de média"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Repos..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Attente utilis."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impr. en pause"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Impression"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impr. annulée"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Moteurs bloqués"); - PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPÉ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rétractation mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Ech. rétr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Vit. rétract°"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saut Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Rét.reprise mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Ech.reprise mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("V.rét. reprise"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("V.éch. reprise"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Rétraction auto"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Changement outil"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Augmenter Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vitesse primaire"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vitesse rétract°"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Garer Extrudeur"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vitesse reprise"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vit. ventil."); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Temps ventil."); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Migration d'outil"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Migration auto"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Extrudeur Final"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrer vers *"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Attente buse"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Longueur retrait"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Longueur Extra"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Longueur de purge"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Changer filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Changer filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Charger filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Charger filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Retrait filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Retrait filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Retirer tout"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Charger le média"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Actualiser média"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Retirer le média"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonde Z hors lit"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Facteur écart"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Ranger"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Déployer"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Mode SW"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Mode 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Mode OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Appliquer Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Mise en 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Mise en OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Afficher Mode"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init. TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test décalage Z"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Sauvegarde"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Déployer TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Déployer Sonde Z"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Ranger Sonde Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Origine %s%s%s Premier"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Position sonde Z"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Décalage X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Décalage Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Décalage Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err TEMP. REDONDANTE"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Err THERMIQUE"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err TEMP. MAX"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err TEMP. MIN"); + LSTR MSG_FLOW = _UxGT("Flux"); + LSTR MSG_FLOW_N = _UxGT("Flux ~"); + LSTR MSG_CONTROL = _UxGT("Contrôler"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Facteur"); + LSTR MSG_AUTOTEMP = _UxGT("Temp. Auto."); + LSTR MSG_LCD_ON = _UxGT("Marche"); + LSTR MSG_LCD_OFF = _UxGT("Arrêt"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Tuning PID terminé"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Echec Autotune! E incorrect"); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Echec Autotune! Temp. trop haute"); + LSTR MSG_PID_TIMEOUT = _UxGT("Echec Autotune! Opér. expirée"); + LSTR MSG_SELECT = _UxGT("Sélectionner"); + LSTR MSG_SELECT_E = _UxGT("Sélectionner *"); + LSTR MSG_ACC = _UxGT("Accélération"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT(" jerk"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT(" jerk"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT(" jerk"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT(" jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT(" jerk"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT(" jerk"); + LSTR MSG_VE_JERK = _UxGT("Ve jerk"); + LSTR MSG_VELOCITY = _UxGT("Vélocité"); + LSTR MSG_VMAX_A = _UxGT("Vit. Max ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vit. Max ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vit. Max ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vit. Max ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vit. Max ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vit. Max ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vit. Max ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vit. Max *"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); + LSTR MSG_VMIN = _UxGT("Vit. Min"); + LSTR MSG_VTRAV_MIN = _UxGT("Vmin course"); + LSTR MSG_ACCELERATION = _UxGT("Accélération"); + LSTR MSG_AMAX_A = _UxGT("Max Accél. ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Max Accél. ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Max Accél. ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Max Accél. ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Max Accél. ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Max Accél. ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Max Accél. ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Max Accél. *"); + LSTR MSG_A_RETRACT = _UxGT("Acc.rétraction"); + LSTR MSG_A_TRAVEL = _UxGT("Acc.course"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Vitesse min"); + LSTR MSG_STEPS_PER_MM = _UxGT("Pas/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pas/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pas/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pas/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pas/mm"); + LSTR MSG_E_STEPS = _UxGT("E pas/mm"); + LSTR MSG_EN_STEPS = _UxGT("* pas/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Température"); + LSTR MSG_MOTION = _UxGT("Mouvement"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("Limite en mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Diamètre fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diamètre fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Retrait mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Charger mm"); + LSTR MSG_ADVANCE_K = _UxGT("Avance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); + LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Enregistrer config."); + LSTR MSG_LOAD_EEPROM = _UxGT("Charger config."); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restaurer défauts"); + LSTR MSG_INIT_EEPROM = _UxGT("Initialiser EEPROM"); + LSTR MSG_SETTINGS_STORED = _UxGT("Config. enregistrée"); + LSTR MSG_MEDIA_UPDATE = _UxGT("MaJ Firmware SD"); + LSTR MSG_RESET_PRINTER = _UxGT("RaZ imprimante"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Actualiser"); + LSTR MSG_INFO_SCREEN = _UxGT("Surveiller"); + LSTR MSG_PREPARE = _UxGT("Préparer"); + LSTR MSG_TUNE = _UxGT("Régler"); + LSTR MSG_START_PRINT = _UxGT("Démarrer impression"); + LSTR MSG_BUTTON_NEXT = _UxGT("Suivant"); + LSTR MSG_BUTTON_INIT = _UxGT("Init."); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Imprimer"); + LSTR MSG_BUTTON_RESET = _UxGT("Reset"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorer"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Annuler"); + LSTR MSG_BUTTON_DONE = _UxGT("Terminé"); + LSTR MSG_BUTTON_BACK = _UxGT("Retour"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Procéder"); + LSTR MSG_BUTTON_SKIP = _UxGT("Passer"); + LSTR MSG_PAUSING = _UxGT("Mise en pause..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pause impression"); + LSTR MSG_RESUME_PRINT = _UxGT("Reprendre impr."); + LSTR MSG_STOP_PRINT = _UxGT("Arrêter impr."); + LSTR MSG_PRINTING_OBJECT = _UxGT("Impression objet"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Annuler objet"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Annuler objet ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Récup. coup."); + LSTR MSG_MEDIA_MENU = _UxGT("Impression SD"); + LSTR MSG_NO_MEDIA = _UxGT("Pas de média"); + LSTR MSG_DWELL = _UxGT("Repos..."); + LSTR MSG_USERWAIT = _UxGT("Attente utilis."); + LSTR MSG_PRINT_PAUSED = _UxGT("Impr. en pause"); + LSTR MSG_PRINTING = _UxGT("Impression"); + LSTR MSG_PRINT_ABORTED = _UxGT("Impr. annulée"); + LSTR MSG_NO_MOVE = _UxGT("Moteurs bloqués"); + LSTR MSG_KILLED = _UxGT("KILLED"); + LSTR MSG_STOPPED = _UxGT("STOPPÉ"); + LSTR MSG_CONTROL_RETRACT = _UxGT("Rétractation mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Ech. rétr. mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Vit. rétract°"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saut Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Rét.reprise mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Ech.reprise mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("V.rét. reprise"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("V.éch. reprise"); + LSTR MSG_AUTORETRACT = _UxGT("Rétraction auto"); + LSTR MSG_TOOL_CHANGE = _UxGT("Changement outil"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Augmenter Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Vitesse primaire"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vitesse rétract°"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Garer Extrudeur"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vitesse reprise"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vit. ventil."); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Temps ventil."); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Migration d'outil"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Migration auto"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Extrudeur Final"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrer vers *"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Attente buse"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Longueur retrait"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Longueur Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Longueur de purge"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Changer filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Changer filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Charger filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Charger filament *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Retrait filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Retrait filament *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Retirer tout"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Charger le média"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Actualiser média"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Retirer le média"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonde Z hors lit"); + LSTR MSG_SKEW_FACTOR = _UxGT("Facteur écart"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Ranger"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Déployer"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Mode SW"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Mode 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Mode OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Appliquer Mode"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Mise en 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Mise en OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Afficher Mode"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Init. TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test décalage Z"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Sauvegarde"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Déployer TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Déployer Sonde Z"); + LSTR MSG_MANUAL_STOW = _UxGT("Ranger Sonde Z"); + LSTR MSG_HOME_FIRST = _UxGT("Origine %s%s%s Premier"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Position sonde Z"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Décalage X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Décalage Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Décalage Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err TEMP. REDONDANTE"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("Err THERMIQUE"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err TEMP. MAX"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err TEMP. MIN"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPR. STOPPÉE"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Redémarrer SVP"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("j"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HALTED = _UxGT("IMPR. STOPPÉE"); + LSTR MSG_PLEASE_RESET = _UxGT("Redémarrer SVP"); + LSTR MSG_SHORT_DAY = _UxGT("j"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("en chauffe..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Refroidissement"); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Lit en chauffe..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Refroid. du lit..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe en chauffe..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Refroid. Probe..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Chauffe caisson..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Refroid. caisson..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibration Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrer X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrer Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrer Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrer centre"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Réglages Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Calibration Auto"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Hauteur Delta"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Delta Z sonde"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diagonale"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Hauteur"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Rayon"); + LSTR MSG_HEATING = _UxGT("en chauffe..."); + LSTR MSG_COOLING = _UxGT("Refroidissement"); + LSTR MSG_BED_HEATING = _UxGT("Lit en chauffe..."); + LSTR MSG_BED_COOLING = _UxGT("Refroid. du lit..."); + LSTR MSG_PROBE_HEATING = _UxGT("Probe en chauffe..."); + LSTR MSG_PROBE_COOLING = _UxGT("Refroid. Probe..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Chauffe caisson..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Refroid. caisson..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibration Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrer X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrer Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrer Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrer centre"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Réglages Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Calibration Auto"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Hauteur Delta"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Delta Z sonde"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diagonale"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Hauteur"); + LSTR MSG_DELTA_RADIUS = _UxGT("Rayon"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Infos imprimante"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Infos imprimante"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Niveau à 3 points"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Niveau linéaire"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Niveau bilinéaire"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Niveau lit unifié"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Niveau par grille"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Niveau terminé"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Stats. imprimante"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Infos carte"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistances"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrudeurs"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Bauds"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocole"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Protection inactive"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Protection active"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_INFO_MENU = _UxGT("Infos imprimante"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Infos imprimante"); + LSTR MSG_3POINT_LEVELING = _UxGT("Niveau à 3 points"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Niveau linéaire"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Niveau bilinéaire"); + LSTR MSG_UBL_LEVELING = _UxGT("Niveau lit unifié"); + LSTR MSG_MESH_LEVELING = _UxGT("Niveau par grille"); + LSTR MSG_MESH_DONE = _UxGT("Niveau terminé"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Stats. imprimante"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Infos carte"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistances"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrudeurs"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Bauds"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocole"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Protection inactive"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Protection active"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Lumière caisson"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosité"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Imprimante incorrecte"); + LSTR MSG_CASE_LIGHT = _UxGT("Lumière caisson"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosité"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Imprimante incorrecte"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nbre impressions"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Terminées"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tps impr. total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impr. la + longue"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total filament"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Nbre impressions"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Terminées"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tps impr. total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Impr. la + longue"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total filament"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impressions"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Terminées"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("+ long"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Filament"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impressions"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Terminées"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("+ long"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Filament"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp Min"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alim."); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp Min"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); + LSTR MSG_INFO_PSU = _UxGT("Alim."); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); + LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); + LSTR MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CHANGER FILAMENT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPR. PAUSE"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CHARGER FIL"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DECHARGER FIL"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPTIONS REPRISE:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purger encore"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Reprendre impr."); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Buse: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Capteur fil."); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Echec origine"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Echec sonde"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CHANGER FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPR. PAUSE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CHARGER FIL"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DECHARGER FIL"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPTIONS REPRISE:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purger encore"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Reprendre impr."); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Buse: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Capteur fil."); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Echec origine"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Echec sonde"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MAJ firmware MMU!!"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOISIR FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU ne répond plus"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuer Imp. MMU"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Reprise MMU..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Charge dans MMU"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Charger tous dans MMU"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Charger dans buse"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejecter fil. du MMU"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Ejecter fil. ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Retrait filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Chargem. fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejection fil..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Retrait fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Tous"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Réinit. MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Réinit. MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Retrait, click"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("MAJ firmware MMU!!"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOISIR FILAMENT"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU ne répond plus"); + LSTR MSG_MMU2_RESUME = _UxGT("Continuer Imp. MMU"); + LSTR MSG_MMU2_RESUMING = _UxGT("Reprise MMU..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Charge dans MMU"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Charger tous dans MMU"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Charger dans buse"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejecter fil. du MMU"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Ejecter fil. ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Retrait filament"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Chargem. fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejection fil..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Retrait fil...."); + LSTR MSG_MMU2_ALL = _UxGT("Tous"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Réinit. MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Réinit. MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Retrait, click"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Composante ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mixeur"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Dégradé"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Dégradé complet"); - 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("Mix dégradé"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Inverser dégradé"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Début V-tool"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Fin V-tool"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Réinit. V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Valider Mix V-tool"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools réinit. ok"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Début Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Jeux"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Casse-briques"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Labyrinthe"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Composante ="); + LSTR MSG_MIXER = _UxGT("Mixeur"); + LSTR MSG_GRADIENT = _UxGT("Dégradé"); + LSTR MSG_FULL_GRADIENT = _UxGT("Dégradé complet"); + LSTR MSG_TOGGLE_MIX = _UxGT("Toggle mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Cycle mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Mix dégradé"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Inverser dégradé"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + LSTR MSG_START_VTOOL = _UxGT("Début V-tool"); + LSTR MSG_END_VTOOL = _UxGT(" Fin V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("Réinit. V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Valider Mix V-tool"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools réinit. ok"); + LSTR MSG_START_Z = _UxGT("Début Z:"); + LSTR MSG_END_Z = _UxGT(" Fin Z:"); + LSTR MSG_GAMES = _UxGT("Jeux"); + LSTR MSG_BRICKOUT = _UxGT("Casse-briques"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Labyrinthe"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Erreur index page"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Erreur vitesse page"); + LSTR MSG_BAD_PAGE = _UxGT("Erreur index page"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Erreur vitesse page"); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Presser bouton", "pour reprendre")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Attente filament", "pour démarrer")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insérer filament", "et app. bouton", "pour continuer...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Presser le bouton", "pour chauffer...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Buse en chauffe", "Patienter SVP...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Attente", "retrait du filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Attente", "chargement filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Attente", "Purge filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Presser pour finir", "la purge du filament")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Attente reprise", "impression")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Presser bouton", "pour reprendre")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parking...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Attente filament", "pour démarrer")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insérer filament", "et app. bouton", "pour continuer...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Presser le bouton", "pour chauffer...")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Buse en chauffe", "Patienter SVP...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Attente", "retrait du filament")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Attente", "chargement filament")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Attente", "Purge filament")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Presser pour finir", "la purge du filament")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Attente reprise", "impression")); #else // LCD_HEIGHT < 4 // Up to 2 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Clic pour continuer")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Patience...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insérer fil.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Chauffer ?")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Chauffage...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Retrait fil...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Chargement...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purge...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Terminer ?")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reprise...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Clic pour continuer")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Patience...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insérer fil.")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Chauffer ?")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Chauffage...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Retrait fil...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Chargement...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purge...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Terminer ?")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Reprise...")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Courant driver"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Seuil hybride"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Home sans capteur"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Mode pas à pas"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop activé"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Réinit."); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dans:"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Lissage"); + LSTR MSG_TMC_CURRENT = _UxGT("Courant driver"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Seuil hybride"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Home sans capteur"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Mode pas à pas"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop activé"); + LSTR MSG_SERVICE_RESET = _UxGT("Réinit."); + LSTR MSG_SERVICE_IN = _UxGT(" dans:"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correction"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Lissage"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Niveau axe X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Etalon. auto."); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Niveau axe X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Etalon. auto."); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("En protection, temp. réduite. Ok pour rechauffer et continuer."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("En protection, temp. réduite. Ok pour rechauffer et continuer."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("En protection"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("En protection"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Chauffer"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Réchauffe..."); + LSTR MSG_REHEAT = _UxGT("Chauffer"); + LSTR MSG_REHEATING = _UxGT("Réchauffe..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Assistant Sonde Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Mesure référence"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Dépl. vers pos"); + LSTR MSG_PROBE_WIZARD = _UxGT("Assistant Sonde Z"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Mesure référence"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Dépl. vers pos"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Sons"); + LSTR MSG_SOUND = _UxGT("Sons"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Coin haut gauche"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Coin bas gauche"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Coin haut droit"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Coin bas droit"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibration terminée"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Échec de l'étalonnage"); + LSTR MSG_TOP_LEFT = _UxGT("Coin haut gauche"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Coin bas gauche"); + LSTR MSG_TOP_RIGHT = _UxGT("Coin haut droit"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Coin bas droit"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibration terminée"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Échec de l'étalonnage"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("Carte SD"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("Clé USB"); + LSTR MSG_SD_CARD = _UxGT("Carte SD"); + LSTR MSG_USB_DISK = _UxGT("Clé USB"); } diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index e29a2772ff..54a323034e 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -33,590 +33,590 @@ namespace Language_gl { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Galician"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Galician"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" lista."); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("SI"); - PROGMEM Language_Str MSG_NO = _UxGT("NON"); - PROGMEM Language_Str MSG_BACK = _UxGT("Atrás"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autoarranque"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progreso"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ir a orixe"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Ir orixe X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Ir orixe Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Ir orixe Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autoaliñar Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Ir orixes XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Prema pulsador"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Seguinte punto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Fin Nivelación!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Axustar Desfases"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfases aplicados"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Fixar orixe"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" lista."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("SI"); + LSTR MSG_NO = _UxGT("NON"); + LSTR MSG_BACK = _UxGT("Atrás"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); + LSTR MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); + LSTR MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); + LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); + LSTR MSG_CONFIGURATION = _UxGT("Configuración"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autoarranque"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); + LSTR MSG_DEBUG_MENU = _UxGT("Menú depuración"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progreso"); + LSTR MSG_AUTO_HOME = _UxGT("Ir a orixe"); + LSTR MSG_AUTO_HOME_X = _UxGT("Ir orixe X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Ir orixe Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Ir orixe Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Autoaliñar Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Ir orixes XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Prema pulsador"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Seguinte punto"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Fin Nivelación!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Axustar Desfases"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfases aplicados"); + LSTR MSG_SET_ORIGIN = _UxGT("Fixar orixe"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Prequentar ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Prequentar ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Bico"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Bico ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Todo"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Cama"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Prequentar ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Prequentar ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Bico"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Bico ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Todo"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" Cama"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preque. ") PREHEAT_1_LABEL _UxGT(" conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Prequentar $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Prequentar $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Preque. $ Bico"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Preque. $ Bico ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Preque. $ Todo"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Preque. $ Cama"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Preque. $ conf"); + LSTR MSG_PREHEAT_M = _UxGT("Prequentar $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Prequentar $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preque. $ Bico"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preque. $ Bico ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preque. $ Todo"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preque. $ Cama"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preque. $ conf"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preque. Personali."); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Arrefriar"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Fuso"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Fuso"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverter xiro"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Acender"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Apagar"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruír"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retraer"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixe"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado Detida"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punto de Proba"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comandos Personaliz."); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Ferramentas Compens"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicación"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Espello"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2º Bico X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2º Bico Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2º Bico Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Executando G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Facer Malla Manual"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Colocar Calzo e Medir"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Medir"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Quitar e Medir Cama"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover ao Seguinte"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp Cama"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp Cama"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp Bico"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp Bico"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Malla"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Malla Person."); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Axuste Fino da Malla"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Fin Edición da Malla"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Malla Person."); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Malla"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Preque. Personali."); + LSTR MSG_COOLDOWN = _UxGT("Arrefriar"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); + LSTR MSG_LASER_MENU = _UxGT("Control Láser"); + LSTR MSG_LASER_POWER = _UxGT("Potencia Láser"); + LSTR MSG_SPINDLE_MENU = _UxGT("Control Fuso"); + LSTR MSG_SPINDLE_POWER = _UxGT("Potencia Fuso"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Inverter xiro"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Acender"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Apagar"); + LSTR MSG_EXTRUDE = _UxGT("Extruír"); + LSTR MSG_RETRACT = _UxGT("Retraer"); + LSTR MSG_MOVE_AXIS = _UxGT("Mover eixe"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelando Cama"); + LSTR MSG_LEVEL_BED = _UxGT("Nivelar Cama"); + LSTR MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); + LSTR MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor Mallado"); + LSTR MSG_EDIT_MESH = _UxGT("Editar Mallado"); + LSTR MSG_EDITING_STOPPED = _UxGT("Ed. Mallado Detida"); + LSTR MSG_PROBING_POINT = _UxGT("Punto de Proba"); + LSTR MSG_MESH_X = _UxGT("Índice X"); + LSTR MSG_MESH_Y = _UxGT("Índice Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valor Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comandos Personaliz."); + LSTR MSG_M48_TEST = _UxGT("M48 Probar Sonda"); + LSTR MSG_M48_POINT = _UxGT("M48 Punto"); + LSTR MSG_M48_DEVIATION = _UxGT("Desviación"); + LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Ferramentas Compens"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicación"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Espello"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2º Bico X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2º Bico Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2º Bico Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Executando G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Facer Malla Manual"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Colocar Calzo e Medir"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Medir"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Quitar e Medir Cama"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover ao Seguinte"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Temp Cama"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp Cama"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp Bico"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp Bico"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Editar Malla"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Malla Person."); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Axuste Fino da Malla"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Fin Edición da Malla"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Malla Person."); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Malla"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Crear Malla ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Validar Malla ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Crear Malla ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validar Malla ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Malla Fría"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Axustar Altura Malla"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altura"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malla"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malla perso."); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Quentando Cama"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Quentando Bico"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Traballo manual..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Traballo Lonxit Fixa"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Fin Traballo"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Cancelado"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Saíndo de G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malla"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelación Malla"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelación 3Puntos"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelación Grid"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malla"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterais"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa "); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Gardar Mapa"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar ao Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Gardar en CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup Externo"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Info do UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidade de Recheo"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Recheo Manual"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Recheo Intelixente"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Recheo da Malla"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar cercanos"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Axustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Axustar Fino Cerc"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacenamento Malla"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Rañura Memoria"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Malla Cama"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Gardar Malla Cama"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malla %i Gardada"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sen Gardar"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro: Gardadado UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro: Recuperación UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Detido"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Crear Malla Fría"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Recheo Intelixente"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validar Malla"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Axustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validar Malla"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Axustar Fino Todo"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Gardar Malla Cama"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Malla Fría"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Axustar Altura Malla"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altura"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malla"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malla perso."); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Quentando Cama"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Quentando Bico"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Traballo manual..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Traballo Lonxit Fixa"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Fin Traballo"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Cancelado"); + LSTR MSG_G26_LEAVING = _UxGT("Saíndo de G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malla"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Nivelación Malla"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelación 3Puntos"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelación Grid"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malla"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterais"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa "); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Gardar Mapa"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar ao Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Gardar en CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup Externo"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Info do UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidade de Recheo"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Recheo Manual"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Recheo Intelixente"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Recheo da Malla"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar cercanos"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Axustar Fino Todo"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Axustar Fino Cerc"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacenamento Malla"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Rañura Memoria"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Cargar Malla Cama"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Gardar Malla Cama"); + LSTR MSG_MESH_LOADED = _UxGT("Malla %i Cargada"); + LSTR MSG_MESH_SAVED = _UxGT("Malla %i Gardada"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Sen Gardar"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Erro: Gardadado UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Erro: Recuperación UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Detido"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Crear Malla Fría"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Recheo Intelixente"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validar Malla"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Axustar Fino Todo"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validar Malla"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Axustar Fino Todo"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Gardar Malla Cama"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Luces"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Axustes Luz"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Vermello"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Laranxa"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Amarelo"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Verde"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Azul"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Branco"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luces personalizadas"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidade Vermello"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidade Verde"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidade Azul"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensidade Branco"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brillo"); + LSTR MSG_LED_CONTROL = _UxGT("Control LED"); + LSTR MSG_LEDS = _UxGT("Luces"); + LSTR MSG_LED_PRESETS = _UxGT("Axustes Luz"); + LSTR MSG_SET_LEDS_RED = _UxGT("Vermello"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Laranxa"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Amarelo"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Verde"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Azul"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Branco"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Luces personalizadas"); + LSTR MSG_INTENSITY_R = _UxGT("Intensidade Vermello"); + LSTR MSG_INTENSITY_G = _UxGT("Intensidade Verde"); + LSTR MSG_INTENSITY_B = _UxGT("Intensidade Azul"); + LSTR MSG_INTENSITY_W = _UxGT("Intensidade Branco"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brillo"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Movendo..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Libre XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Bico ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Bico Estacionado"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Bico Standby"); - PROGMEM Language_Str MSG_BED = _UxGT("Cama"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Cámara"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventilador Mem. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Vent. Extra"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Vent. Extra ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidade Repouso"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidade Activa"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo Repouso"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxo"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxo ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Acender"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Fin Auto-Sint PID"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida. Extrusor danado."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida. Temperatura moi alta."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida. Tempo excedido."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Escolla"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Escolla *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Acel"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Max E Jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max * Vel"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("V-viaxe min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Aceleración"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrac."); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-viaxe"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frecuencia max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Avance min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E pasos/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* pasos/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movemento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carga mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avance K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Constraste LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gardar Configuración"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar Configuración"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. Defecto"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Erro: CRC EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Config Gardada"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Información"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Axustar"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Comezar impresión"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Seguinte"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Comezar"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Deter"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimir"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Atrás"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausando..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Retomar impresión"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impresión"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimindo Obxecto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Obxecto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impresión"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); - PROGMEM Language_Str MSG_DWELL = _UxGT("En repouso..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Prema para Retomar.."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimindo..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión Cancelada"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Fin Impresión"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sen movemento."); - PROGMEM Language_Str MSG_KILLED = _UxGT("MORTO."); - PROGMEM Language_Str MSG_STOPPED = _UxGT("DETIDO."); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Cambio retra. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Alzar Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Recup. retra. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Cambio recup. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Recuperacion V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retracción"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lonxitude Retracción"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Cambio Extra"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocidade prim."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de Retracción"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Extrusor Est."); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vel. Recuperación"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vel. Ventilador"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo Ventilador"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Cambio Ferramenta"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Cambio Automático"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Último Extrusor"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Cambio a *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Cargar Filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Descargar Filamento"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Descargar Filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar Todo"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda-Z fóra Cama"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Factor de Desviación"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Auto-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Recoller"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Estender"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Modo Software"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Modo 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Modo OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Modo Almacenar"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Axustar BLTouch a 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Axustar BLTouch a OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Modo de Informe"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERIGO: Unha mala configuración pode producir daños! Proceder igualmente?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test de Desfase Z"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Gardar"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estender TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda Z"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Recoller Sonda Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Orixe %s%s%s Primeiro"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desfases Sonda"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Erro FinCarro"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fallo Quentando"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CÁMARA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Erro:TEMP MÁX"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Erro:TEMP MÍN"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA DETIDA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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("Quentando..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Arrefriando..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Quentando cama..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Enfriando Cama..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Quentando Cámara..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Arrefriando Cámara..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Acerca de..."); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Información"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelación 3puntos"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelación Lineal"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelación Bilineal"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelación UBL"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelación en Malla"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Placa nai"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Reloxo Traballo: OFF"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Reloxo Traballo: ON"); + LSTR MSG_MOVING = _UxGT("Movendo..."); + LSTR MSG_FREE_XY = _UxGT("Libre XY"); + LSTR MSG_MOVE_X = _UxGT("Mover X"); + LSTR MSG_MOVE_Y = _UxGT("Mover Y"); + LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_E = _UxGT("Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mover 100mm"); + LSTR MSG_SPEED = _UxGT("Velocidade"); + LSTR MSG_BED_Z = _UxGT("Cama Z"); + LSTR MSG_NOZZLE = _UxGT("Bico"); + LSTR MSG_NOZZLE_N = _UxGT("Bico ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Bico Estacionado"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Bico Standby"); + LSTR MSG_BED = _UxGT("Cama"); + LSTR MSG_CHAMBER = _UxGT("Cámara"); + LSTR MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); + LSTR MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Ventilador Mem. ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Vent. Extra"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Vent. Extra ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidade Repouso"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidade Activa"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo Repouso"); + LSTR MSG_FLOW = _UxGT("Fluxo"); + LSTR MSG_FLOW_N = _UxGT("Fluxo ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Temperatura Auto."); + LSTR MSG_LCD_ON = _UxGT("Acender"); + LSTR MSG_LCD_OFF = _UxGT("Apagar"); + LSTR MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Fin Auto-Sint PID"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-Sint. fallida. Extrusor danado."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-Sint. fallida. Temperatura moi alta."); + LSTR MSG_PID_TIMEOUT = _UxGT("Auto-Sint. fallida. Tempo excedido."); + LSTR MSG_SELECT = _UxGT("Escolla"); + LSTR MSG_SELECT_E = _UxGT("Escolla *"); + LSTR MSG_ACC = _UxGT("Acel"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); + LSTR MSG_VELOCITY = _UxGT("Velocidade"); + LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("V-viaxe min"); + LSTR MSG_ACCELERATION = _UxGT("Aceleración"); + LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); + LSTR MSG_A_RETRACT = _UxGT("A-retrac."); + LSTR MSG_A_TRAVEL = _UxGT("A-viaxe"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frecuencia max"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Avance min"); + LSTR MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); + LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); + LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movemento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Diam. fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diam. fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Carga mm"); + LSTR MSG_ADVANCE_K = _UxGT("Avance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); + LSTR MSG_CONTRAST = _UxGT("Constraste LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Gardar Configuración"); + LSTR MSG_LOAD_EEPROM = _UxGT("Cargar Configuración"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Rest. Defecto"); + LSTR MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Erro: CRC EEPROM"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); + LSTR MSG_SETTINGS_STORED = _UxGT("Config Gardada"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + LSTR MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); + LSTR MSG_INFO_SCREEN = _UxGT("Información"); + LSTR MSG_PREPARE = _UxGT("Preparar"); + LSTR MSG_TUNE = _UxGT("Axustar"); + LSTR MSG_START_PRINT = _UxGT("Comezar impresión"); + LSTR MSG_BUTTON_NEXT = _UxGT("Seguinte"); + LSTR MSG_BUTTON_INIT = _UxGT("Comezar"); + LSTR MSG_BUTTON_STOP = _UxGT("Deter"); + LSTR MSG_BUTTON_PRINT = _UxGT("Imprimir"); + LSTR MSG_BUTTON_RESET = _UxGT("Reiniciar"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Cancelar"); + LSTR MSG_BUTTON_DONE = _UxGT("Listo"); + LSTR MSG_BUTTON_BACK = _UxGT("Atrás"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Proceder"); + LSTR MSG_PAUSING = _UxGT("Pausando..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); + LSTR MSG_RESUME_PRINT = _UxGT("Retomar impresión"); + LSTR MSG_STOP_PRINT = _UxGT("Deter impresión"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimindo Obxecto"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Obxecto"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impresión"); + LSTR MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); + LSTR MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); + LSTR MSG_DWELL = _UxGT("En repouso..."); + LSTR MSG_USERWAIT = _UxGT("Prema para Retomar.."); + LSTR MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); + LSTR MSG_PRINTING = _UxGT("Imprimindo..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Impresión Cancelada"); + LSTR MSG_PRINT_DONE = _UxGT("Fin Impresión"); + LSTR MSG_NO_MOVE = _UxGT("Sen movemento."); + LSTR MSG_KILLED = _UxGT("MORTO."); + LSTR MSG_STOPPED = _UxGT("DETIDO."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Cambio retra. mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Alzar Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Recup. retra. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Cambio recup. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Recuperacion V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retracción"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lonxitude Retracción"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Cambio Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); + LSTR MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocidade prim."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Vel. de Retracción"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Extrusor Est."); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Vel. Recuperación"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Vel. Ventilador"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo Ventilador"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Cambio Ferramenta"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Cambio Automático"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Último Extrusor"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Cambio a *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Cargar Filamento *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Descargar Filamento"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Descargar Filamento *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar Todo"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda-Z fóra Cama"); + LSTR MSG_SKEW_FACTOR = _UxGT("Factor de Desviación"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Auto-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reiniciar"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Recoller"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Estender"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Modo Software"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Modo 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Modo OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Modo Almacenar"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Axustar BLTouch a 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Axustar BLTouch a OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Modo de Informe"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERIGO: Unha mala configuración pode producir daños! Proceder igualmente?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test de Desfase Z"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Gardar"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estender TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda Z"); + LSTR MSG_MANUAL_STOW = _UxGT("Recoller Sonda Z"); + LSTR MSG_HOME_FIRST = _UxGT("Orixe %s%s%s Primeiro"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Desfases Sonda"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Micropaso X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Erro FinCarro"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Fallo Quentando"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CÁMARA"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Erro:TEMP MÁX"); + LSTR MSG_ERR_MINTEMP = _UxGT("Erro:TEMP MÍN"); + LSTR MSG_HALTED = _UxGT("IMPRESORA DETIDA"); + LSTR MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Quentando..."); + LSTR MSG_COOLING = _UxGT("Arrefriando..."); + LSTR MSG_BED_HEATING = _UxGT("Quentando cama..."); + LSTR MSG_BED_COOLING = _UxGT("Enfriando Cama..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Quentando Cámara..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Arrefriando Cámara..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radio"); + LSTR MSG_INFO_MENU = _UxGT("Acerca de..."); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Información"); + LSTR MSG_3POINT_LEVELING = _UxGT("Nivelación 3puntos"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Nivelación Lineal"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Nivelación Bilineal"); + LSTR MSG_UBL_LEVELING = _UxGT("Nivelación UBL"); + LSTR MSG_MESH_LEVELING = _UxGT("Nivelación en Malla"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Placa nai"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baudios"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocolo"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Reloxo Traballo: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Reloxo Traballo: ON"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Caixa"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); + LSTR MSG_CASE_LIGHT = _UxGT("Luz da Caixa"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo Total Imp."); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impresión máis longa"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruído"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo Total Imp."); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Impresión máis longa"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruído"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impresións"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Máis Longa"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impresións"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Máis Longa"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte Alimentación"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCIÓN DE RETOMAR:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar máis"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Retomar traballo"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bico: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor Filamento"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); + LSTR MSG_INFO_PSU = _UxGT("Fonte Alimentación"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCIÓN DE RETOMAR:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar máis"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Retomar traballo"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bico: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Sensor Filamento"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Actualizar FW MMU!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Precisa Atención."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Retomar impr."); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Retomando..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar até bico"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Todo"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Expulsar, premer"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Actualizar FW MMU!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Precisa Atención."); + LSTR MSG_MMU2_RESUME = _UxGT("Retomar impr."); + LSTR MSG_MMU2_RESUMING = _UxGT("Retomando..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar até bico"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil..."); + LSTR MSG_MMU2_ALL = _UxGT("Todo"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + LSTR MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Expulsar, premer"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mestura"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Compoñente ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mesturadora"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Degradado"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Degradado Total"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Mestura Conmutada"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Mestura Cíclica"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Mestura de Degradado"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Degradado Inverso"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Activar Ferr-V"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Inicio Ferr-V"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Fin Ferr-V"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias Ferr-V"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reiniciar Ferr-V"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit mest. Ferr-V"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("Ferr-V reiniciadas"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Inicio Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); + LSTR MSG_MIX = _UxGT("Mestura"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Compoñente ="); + LSTR MSG_MIXER = _UxGT("Mesturadora"); + LSTR MSG_GRADIENT = _UxGT("Degradado"); + LSTR MSG_FULL_GRADIENT = _UxGT("Degradado Total"); + LSTR MSG_TOGGLE_MIX = _UxGT("Mestura Conmutada"); + LSTR MSG_CYCLE_MIX = _UxGT("Mestura Cíclica"); + LSTR MSG_GRADIENT_MIX = _UxGT("Mestura de Degradado"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Degradado Inverso"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Activar Ferr-V"); + LSTR MSG_START_VTOOL = _UxGT("Inicio Ferr-V"); + LSTR MSG_END_VTOOL = _UxGT(" Fin Ferr-V"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias Ferr-V"); + LSTR MSG_RESET_VTOOLS = _UxGT("Reiniciar Ferr-V"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Commit mest. Ferr-V"); + LSTR MSG_VTOOLS_RESET = _UxGT("Ferr-V reiniciadas"); + LSTR MSG_START_Z = _UxGT("Inicio Z:"); + LSTR MSG_END_Z = _UxGT(" Fin Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Xogos"); - 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("Labirinto"); + LSTR MSG_GAMES = _UxGT("Xogos"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Labirinto"); #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Preme o botón para", "continuar impresión")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "comezar cambio", "de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Introduza o", "filamento e", "faga click")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Prema o botón para", "quentar o bico")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Quentando bico", "Agarde, por favor...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Agarde pola", "carga do", "filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Agarde para", "purgar o filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Prema para finalizar", "a purga do filamen.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde a que", "se retome", "a impresión")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Preme o botón para", "continuar impresión")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "comezar cambio", "de filamento")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Introduza o", "filamento e", "faga click")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Prema o botón para", "quentar o bico")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Quentando bico", "Agarde, por favor...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Agarde pola", "carga do", "filamento")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Agarde para", "purgar o filamento")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Prema para finalizar", "a purga do filamen.")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde a que", "se retome", "a impresión")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premer para continuar")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Agarde...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Introduza e click")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Prema para quentar")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Quentando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Prema para finalizar")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Retomando...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premer para continuar")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Estacionando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Agarde...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Introduza e click")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Prema para quentar")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Quentando...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Prema para finalizar")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Retomando...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Controlador Actual"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Limiar Hibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Orixe sen Sensores"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reiniciar"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dentro:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Reacción"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); + LSTR MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Controlador Actual"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Limiar Hibrido"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Orixe sen Sensores"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); + LSTR MSG_SERVICE_RESET = _UxGT("Reiniciar"); + LSTR MSG_SERVICE_IN = _UxGT(" dentro:"); + LSTR MSG_BACKLASH = _UxGT("Reacción"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivel Eixe X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Tempo exc. Quent."); - PROGMEM Language_Str MSG_REHEAT = _UxGT("Requentar"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Requentando..."); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivel Eixe X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Tempo exc. Quent."); + LSTR MSG_REHEAT = _UxGT("Requentar"); + LSTR MSG_REHEATING = _UxGT("Requentando..."); } diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index e4cbdaed6c..f0da04b063 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -33,139 +33,139 @@ namespace Language_hr { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Croatian"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Croatian"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" spreman."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD kartica umetnuta"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD kartica uklonjena"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Main"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto pokretanje"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Ugasi steppere"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Automatski homing"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home-aj X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home-aj Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home-aj Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Home-aj XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klikni za početak"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Sljedeća točka"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Niveliranje gotovo!"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Postavi home offsete"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets postavljeni"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Postavi ishodište"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" spreman."); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD kartica umetnuta"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD kartica uklonjena"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Main"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto pokretanje"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Ugasi steppere"); + LSTR MSG_AUTO_HOME = _UxGT("Automatski homing"); + LSTR MSG_AUTO_HOME_X = _UxGT("Home-aj X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Home-aj Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Home-aj Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Home-aj XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klikni za početak"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Sljedeća točka"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Niveliranje gotovo!"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Postavi home offsete"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets postavljeni"); + LSTR MSG_SET_ORIGIN = _UxGT("Postavi ishodište"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Predgrij ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Predgrij ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Dizna"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Dizna ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Sve"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Bed"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Predgrij ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Predgrij ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Dizna"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Dizna ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Sve"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" Bed"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Predgrij ") PREHEAT_1_LABEL _UxGT(" conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Predgrij $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Predgrij $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Predgrij $ Dizna"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Predgrij $ Dizna ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Predgrij $ Sve"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Predgrij $ Bed"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Predgrij $ conf"); + LSTR MSG_PREHEAT_M = _UxGT("Predgrij $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Predgrij $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Predgrij $ Dizna"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Predgrij $ Dizna ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Predgrij $ Sve"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Predgrij $ Bed"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Predgrij $ conf"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Hlađenje"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Uključi napajanje"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Isključi napajanje"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Miči os"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Niveliraj bed"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveliraj bed"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Miči X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Miči Y"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Miči %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Miči 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Miči 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Miči 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Brzina"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dizna"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dizna ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Bed"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Brzina ventilatora"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Brzina ventilatora ~"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Odaberi"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Odaberi *"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Gibanje"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD-a"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Pohrani u memoriju"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Učitaj memoriju"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Učitaj Defaults"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Osvježi"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info screen"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Pripremi"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pauziraj print"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Nastavi print"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Zaustavi print"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Printaj s SD kartice"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Nema SD kartice"); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Čekaj korisnika..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Print otkazan"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ZAUSTAVLJEN. "); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Promijeni filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Promijeni filament *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Init. SD karticu"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Promijeni SD karticu"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Grijanje neuspješno"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Grijanje..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Grijanje Bed-a..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibracija"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibriraj X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibriraj Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibriraj Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriraj Središte"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("O printeru"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Podaci o printeru"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statistika printera"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Podaci o elektronici"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistori"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderi"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvjetljenje"); + LSTR MSG_COOLDOWN = _UxGT("Hlađenje"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Uključi napajanje"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Isključi napajanje"); + LSTR MSG_MOVE_AXIS = _UxGT("Miči os"); + LSTR MSG_BED_LEVELING = _UxGT("Niveliraj bed"); + LSTR MSG_LEVEL_BED = _UxGT("Niveliraj bed"); + LSTR MSG_MOVE_X = _UxGT("Miči X"); + LSTR MSG_MOVE_Y = _UxGT("Miči Y"); + LSTR MSG_MOVE_N_MM = _UxGT("Miči %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Miči 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Miči 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Miči 100mm"); + LSTR MSG_SPEED = _UxGT("Brzina"); + LSTR MSG_BED_Z = _UxGT("Bed Z"); + LSTR MSG_NOZZLE = _UxGT("Dizna"); + LSTR MSG_NOZZLE_N = _UxGT("Dizna ~"); + LSTR MSG_BED = _UxGT("Bed"); + LSTR MSG_FAN_SPEED = _UxGT("Brzina ventilatora"); + LSTR MSG_FAN_SPEED_N = _UxGT("Brzina ventilatora ~"); + LSTR MSG_SELECT = _UxGT("Odaberi"); + LSTR MSG_SELECT_E = _UxGT("Odaberi *"); + LSTR MSG_TEMPERATURE = _UxGT("Temperature"); + LSTR MSG_MOTION = _UxGT("Gibanje"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_CONTRAST = _UxGT("Kontrast LCD-a"); + LSTR MSG_STORE_EEPROM = _UxGT("Pohrani u memoriju"); + LSTR MSG_LOAD_EEPROM = _UxGT("Učitaj memoriju"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Učitaj Defaults"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Osvježi"); + LSTR MSG_INFO_SCREEN = _UxGT("Info screen"); + LSTR MSG_PREPARE = _UxGT("Pripremi"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pauziraj print"); + LSTR MSG_RESUME_PRINT = _UxGT("Nastavi print"); + LSTR MSG_STOP_PRINT = _UxGT("Zaustavi print"); + LSTR MSG_MEDIA_MENU = _UxGT("Printaj s SD kartice"); + LSTR MSG_NO_MEDIA = _UxGT("Nema SD kartice"); + LSTR MSG_USERWAIT = _UxGT("Čekaj korisnika..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Print otkazan"); + LSTR MSG_STOPPED = _UxGT("ZAUSTAVLJEN. "); + LSTR MSG_FILAMENTCHANGE = _UxGT("Promijeni filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Promijeni filament *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Init. SD karticu"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Promijeni SD karticu"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Grijanje neuspješno"); + LSTR MSG_HEATING = _UxGT("Grijanje..."); + LSTR MSG_BED_HEATING = _UxGT("Grijanje Bed-a..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibracija"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibriraj X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibriraj Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibriraj Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriraj Središte"); + LSTR MSG_INFO_MENU = _UxGT("O printeru"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Podaci o printeru"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Statistika printera"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Podaci o elektronici"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistori"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extruderi"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokol"); + LSTR MSG_CASE_LIGHT = _UxGT("Osvjetljenje"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Neispravan pisač"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Neispravan pisač"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Broj printova"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Završeni"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Ukupno printanja"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najduži print"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudirano ukupno"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Broj printova"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Završeni"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Ukupno printanja"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najduži print"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudirano ukupno"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Printovi"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Završeni"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Ukupno"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najduži"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudirano"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Printovi"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Završeni"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Ukupno"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najduži"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrudirano"); #endif - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Napajanje"); + LSTR MSG_INFO_PSU = _UxGT("Napajanje"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Nastavi print"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Nastavi print"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Čekaj", "filament unload")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Pričekaj", "filament load")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Nastavljam...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Čekaj", "filament unload")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Pričekaj", "filament load")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Nastavljam...")); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čekaj početak", "filamenta", "promijeni")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Umetni filament", "i pritisni tipku", "za nastavak...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čekaj početak", "filamenta", "promijeni")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Umetni filament", "i pritisni tipku", "za nastavak...")); #else // Up to 2 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT("Pričekaj..."); - //PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("?", "?")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT("Pričekaj..."); + //LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("?", "?")); #endif } diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 2b879a7d6f..83e58de158 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -36,709 +36,709 @@ namespace Language_hu { using namespace Language_en; // A fordítás az örökölt Amerikai Angol (English) karakterláncokat használja. - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Magyar"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Magyar"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Kész."); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("IGEN"); - PROGMEM Language_Str MSG_NO = _UxGT("NEM"); - PROGMEM Language_Str MSG_BACK = _UxGT("Vissza"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD-kártya hiba"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás"); - PROGMEM Language_Str MSG_MAIN = _UxGT(""); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("További beállítások"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguráció"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Fájl auto. futtatás"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motorok kikapcsolása"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Hiba Menü"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Haladás sáv teszt"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("X-Y-Z auto kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z kezdöpont"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Kezdö ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Kezdö ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Kezdö ") LCD_STR_K; - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-igazítás"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ismétlés: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Pontosság csökken!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Pontosság elérve"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("X-Y-Z kezdöpont"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kattints a kezdéshez."); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Következö pont"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés kész!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint csökkentés"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Eredeti választása"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Utolsó érték "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Kész."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("IGEN"); + LSTR MSG_NO = _UxGT("NEM"); + LSTR MSG_BACK = _UxGT("Vissza"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva"); + LSTR MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); + LSTR MSG_SD_INIT_FAIL = _UxGT("SD-kártya hiba"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás"); + LSTR MSG_MAIN = _UxGT(""); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("További beállítások"); + LSTR MSG_CONFIGURATION = _UxGT("Konfiguráció"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Fájl auto. futtatás"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Motorok kikapcsolása"); + LSTR MSG_DEBUG_MENU = _UxGT("Hiba Menü"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Haladás sáv teszt"); + LSTR MSG_AUTO_HOME = _UxGT("X-Y-Z auto kezdöpont"); + LSTR MSG_AUTO_HOME_X = _UxGT("X kezdöpont"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Y kezdöpont"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Z kezdöpont"); + LSTR MSG_AUTO_HOME_I = _UxGT("Kezdö ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Kezdö ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Kezdö ") LCD_STR_K; + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-igazítás"); + LSTR MSG_ITERATION = _UxGT("G34 Ismétlés: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Pontosság csökken!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Pontosság elérve"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("X-Y-Z kezdöpont"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Kattints a kezdéshez."); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Következö pont"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Szintezés kész!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Szint csökkentés"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); + LSTR MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); + LSTR MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); + LSTR MSG_SET_ORIGIN = _UxGT("Eredeti Be"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Eredeti választása"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Utolsó érték "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Fütés ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Fütés ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Mind"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Ágy"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Beáll"); + LSTR MSG_PREHEAT_1 = _UxGT("Fütés ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Fütés ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Mind"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Ágy"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Beáll"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Fütés $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Fütés $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Fütés $ Fej"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Fütés $ Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Fütés $ Mind"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Fütés $ Ágy"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Fütés $ Beáll"); + LSTR MSG_PREHEAT_M = _UxGT("Fütés $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Fütés $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Fütés $ Fej"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Fütés $ Fej ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Fütés $ Mind"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Fütés $ Ágy"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Fütés $ Beáll"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi elömelegítés"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Visszahütés"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Egyedi elömelegítés"); + LSTR MSG_COOLDOWN = _UxGT("Visszahütés"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lézer vezérlés"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Orsó vezérlés"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer telj."); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó telj."); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Lézer váltás"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Hütés váltás"); - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Levegö segéd"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Impulzus teszt ms"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Tüz impulzus"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Áramlási hiba"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Orsóváltás"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vákuum váltás"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó elöre"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó hátra"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Adagol"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Visszahúz"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Tengelyek mozgatása"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Ágy szintezés"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Ágy szintezése"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Sarok szint"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Ágy emelése a szonda váltásig"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Jó pontok: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Utolsó Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Következö sarok"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Háló szerkesztö"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Háló szerkesztése"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Háló szerk. állj"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Próbapont"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z érték"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Egyéni parancs"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Szonda teszt"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Pont"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Szonda határon kívül"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Eltérés"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX mód"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Eszköz eltolás"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Automata parkolás"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikálás"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Tükrözött másolás"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Teljes felügyelet"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("X-hézag másolása"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. fej X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. fej Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. fej Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Szintezz! G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL eszköz"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési pont"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi háló építés"); - PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Háló varázsló"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Továbblépés"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktívál"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktívál"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy höfok"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Egyéni ágy höfok"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fejhöfok"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Egyéni fejhöfok"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló szerkesztés"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni háló szerkesztés"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított háló"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Háló kész"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Egyéni háló építés"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Háló építés"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Háló építés ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Hideg háló építés"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Háló magasság állítás"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Magasság összege"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Háló elfogadás"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Háló elfogadás ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valódi háló elfogadása"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Ágy fütés"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Fej fütés"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Kézi alapozás..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Fix hosszúságú alap"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Alapozás kész"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Törölve"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Kilépö G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Ágy háló folyt."); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Háló szintezés"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Pontos szintezés"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rács szintezés"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Háló szint"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Oldal pontok"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Térkép típus"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Háló térkép kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV kimenet"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Nyomtató bizt.mentés"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL infó kimenet"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Kitöltési költség"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Kézi kitöltés"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Okos kitöltés"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Háló kitöltés"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Minden érvénytelen"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Közelebbi érvénytelen"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Mindet finomhangolja"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Közelebbi finomhangolása"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Háló tárolás"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memória foglalat"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ágy háló betöltés"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Ágy háló mentés"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Háló %i betöltve"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Háló %i mentve"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nincs tároló"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hiba: UBL mentés"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hiba: UBL visszaáll."); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-eltolás: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-eltolás leállítva"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Lépésröl lépésre UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Hideg háló készítés"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligens kitöltés"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Háló érvényesítés"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Minden finomítása"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Háló érvényesítés"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Minden finomítása"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Ágy háló mentése"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); + LSTR MSG_LASER_MENU = _UxGT("Lézer vezérlés"); + LSTR MSG_SPINDLE_MENU = _UxGT("Orsó vezérlés"); + LSTR MSG_LASER_POWER = _UxGT("Lézer telj."); + LSTR MSG_SPINDLE_POWER = _UxGT("Orsó telj."); + LSTR MSG_LASER_TOGGLE = _UxGT("Lézer váltás"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Hütés váltás"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Levegö segéd"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Impulzus teszt ms"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Tüz impulzus"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Áramlási hiba"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Orsóváltás"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vákuum váltás"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Orsó elöre"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Orsó hátra"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); + LSTR MSG_EXTRUDE = _UxGT("Adagol"); + LSTR MSG_RETRACT = _UxGT("Visszahúz"); + LSTR MSG_MOVE_AXIS = _UxGT("Tengelyek mozgatása"); + LSTR MSG_BED_LEVELING = _UxGT("Ágy szintezés"); + LSTR MSG_LEVEL_BED = _UxGT("Ágy szintezése"); + LSTR MSG_BED_TRAMMING = _UxGT("Sarok szint"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Ágy emelése a szonda váltásig"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Minden sarok tolerancián belül. Szint jó."); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Jó pontok: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Utolsó Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Következö sarok"); + LSTR MSG_MESH_EDITOR = _UxGT("Háló szerkesztö"); + LSTR MSG_EDIT_MESH = _UxGT("Háló szerkesztése"); + LSTR MSG_EDITING_STOPPED = _UxGT("Háló szerk. állj"); + LSTR MSG_PROBING_POINT = _UxGT("Próbapont"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z érték"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Egyéni parancs"); + LSTR MSG_M48_TEST = _UxGT("M48 Szonda teszt"); + LSTR MSG_M48_POINT = _UxGT("M48 Pont"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Szonda határon kívül"); + LSTR MSG_M48_DEVIATION = _UxGT("Eltérés"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX mód"); + LSTR MSG_OFFSETS_MENU = _UxGT("Eszköz eltolás"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Automata parkolás"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikálás"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Tükrözött másolás"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Teljes felügyelet"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("X-hézag másolása"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. fej X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. fej Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. fej Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Szintezz! G29"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL eszköz"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Döntési pont"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Kézi háló építés"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Háló varázsló"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Továbblépés"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktívál"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktívál"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Ágy höfok"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Egyéni ágy höfok"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fejhöfok"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Egyéni fejhöfok"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Háló szerkesztés"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni háló szerkesztés"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított háló"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Háló kész"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Egyéni háló építés"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Háló építés"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Háló építés ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Hideg háló építés"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Háló magasság állítás"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Magasság összege"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Háló elfogadás"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Háló elfogadás ($)"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valódi háló elfogadása"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Ágy fütés"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Fej fütés"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Kézi alapozás..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fix hosszúságú alap"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Alapozás kész"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Törölve"); + LSTR MSG_G26_LEAVING = _UxGT("Kilépö G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Ágy háló folyt."); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Háló szintezés"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Pontos szintezés"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rács szintezés"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Háló szint"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Oldal pontok"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Térkép típus"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Háló térkép kimenet"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host kimenet"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV kimenet"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Nyomtató bizt.mentés"); + LSTR MSG_UBL_INFO_UBL = _UxGT("UBL infó kimenet"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Kitöltési költség"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Kézi kitöltés"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Okos kitöltés"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Háló kitöltés"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Minden érvénytelen"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Közelebbi érvénytelen"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Mindet finomhangolja"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Közelebbi finomhangolása"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Háló tárolás"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Memória foglalat"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Ágy háló betöltés"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Ágy háló mentés"); + LSTR MSG_MESH_LOADED = _UxGT("M117 Háló %i betöltve"); + LSTR MSG_MESH_SAVED = _UxGT("M117 Háló %i mentve"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Nincs tároló"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Hiba: UBL mentés"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Hiba: UBL visszaáll."); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-eltolás: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-eltolás leállítva"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Lépésröl lépésre UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Hideg háló készítés"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligens kitöltés"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Háló érvényesítés"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Minden finomítása"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Háló érvényesítés"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Minden finomítása"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Ágy háló mentése"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED vezérlés"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Világítás"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított színek"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Piros"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Zöld"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Kék"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigó"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Fehér"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("LED-ek #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni szín"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék intenzitás"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Fehér intenzitás"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Fényerö"); + LSTR MSG_LED_CONTROL = _UxGT("LED vezérlés"); + LSTR MSG_LEDS = _UxGT("Világítás"); + LSTR MSG_LED_PRESETS = _UxGT("Beállított színek"); + LSTR MSG_SET_LEDS_RED = _UxGT("Piros"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Zöld"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Kék"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigó"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Viola"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Fehér"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); + LSTR MSG_LEDS2 = _UxGT("LED-ek #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Egyéni szín"); + LSTR MSG_INTENSITY_R = _UxGT("Piros intenzitás"); + LSTR MSG_INTENSITY_G = _UxGT("Zöld intenzitás"); + LSTR MSG_INTENSITY_B = _UxGT("Kék intenzitás"); + LSTR MSG_INTENSITY_W = _UxGT("Fehér intenzitás"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Fényerö"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Mozgás..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY szabad"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("X mozgás"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y mozgás"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z mozgás"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Mozgás ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Mozgás ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Mozgás ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Adagoló"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Adagoló *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mozgás %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.025mm"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.254mm"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 2.54mm"); - PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Mozgáá 25.4mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Sebesség"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z ágy"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Fej"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Fej ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Fej parkolva"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Fej készenlétbe"); - PROGMEM Language_Str MSG_BED = _UxGT("Ágy"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Burkolat"); - PROGMEM Language_Str MSG_COOLER = _UxGT("Lézer hütövíz"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Hütö kapcsoló"); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); - PROGMEM Language_Str MSG_LASER = _UxGT("Lézer"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Hütés sebesség"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Tárolt hütés ="); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra hütés sebesség"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség ="); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Hütésvezérlés"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Alapjárat"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus mód"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív sebesség"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Készenlét"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Folyás"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Folyás ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Konfiguráció"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Minimum"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Maximum"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tényezö"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata höfok"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Be"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID hangolás"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID hangolás *"); - PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("PID ciklus"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); - 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("Kiválaszt"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); - PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Seb.") LCD_STR_A _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Seb.") LCD_STR_B _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Seb.") LCD_STR_C _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Seb.") LCD_STR_I _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Seb.") LCD_STR_J _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Seb.") LCD_STR_K _UxGT("-Rántás"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("E ránt. seb."); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Seb. ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Max Seb. ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Max Seb. ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Max Seb. ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Max Seb. ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Max Seb. ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Seb. ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max sebesség *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Min sebesség"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Gyorsulás"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max gyors. ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max gyors. ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max gyors. ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max gyors. ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max gyors. ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max gyors. ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max gyors. ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max gyorsulás *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Visszahúzás"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Utazás"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max frekvencia"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min elötolás"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Lépés/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*Lépés/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Mozgatások"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Nyomtatószál"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E mm³-ben"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit mm³-ben"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Szál. átm."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Szál. átm. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Kiadás mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Betöltés mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Haladó K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Haladó K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontraszt"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Mentés EEPROM"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM inicializálás"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Hiba: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM verzió"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások mentve"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló frissítés"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató újraindítása"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT(""); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Vezérlés"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Hangolás"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Teljesítménymonitor"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Jelenlegi"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Feszültség"); - PROGMEM Language_Str MSG_POWER = _UxGT("Energia"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás indítása"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Tovább"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Kezdet"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Állj"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Nyomtatás"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Újraindítás"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Mellöz"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Mégse"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Kész"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Vissza"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Folytatás"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Kihagy"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Szüneteltetve..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Nyomtatás szünetelés"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Nyomtatás folytatása"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Hoszt indítás"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Nyomtatás leállítása"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Hurok ismétlés vége"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objektum nyomtatása"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objektum törlése"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objektum törlése ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Kiesés helyreáll."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Nyomtatás tárolóról"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Nincs tároló"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Alvás..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Katt a folytatáshoz..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Nyomtatás szünetelve"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Nyomtatás..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Nyomtatás leállítva"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Nyomtatás kész"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nincs mozgás."); - PROGMEM Language_Str MSG_KILLED = _UxGT("HALOTT! "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("MEGÁLLT! "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Visszahúzás mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Visszahúzás cs. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Viszahúzás"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Ugrás mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Visszah.helyre mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Csere.visszah.helyre mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Visszahúzás V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S Vissza.h V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto visszah."); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás távolság"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra csere"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási távolság"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z emelés"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Fösebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. sebesség"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej parkolás"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszav.visszah. sebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN sebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("FAN idö"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto BE"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto KI"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Szerszámcsere"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata csere"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Utolsó adagoló"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Csere *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szálcsere"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szálcsere *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Szál betöltés *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Szál eltávolítás"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Szál eltávolítás *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Mindet eltávolít"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Tároló"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Tároló csere"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Tároló Kiadása"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z szonda tálcán kivül"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Ferdeség faktor"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Önteszt"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Visszaállítás"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Elhelyez"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Telepít"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mód"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mód"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mód"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Módok"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V mód"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD mód"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Jelentés"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("VESZÉLY: A rossz beállítások kárt okozhatnak! Biztos továbblép?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Kezd TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z eltolás teszt"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Mentés"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI használ"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Szonda telepítés"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Szonda elhelyezés"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Elöször %s%s%s kell"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Szonda eltolások"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X szonda eltolás"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y szonda eltolás"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z szonda eltolás"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Fej az ágyhoz"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Mikrolépés ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Mikrolépés ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Mikrolépés ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Hiba: SZÜKSÉGTELEN HÖFOK"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FÜTÉS KIMARADÁS"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ÁGY FÜTÉS KIMARADÁS"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Hütés kimaradás"); - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Hütés sikertelen"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX höfok"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hiba: MIN höfok"); - PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEÁLLT"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("ó"); // Csak egy karakter - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("p"); // Csak egy karakter - PROGMEM Language_Str MSG_HEATING = _UxGT("Fütés..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Hütés..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Ágy fütés..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Ágy hütés..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Szonda fütése..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Szonda hütése..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Kamra fütés..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Kamra hütés..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Lézer hütés..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibráció"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("X kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Y kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Z kalibrálás"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ kalibrálás"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta beállítások"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibráció"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta magasság kalib."); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z eltolás"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag rúd"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Magasság"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Sugár"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("A Nyomtatóról"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Nyomtató infó"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Pontos szintezés"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló szintezés"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Háló szintezés kész"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Adagolók"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Futáselemzés: BE"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Fej üresjárati idök."); + LSTR MSG_MOVING = _UxGT("Mozgás..."); + LSTR MSG_FREE_XY = _UxGT("XY szabad"); + LSTR MSG_MOVE_X = _UxGT("X mozgás"); + LSTR MSG_MOVE_Y = _UxGT("Y mozgás"); + LSTR MSG_MOVE_Z = _UxGT("Z mozgás"); + LSTR MSG_MOVE_I = _UxGT("Mozgás ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Mozgás ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Mozgás ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Adagoló"); + LSTR MSG_MOVE_EN = _UxGT("Adagoló *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); + LSTR MSG_MOVE_N_MM = _UxGT("Mozgás %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Mozgás 0.025mm"); + LSTR MSG_MOVE_001IN = _UxGT("Mozgás 0.254mm"); + LSTR MSG_MOVE_01IN = _UxGT("Mozgás 2.54mm"); + LSTR MSG_MOVE_1IN = _UxGT("Mozgáá 25.4mm"); + LSTR MSG_SPEED = _UxGT("Sebesség"); + LSTR MSG_BED_Z = _UxGT("Z ágy"); + LSTR MSG_NOZZLE = _UxGT("Fej"); + LSTR MSG_NOZZLE_N = _UxGT("Fej ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Fej parkolva"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Fej készenlétbe"); + LSTR MSG_BED = _UxGT("Ágy"); + LSTR MSG_CHAMBER = _UxGT("Burkolat"); + LSTR MSG_COOLER = _UxGT("Lézer hütövíz"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Hütö kapcsoló"); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); + LSTR MSG_LASER = _UxGT("Lézer"); + LSTR MSG_FAN_SPEED = _UxGT("Hütés sebesség"); + LSTR MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); + LSTR MSG_STORED_FAN_N = _UxGT("Tárolt hütés ="); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra hütés sebesség"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség ="); + LSTR MSG_CONTROLLER_FAN = _UxGT("Hütésvezérlés"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Alapjárat"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus mód"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív sebesség"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Készenlét"); + LSTR MSG_FLOW = _UxGT("Folyás"); + LSTR MSG_FLOW_N = _UxGT("Folyás ~"); + LSTR MSG_CONTROL = _UxGT("Konfiguráció"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Minimum"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Maximum"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tényezö"); + LSTR MSG_AUTOTEMP = _UxGT("Automata höfok"); + LSTR MSG_LCD_ON = _UxGT("Be"); + LSTR MSG_LCD_OFF = _UxGT("Ki"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID hangolás"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID hangolás *"); + LSTR MSG_PID_CYCLE = _UxGT("PID ciklus"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); + LSTR MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); + LSTR MSG_PID_P = _UxGT("PID-P"); + LSTR MSG_PID_P_E = _UxGT("PID-P *"); + LSTR MSG_PID_I = _UxGT("PID-I"); + LSTR MSG_PID_I_E = _UxGT("PID-I *"); + LSTR MSG_PID_D = _UxGT("PID-D"); + LSTR MSG_PID_D_E = _UxGT("PID-D *"); + LSTR MSG_PID_C = _UxGT("PID-C"); + LSTR MSG_PID_C_E = _UxGT("PID-C *"); + LSTR MSG_PID_F = _UxGT("PID-F"); + LSTR MSG_PID_F_E = _UxGT("PID-F *"); + LSTR MSG_SELECT = _UxGT("Kiválaszt"); + LSTR MSG_SELECT_E = _UxGT("Kiválaszt *"); + LSTR MSG_ACC = _UxGT("Gyorsítás"); + LSTR MSG_JERK = _UxGT("Rántás"); + LSTR MSG_VA_JERK = _UxGT("Seb.") LCD_STR_A _UxGT("-Rántás"); + LSTR MSG_VB_JERK = _UxGT("Seb.") LCD_STR_B _UxGT("-Rántás"); + LSTR MSG_VC_JERK = _UxGT("Seb.") LCD_STR_C _UxGT("-Rántás"); + LSTR MSG_VI_JERK = _UxGT("Seb.") LCD_STR_I _UxGT("-Rántás"); + LSTR MSG_VJ_JERK = _UxGT("Seb.") LCD_STR_J _UxGT("-Rántás"); + LSTR MSG_VK_JERK = _UxGT("Seb.") LCD_STR_K _UxGT("-Rántás"); + LSTR MSG_VE_JERK = _UxGT("E ránt. seb."); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); + LSTR MSG_VELOCITY = _UxGT("Sebesség"); + LSTR MSG_VMAX_A = _UxGT("Max Seb. ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Max Seb. ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Max Seb. ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Max Seb. ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Max Seb. ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Max Seb. ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Max Seb. ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Max sebesség *"); + LSTR MSG_VMIN = _UxGT("Min sebesség"); + LSTR MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); + LSTR MSG_ACCELERATION = _UxGT("Gyorsulás"); + LSTR MSG_AMAX_A = _UxGT("Max gyors. ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Max gyors. ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Max gyors. ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Max gyors. ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Max gyors. ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Max gyors. ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Max gyors. ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Max gyorsulás *"); + LSTR MSG_A_RETRACT = _UxGT("Visszahúzás"); + LSTR MSG_A_TRAVEL = _UxGT("Utazás"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max frekvencia"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min elötolás"); + LSTR MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Lépés/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Lépés/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Lépés/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Lépés/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Lépés/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Lépés/mm"); + LSTR MSG_E_STEPS = _UxGT("E lépés/mm"); + LSTR MSG_EN_STEPS = _UxGT("*Lépés/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Höfok"); + LSTR MSG_MOTION = _UxGT("Mozgatások"); + LSTR MSG_FILAMENT = _UxGT("Nyomtatószál"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E mm³-ben"); + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit mm³-ben"); + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Szál. átm."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Szál. átm. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Kiadás mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Betöltés mm"); + LSTR MSG_ADVANCE_K = _UxGT("Haladó K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Haladó K *"); + LSTR MSG_CONTRAST = _UxGT("LCD kontraszt"); + LSTR MSG_STORE_EEPROM = _UxGT("Mentés EEPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); + LSTR MSG_INIT_EEPROM = _UxGT("EEPROM inicializálás"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Hiba: EEPROM CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM index"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM verzió"); + LSTR MSG_SETTINGS_STORED = _UxGT("Beállítások mentve"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Tároló frissítés"); + LSTR MSG_RESET_PRINTER = _UxGT("Nyomtató újraindítása"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); + LSTR MSG_INFO_SCREEN = _UxGT(""); + LSTR MSG_PREPARE = _UxGT("Vezérlés"); + LSTR MSG_TUNE = _UxGT("Hangolás"); + LSTR MSG_POWER_MONITOR = _UxGT("Teljesítménymonitor"); + LSTR MSG_CURRENT = _UxGT("Jelenlegi"); + LSTR MSG_VOLTAGE = _UxGT("Feszültség"); + LSTR MSG_POWER = _UxGT("Energia"); + LSTR MSG_START_PRINT = _UxGT("Nyomtatás indítása"); + LSTR MSG_BUTTON_NEXT = _UxGT("Tovább"); + LSTR MSG_BUTTON_INIT = _UxGT("Kezdet"); + LSTR MSG_BUTTON_STOP = _UxGT("Állj"); + LSTR MSG_BUTTON_PRINT = _UxGT("Nyomtatás"); + LSTR MSG_BUTTON_RESET = _UxGT("Újraindítás"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Mellöz"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Mégse"); + LSTR MSG_BUTTON_DONE = _UxGT("Kész"); + LSTR MSG_BUTTON_BACK = _UxGT("Vissza"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Folytatás"); + LSTR MSG_BUTTON_SKIP = _UxGT("Kihagy"); + LSTR MSG_PAUSING = _UxGT("Szüneteltetve..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Nyomtatás szünetelés"); + LSTR MSG_RESUME_PRINT = _UxGT("Nyomtatás folytatása"); + LSTR MSG_HOST_START_PRINT = _UxGT("Hoszt indítás"); + LSTR MSG_STOP_PRINT = _UxGT("Nyomtatás leállítása"); + LSTR MSG_END_LOOPS = _UxGT("Hurok ismétlés vége"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Objektum nyomtatása"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Objektum törlése"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objektum törlése ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Kiesés helyreáll."); + LSTR MSG_MEDIA_MENU = _UxGT("Nyomtatás tárolóról"); + LSTR MSG_NO_MEDIA = _UxGT("Nincs tároló"); + LSTR MSG_DWELL = _UxGT("Alvás..."); + LSTR MSG_USERWAIT = _UxGT("Katt a folytatáshoz..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Nyomtatás szünetelve"); + LSTR MSG_PRINTING = _UxGT("Nyomtatás..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Nyomtatás leállítva"); + LSTR MSG_PRINT_DONE = _UxGT("Nyomtatás kész"); + LSTR MSG_NO_MOVE = _UxGT("Nincs mozgás."); + LSTR MSG_KILLED = _UxGT("HALOTT! "); + LSTR MSG_STOPPED = _UxGT("MEGÁLLT! "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Visszahúzás mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Visszahúzás cs. mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Viszahúzás"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Ugrás mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Visszah.helyre mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Csere.visszah.helyre mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Visszahúzás V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S Vissza.h V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto visszah."); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás távolság"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra csere"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási távolság"); + LSTR MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z emelés"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Fösebesség"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. sebesség"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej parkolás"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszav.visszah. sebesség"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN sebesség"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("FAN idö"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto BE"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto KI"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Szerszámcsere"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata csere"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Utolsó adagoló"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Csere *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Szálcsere"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Szálcsere *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Szál betöltés *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Szál eltávolítás"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Szál eltávolítás *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Mindet eltávolít"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Tároló"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Tároló csere"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Tároló Kiadása"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z szonda tálcán kivül"); + LSTR MSG_SKEW_FACTOR = _UxGT("Ferdeség faktor"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Önteszt"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Visszaállítás"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Elhelyez"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Telepít"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mód"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mód"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mód"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Módok"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V mód"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD mód"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Jelentés"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("VESZÉLY: A rossz beállítások kárt okozhatnak! Biztos továbblép?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Kezd TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z eltolás teszt"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Mentés"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI használ"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Z-Szonda telepítés"); + LSTR MSG_MANUAL_STOW = _UxGT("Z-Szonda elhelyezés"); + LSTR MSG_HOME_FIRST = _UxGT("Elöször %s%s%s kell"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Szonda eltolások"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("X szonda eltolás"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Y szonda eltolás"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z szonda eltolás"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Fej az ágyhoz"); + LSTR MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Mikrolépés ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Mikrolépés ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Mikrolépés ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Hiba: SZÜKSÉGTELEN HÖFOK"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("FÜTÉS KIMARADÁS"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ÁGY FÜTÉS KIMARADÁS"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Hütés kimaradás"); + LSTR MSG_COOLING_FAILED = _UxGT("Hütés sikertelen"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX höfok"); + LSTR MSG_ERR_MINTEMP = _UxGT("Hiba: MIN höfok"); + LSTR MSG_HALTED = _UxGT("A NYOMTATÓ LEÁLLT"); + LSTR MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); + LSTR MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter + LSTR MSG_SHORT_HOUR = _UxGT("ó"); // Csak egy karakter + LSTR MSG_SHORT_MINUTE = _UxGT("p"); // Csak egy karakter + LSTR MSG_HEATING = _UxGT("Fütés..."); + LSTR MSG_COOLING = _UxGT("Hütés..."); + LSTR MSG_BED_HEATING = _UxGT("Ágy fütés..."); + LSTR MSG_BED_COOLING = _UxGT("Ágy hütés..."); + LSTR MSG_PROBE_HEATING = _UxGT("Szonda fütése..."); + LSTR MSG_PROBE_COOLING = _UxGT("Szonda hütése..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Kamra fütés..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Kamra hütés..."); + LSTR MSG_LASER_COOLING = _UxGT("Lézer hütés..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta kalibráció"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("X kalibrálás"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Y kalibrálás"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Z kalibrálás"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ kalibrálás"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta beállítások"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibráció"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta magasság kalib."); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z eltolás"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rúd"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Magasság"); + LSTR MSG_DELTA_RADIUS = _UxGT("Sugár"); + LSTR MSG_INFO_MENU = _UxGT("A Nyomtatóról"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Nyomtató infó"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-Pontos szintezés"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); + LSTR MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); + LSTR MSG_MESH_LEVELING = _UxGT("Háló szintezés"); + LSTR MSG_MESH_DONE = _UxGT("Háló szintezés kész"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Adagolók"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokol"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Futáselemzés: BE"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Fej üresjárati idök."); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Munkalámpa"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); + LSTR MSG_CASE_LIGHT = _UxGT("Munkalámpa"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás számláló"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Összes nyomtatási idö"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb munkaidö"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Összes anyag"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás számláló"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Összes nyomtatási idö"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb munkaidö"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Összes anyag"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatások"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Összes"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Kiadott"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatások"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Összes"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Leghosszabb"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Kiadott"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min höfok"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Meghajtó %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("NYOMTATÓSZÁL CSERE"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("NYOMTATÁS SZÜNETEL"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("SZÁL BETÖLTÉS"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("SZÁL ELTÁVOLÍTÁS"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FOLYTATÁSI OPCIÓ:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Tisztítsd meg"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Folytatás"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fej: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Túlfutás szenzor"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás táv. mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Tájolási hiba"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min höfok"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("NYOMTATÓSZÁL CSERE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("NYOMTATÁS SZÜNETEL"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("SZÁL BETÖLTÉS"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("SZÁL ELTÁVOLÍTÁS"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FOLYTATÁSI OPCIÓ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Tisztítsd meg"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Folytatás"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Fej: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Túlfutás szenzor"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás táv. mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Tájolási hiba"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU szoftver feltöltése!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU figyelmeztetés."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Nyomtatás folytatása"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Folytatás..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál betöltése"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes betöltése"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fej betöltése"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kidobás"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kidobás ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kidobás. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Mind"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU újraindítás"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU újraindul..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU szoftver feltöltése!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU figyelmeztetés."); + LSTR MSG_MMU2_RESUME = _UxGT("Nyomtatás folytatása"); + LSTR MSG_MMU2_RESUMING = _UxGT("Folytatás..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál betöltése"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Összes betöltése"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fej betöltése"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kidobás"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kidobás ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kidobás. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); + LSTR MSG_MMU2_ALL = _UxGT("Mind"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); + LSTR MSG_MMU2_RESET = _UxGT("MMU újraindítás"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU újraindul..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); - PROGMEM Language_Str MSG_MIX = _UxGT("Kever"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Keverö"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Színátm."); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Teljes színátm."); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Váltás keverésre"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Ciklikus keverés"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Színátm. keverés"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Fordított színátm."); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktív V-szerszám"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Kezdés V-szerszám"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Vége V-szerszám"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Ál V-szerszám"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Újra V-szerszám"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Gyors V-szerszám Kev."); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-szersz. visszaáll."); - PROGMEM Language_Str MSG_START_Z = _UxGT("Kezdés Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Vége Z:"); + LSTR MSG_MIX = _UxGT("Kever"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); + LSTR MSG_MIXER = _UxGT("Keverö"); + LSTR MSG_GRADIENT = _UxGT("Színátm."); + LSTR MSG_FULL_GRADIENT = _UxGT("Teljes színátm."); + LSTR MSG_TOGGLE_MIX = _UxGT("Váltás keverésre"); + LSTR MSG_CYCLE_MIX = _UxGT("Ciklikus keverés"); + LSTR MSG_GRADIENT_MIX = _UxGT("Színátm. keverés"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Fordított színátm."); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktív V-szerszám"); + LSTR MSG_START_VTOOL = _UxGT("Kezdés V-szerszám"); + LSTR MSG_END_VTOOL = _UxGT(" Vége V-szerszám"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Ál V-szerszám"); + LSTR MSG_RESET_VTOOLS = _UxGT("Újra V-szerszám"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Gyors V-szerszám Kev."); + LSTR MSG_VTOOLS_RESET = _UxGT("V-szersz. visszaáll."); + LSTR MSG_START_Z = _UxGT("Kezdés Z:"); + LSTR MSG_END_Z = _UxGT(" Vége Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Játékok"); - 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"); + LSTR MSG_GAMES = _UxGT("Játékok"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Rossz oldalindex"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Rossz oldalsebesség"); + LSTR MSG_BAD_PAGE = _UxGT("Rossz oldalindex"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Rossz oldalsebesség"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Jelszó szerkesztése"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Belépés szükséges"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Jelszóbeállítások"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Írja be a számokat"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Jelszó Beáll/Szerk"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Jelszó törlése"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("A jelszó "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Újrakezdés"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Mentsd el!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Jelszó törölve"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Jelszó szerkesztése"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Belépés szükséges"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Jelszóbeállítások"); + LSTR MSG_ENTER_DIGIT = _UxGT("Írja be a számokat"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Jelszó Beáll/Szerk"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Jelszó törlése"); + LSTR MSG_PASSWORD_SET = _UxGT("A jelszó "); + LSTR MSG_START_OVER = _UxGT("Újrakezdés"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Mentsd el!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Jelszó törölve"); // // 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("Nyomj gombot", "nyomtatás folytatáshoz")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szálcsere", "indítás")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Szál behelyezés", "majd nyomj gombot", "a folytatáshoz")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fej fütéséhez")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Fej fütése", "Kérlek várj...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Várj a", "szál kiadására")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd folytat...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nyomj gombot", "nyomtatás folytatáshoz")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Várj míg", "szálcsere", "indítás")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Szál behelyezés", "majd nyomj gombot", "a folytatáshoz")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nyomj gombot", "a fej fütéséhez")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Fej fütése", "Kérlek várj...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Várj a", "szál kiadására")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd folytat...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek várj...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Behelyez majd katt")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fütéshez")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Fütés...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Kiadás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Betöltés...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Tisztítás...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Katt ha kész")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Folytatás...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Kérlek várj...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Behelyez majd katt")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Katt a fütéshez")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Fütés...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Kiadás...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Betöltés...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Tisztítás...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Katt ha kész")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Folytatás...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC meghajtók"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Meghajtó áram"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid küszöbérték"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros kezdöpont"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö mód"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop mód"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Újraindítás"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" be:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Holtjáték"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC meghajtók"); + LSTR MSG_TMC_CURRENT = _UxGT("Meghajtó áram"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hibrid küszöbérték"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Motoros kezdöpont"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Léptetö mód"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop mód"); + LSTR MSG_SERVICE_RESET = _UxGT("Újraindítás"); + LSTR MSG_SERVICE_IN = _UxGT(" be:"); + LSTR MSG_BACKLASH = _UxGT("Holtjáték"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X tengely szint"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Önkalibrálás"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("X tengely szint"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Önkalibrálás"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Tétlenségi idökorlát, a hömérséklet csökkent. Nyomd meg az OK gombot az ismételt felfütéshez, és újra a folytatáshoz."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Tétlenségi idökorlát, a hömérséklet csökkent. Nyomd meg az OK gombot az ismételt felfütéshez, és újra a folytatáshoz."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Fütés idökorlátja"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Fütés idökorlátja"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Újrafüt"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Újrafütés..."); + LSTR MSG_REHEAT = _UxGT("Újrafüt"); + LSTR MSG_REHEATING = _UxGT("Újrafütés..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z szonda varázsló"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Z referencia mérés"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Menj a próba pontra"); + LSTR MSG_PROBE_WIZARD = _UxGT("Z szonda varázsló"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Z referencia mérés"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Menj a próba pontra"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Hang"); + LSTR MSG_SOUND = _UxGT("Hang"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Bal felsö"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bal alsó"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Jobb felsö"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Jobb alsó"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrálás befejezve"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); + LSTR MSG_TOP_LEFT = _UxGT("Bal felsö"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Bal alsó"); + LSTR MSG_TOP_RIGHT = _UxGT("Jobb felsö"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Jobb alsó"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrálás befejezve"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Kártya"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Lemez"); + LSTR MSG_SD_CARD = _UxGT("SD Kártya"); + LSTR MSG_USB_DISK = _UxGT("USB Lemez"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 388498fe8f..c8ee795e61 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -40,701 +40,701 @@ namespace Language_it { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Italiano"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Italiano"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("Si"); - PROGMEM Language_Str MSG_NO = _UxGT("No"); - PROGMEM Language_Str MSG_BACK = _UxGT("Indietro"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Annullando..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media inserito"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Aspettando media"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Inizial.SD fallita"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow subchiamate"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principale"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configurazione"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu di debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterazione G34: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Precisione raggiunta"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Home assi XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Premi per iniziare"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Punto successivo"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Livel. terminato!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Imp. offset home"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Offset home X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Imposta Origine"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Selez. origine"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Ultimo valore "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("Si"); + LSTR MSG_NO = _UxGT("No"); + LSTR MSG_BACK = _UxGT("Indietro"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Media inserito"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); + LSTR MSG_MEDIA_WAITING = _UxGT("Aspettando media"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Inizial.SD fallita"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow subchiamate"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); + LSTR MSG_MAIN = _UxGT("Menu principale"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); + LSTR MSG_CONFIGURATION = _UxGT("Configurazione"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); + LSTR MSG_DEBUG_MENU = _UxGT("Menu di debug"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); + LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); + LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); + LSTR MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); + LSTR MSG_ITERATION = _UxGT("Iterazione G34: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Precisione raggiunta"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Home assi XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Premi per iniziare"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Punto successivo"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Livel. terminato!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Imp. offset home"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Offset home X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); + LSTR MSG_SET_ORIGIN = _UxGT("Imposta Origine"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Selez. origine"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Ultimo valore "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preriscalda ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preriscalda ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Ugello"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Ugello ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Tutto"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Piatto"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Preriscalda ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Preriscalda ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Ugello"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Ugello ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Tutto"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Piatto"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Preriscalda $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Preris.$ Ugello"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Preris.$ Ugello ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Preris.$ Tutto"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.$ Piatto"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.$ conf"); + LSTR MSG_PREHEAT_M = _UxGT("Preriscalda $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preris.$ Ugello"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preris.$ Ugello ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preris.$ Tutto"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.$ Piatto"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.$ conf"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Raffredda"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); + LSTR MSG_COOLDOWN = _UxGT("Raffredda"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenza"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Controllo laser"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Controllo mandrino"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potenza laser"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potenza mandrino"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Alterna Laser"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Alterna soffiatore"); - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Alterna aria supp."); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("ms impulso di test"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Spara impulso"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Err.flusso refrig."); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Alterna mandrino"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Alterna vuoto"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Mandrino in avanti"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Spegni aliment."); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Estrudi"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Ritrai"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muovi Asse"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Livella piano"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Livella piano"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Tramming piano"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finché la sonda non rileva il piano."); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Punti buoni: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Ultimo Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Prossimo punto"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Modifica Mesh"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punto sondato"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Indice X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indice Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valore di Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comandi personaliz."); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("Test sonda M48"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("Punto M48"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda oltre i limiti"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Deviazione"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Strumenti Offsets"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicazione"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia speculare"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pieno controllo"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("X-Gap-X duplicato"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2° ugello X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2° ugello Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2° ugello Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 in corso"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Strumenti UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); - PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Misura"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Rimuovi e mis.piatto"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Spostamento succes."); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Attiva UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Disattiva UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Piatto"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Piatto"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Ugello"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Ugello"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Modifica Mesh"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Modif.Mesh personal."); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Ritocca Mesh"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Modif.Mesh fatta"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crea Mesh personal."); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crea Mesh"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frequenza"); + LSTR MSG_LASER_MENU = _UxGT("Controllo laser"); + LSTR MSG_SPINDLE_MENU = _UxGT("Controllo mandrino"); + LSTR MSG_LASER_POWER = _UxGT("Potenza laser"); + LSTR MSG_SPINDLE_POWER = _UxGT("Potenza mandrino"); + LSTR MSG_LASER_TOGGLE = _UxGT("Alterna Laser"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Alterna soffiatore"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Alterna aria supp."); + LSTR MSG_LASER_PULSE_MS = _UxGT("ms impulso di test"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Spara impulso"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Err.flusso refrig."); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Alterna mandrino"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Alterna vuoto"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Mandrino in avanti"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Spegni aliment."); + LSTR MSG_EXTRUDE = _UxGT("Estrudi"); + LSTR MSG_RETRACT = _UxGT("Ritrai"); + LSTR MSG_MOVE_AXIS = _UxGT("Muovi Asse"); + LSTR MSG_BED_LEVELING = _UxGT("Livella piano"); + LSTR MSG_LEVEL_BED = _UxGT("Livella piano"); + LSTR MSG_BED_TRAMMING = _UxGT("Tramming piano"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Regola la vite finché la sonda non rileva il piano."); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Tolleranza raggiunta su tutti gli angoli. Piano livellato!"); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Punti buoni: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Ultimo Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Prossimo punto"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor Mesh"); + LSTR MSG_EDIT_MESH = _UxGT("Modifica Mesh"); + LSTR MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata"); + LSTR MSG_PROBING_POINT = _UxGT("Punto sondato"); + LSTR MSG_MESH_X = _UxGT("Indice X"); + LSTR MSG_MESH_Y = _UxGT("Indice Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valore di Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comandi personaliz."); + LSTR MSG_M48_TEST = _UxGT("Test sonda M48"); + LSTR MSG_M48_POINT = _UxGT("Punto M48"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda oltre i limiti"); + LSTR MSG_M48_DEVIATION = _UxGT("Deviazione"); + LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Strumenti Offsets"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicazione"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia speculare"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pieno controllo"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("X-Gap-X duplicato"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2° ugello X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2° ugello Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2° ugello Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("G29 in corso"); + LSTR MSG_UBL_TOOLS = _UxGT("Strumenti UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Misura"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Rimuovi e mis.piatto"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Spostamento succes."); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Attiva UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Disattiva UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Piatto"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Piatto"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Ugello"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Ugello"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Modifica Mesh"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Modif.Mesh personal."); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Ritocca Mesh"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Modif.Mesh fatta"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crea Mesh personal."); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Crea Mesh"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Crea Mesh ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Valida Mesh ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Crea Mesh ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Valida Mesh ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crea Mesh a freddo"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Aggiusta Alt. Mesh"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altezza"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Valida Mesh"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 riscald.letto"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 riscald.ugello"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Priming manuale..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Prime a lung.fissa"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Priming terminato"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Annullato"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Uscita da G26"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valida Mesh pers."); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continua Mesh"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Livell. Mesh"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Livell. 3 Punti"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Livell. Griglia Mesh"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Livella Mesh"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Punti laterali"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo di Mappa"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Esporta Mappa"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Esporta per Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Esporta in CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup esterno"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Esporta Info UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Riempimento"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Riempimento Manuale"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Riempimento Smart"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Riempimento Mesh"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalida Tutto"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalid.Punto Vicino"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Ritocca All"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ritocca Punto Vicino"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Salvate"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot di memoria"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Carica Mesh Piatto"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Salva Mesh Piatto"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i caricata"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i salvata"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nessuna memoria"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: Salvataggio UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: Ripristino UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Fermato"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL passo passo"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crea Mesh a freddo"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Riempimento Smart"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Valida Mesh"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ritocca All"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Valida Mesh"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ritocca All"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Salva Mesh Piatto"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Crea Mesh a freddo"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Aggiusta Alt. Mesh"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altezza"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Valida Mesh"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 riscald.letto"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 riscald.ugello"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Priming manuale..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Prime a lung.fissa"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Priming terminato"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Annullato"); + LSTR MSG_G26_LEAVING = _UxGT("Uscita da G26"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Valida Mesh pers."); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continua Mesh"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Livell. Mesh"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Livell. 3 Punti"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Livell. Griglia Mesh"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Livella Mesh"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Punti laterali"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Tipo di Mappa"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Esporta Mappa"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Esporta per Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Esporta in CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup esterno"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Esporta Info UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Riempimento"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Riempimento Manuale"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Riempimento Smart"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Riempimento Mesh"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalida Tutto"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalid.Punto Vicino"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Ritocca All"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ritocca Punto Vicino"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Salvate"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot di memoria"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Carica Mesh Piatto"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Salva Mesh Piatto"); + LSTR MSG_MESH_LOADED = _UxGT("Mesh %i caricata"); + LSTR MSG_MESH_SAVED = _UxGT("Mesh %i salvata"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Nessuna memoria"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err: Salvataggio UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err: Ripristino UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Fermato"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL passo passo"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Crea Mesh a freddo"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Riempimento Smart"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Valida Mesh"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ritocca All"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Valida Mesh"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ritocca All"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Salva Mesh Piatto"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Controllo LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Luci"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Presets luce"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Rosso"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Arancione"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Giallo"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Verde"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blu"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indaco"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Bianco"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Predefinito"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Canale ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Luci #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Presets luce #2"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Luminosità"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luci personalizzate"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensità rosso"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensità verde"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensità blu"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensità bianco"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Luminosità"); + LSTR MSG_LED_CONTROL = _UxGT("Controllo LED"); + LSTR MSG_LEDS = _UxGT("Luci"); + LSTR MSG_LED_PRESETS = _UxGT("Presets luce"); + LSTR MSG_SET_LEDS_RED = _UxGT("Rosso"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Arancione"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Giallo"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Verde"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Blu"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indaco"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Viola"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Bianco"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Predefinito"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Canale ="); + LSTR MSG_LEDS2 = _UxGT("Luci #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Presets luce #2"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Luminosità"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Luci personalizzate"); + LSTR MSG_INTENSITY_R = _UxGT("Intensità rosso"); + LSTR MSG_INTENSITY_G = _UxGT("Intensità verde"); + LSTR MSG_INTENSITY_B = _UxGT("Intensità blu"); + LSTR MSG_INTENSITY_W = _UxGT("Intensità bianco"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Luminosità"); - PROGMEM Language_Str MSG_MOVING = _UxGT("In movimento..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("XY liberi"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Muovi X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Muovi Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Muovi Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusore"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusore *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Muovi di %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Muovi di 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001\""); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01\""); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); - PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Muovi di 1\""); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocità"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Piatto Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ugello"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Ugello ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello parcheggiato"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Ugello in pausa"); - PROGMEM Language_Str MSG_BED = _UxGT("Piatto"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Camera"); - PROGMEM Language_Str MSG_COOLER = _UxGT("Raffreddam. laser"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Alterna raffreddam."); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Sicurezza flusso"); - PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. ventola"); // Max 15 characters - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. ventola ~"); // Max 15 characters - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventola mem. ~"); // Max 15 characters - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra vel.vent."); // Max 15 characters - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra v.vent. ~"); // Max 15 characters - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller vent."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Vel. inattivo"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo autom."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Vel. attivo"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo inattivo"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flusso"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flusso ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Controllo"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 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_PID_AUTOTUNE = _UxGT("Calibrazione PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Calibraz. PID *"); - PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("Ciclo PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Seleziona"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seleziona *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-jerk"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocità"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Accelerazione"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max * Accel"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Spostamento"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passi/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passi/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passi/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("Limite E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite E *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. filo"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. filo *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Rimuovi mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carica mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K Avanzamento"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K Avanzamento *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contrasto LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Salva impostazioni"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Carica impostazioni"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ripristina imp."); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inizializza EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: CRC EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Indice EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versione EEPROM"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Impostazioni mem."); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aggiorna media"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetta stampante"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Schermata info"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Prepara"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Regola"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Controllo aliment."); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Corrente"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Tensione"); - PROGMEM Language_Str MSG_POWER = _UxGT("Potenza"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Avvia stampa"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Prossimo"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inizializza"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Stampa"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetta"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignora"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Annulla"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fatto"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Indietro"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Procedi"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Salta"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Messa in pausa..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausa stampa"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Riprendi stampa"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Avvio"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Arresta stampa"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Fine cicli di rip."); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Stampa Oggetto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancella Oggetto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Canc. Oggetto ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Ripresa da PowerLoss"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Stampa da media"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Media non presente"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Sospensione..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Premi tasto.."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Stampa sospesa"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Stampa..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Stampa Annullata"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Stampa Eseguita"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nessun Movimento"); - PROGMEM Language_Str MSG_KILLED = _UxGT("UCCISO. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ARRESTATO. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Ritrai mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Scamb. Ritrai mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Ritrai V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Salta mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Avanza mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Scamb. Avanza mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Avanza V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Scamb. Avanza V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoRitrai"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lunghezza scambio"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra scambio"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lunghezza spurgo"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambio utensile"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocità innesco"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Velocità ritrazione"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Parcheggia testa"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Velocità ventola"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo ventola"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Migrazione utensile"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migrazione"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Ultimo estrusore"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migra a *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filam. *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Carica filamento"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Carica filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Rimuovi filamento"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Rimuovi filam. *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Rimuovi tutto"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Collega media"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambia media"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Rilascia media"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z probe fuori piatto"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Fattore distorsione"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Autotest BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Resetta BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Estendi BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("BLTouch modo SW"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("BLTouch modo 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("BLTouch modo OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("BLTouch modo mem."); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Metti BLTouch a 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Metti BLTouch a OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Segnala modo"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERICOLO: impostazioni errate possono cause danni! Procedo comunque?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Inizializ.TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test Z offset"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Memorizzare"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estendi TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Estendi Sonda-Z"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Ritrai BLTouch"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Ritrai Sonda-Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s prima"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Offsets sonda"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Offset X sonda"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Offset Y sonda"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z sonda"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Muovi ugel.su letto"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Interrompi se FC"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 characters - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP RIDONDANTE"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEMP FUORI CONTROLLO"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEMP PIAT.FUORI CTRL"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("T.CAMERA FUORI CTRL"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("RAFFREDAM.FUORI CTRL"); - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Raffreddam. fallito"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MASSIMA"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); - PROGMEM Language_Str MSG_HALTED = _UxGT("STAMPANTE FERMATA"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Riavviare prego"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("g"); // One character - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // One character - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character - PROGMEM Language_Str MSG_HEATING = _UxGT("Riscaldamento..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Raffreddamento.."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Risc. piatto..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Raffr. piatto..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Risc. sonda..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Raffr. sonda..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Risc. camera..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Raffr. camera..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Raffr. laser..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibraz. Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibra X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibra Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibra Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra centro"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Impostaz. Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto calibrazione"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Imp. altezza Delta"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Offset sonda-Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonale"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altezza"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Raggio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Info su stampante"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info. stampante"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Livel. a 3 punti"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Livel. Lineare"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Livel. Bilineare"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Livel.piatto unific."); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Livel. Mesh"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Sond.mesh eseguito"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statistiche"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. scheda"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistori"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Estrusori"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocollo"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Controllo fuga: OFF"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Controllo fuga: ON"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Timeout inatt.ugello"); + LSTR MSG_MOVING = _UxGT("In movimento..."); + LSTR MSG_FREE_XY = _UxGT("XY liberi"); + LSTR MSG_MOVE_X = _UxGT("Muovi X"); + LSTR MSG_MOVE_Y = _UxGT("Muovi Y"); + LSTR MSG_MOVE_Z = _UxGT("Muovi Z"); + LSTR MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Estrusore"); + LSTR MSG_MOVE_EN = _UxGT("Estrusore *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); + LSTR MSG_MOVE_N_MM = _UxGT("Muovi di %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Muovi di 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Muovi di 0.001\""); + LSTR MSG_MOVE_001IN = _UxGT("Muovi di 0.01\""); + LSTR MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); + LSTR MSG_MOVE_1IN = _UxGT("Muovi di 1\""); + LSTR MSG_SPEED = _UxGT("Velocità"); + LSTR MSG_BED_Z = _UxGT("Piatto Z"); + LSTR MSG_NOZZLE = _UxGT("Ugello"); + LSTR MSG_NOZZLE_N = _UxGT("Ugello ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Ugello parcheggiato"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Ugello in pausa"); + LSTR MSG_BED = _UxGT("Piatto"); + LSTR MSG_CHAMBER = _UxGT("Camera"); + LSTR MSG_COOLER = _UxGT("Raffreddam. laser"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Alterna raffreddam."); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Sicurezza flusso"); + LSTR MSG_LASER = _UxGT("Laser"); + LSTR MSG_FAN_SPEED = _UxGT("Vel. ventola"); // Max 15 characters + LSTR MSG_FAN_SPEED_N = _UxGT("Vel. ventola ~"); // Max 15 characters + LSTR MSG_STORED_FAN_N = _UxGT("Ventola mem. ~"); // Max 15 characters + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra vel.vent."); // Max 15 characters + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra v.vent. ~"); // Max 15 characters + LSTR MSG_CONTROLLER_FAN = _UxGT("Controller vent."); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Vel. inattivo"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo autom."); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Vel. attivo"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo inattivo"); + LSTR MSG_FLOW = _UxGT("Flusso"); + LSTR MSG_FLOW_N = _UxGT("Flusso ~"); + LSTR MSG_CONTROL = _UxGT("Controllo"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("On"); + LSTR MSG_LCD_OFF = _UxGT("Off"); + LSTR MSG_PID_AUTOTUNE = _UxGT("Calibrazione PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Calibraz. PID *"); + LSTR MSG_PID_CYCLE = _UxGT("Ciclo PID"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita. Estrusore errato."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita. Temperatura troppo alta."); + LSTR MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); + LSTR MSG_SELECT = _UxGT("Seleziona"); + LSTR MSG_SELECT_E = _UxGT("Seleziona *"); + LSTR MSG_ACC = _UxGT("Accel"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); + LSTR MSG_VE_JERK = _UxGT("Ve-jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); + LSTR MSG_VELOCITY = _UxGT("Velocità"); + LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("VTrav min"); + LSTR MSG_ACCELERATION = _UxGT("Accelerazione"); + LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); + LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione"); + LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); + LSTR MSG_STEPS_PER_MM = _UxGT("Passi/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); + LSTR MSG_E_STEPS = _UxGT("E passi/mm"); + LSTR MSG_EN_STEPS = _UxGT("* passi/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movimento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("Limite E in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("Limite E *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Diam. filo"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diam. filo *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Rimuovi mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Carica mm"); + LSTR MSG_ADVANCE_K = _UxGT("K Avanzamento"); + LSTR MSG_ADVANCE_K_E = _UxGT("K Avanzamento *"); + LSTR MSG_CONTRAST = _UxGT("Contrasto LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Salva impostazioni"); + LSTR MSG_LOAD_EEPROM = _UxGT("Carica impostazioni"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Ripristina imp."); + LSTR MSG_INIT_EEPROM = _UxGT("Inizializza EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Err: CRC EEPROM"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Err: Indice EEPROM"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versione EEPROM"); + LSTR MSG_SETTINGS_STORED = _UxGT("Impostazioni mem."); + LSTR MSG_MEDIA_UPDATE = _UxGT("Aggiorna media"); + LSTR MSG_RESET_PRINTER = _UxGT("Resetta stampante"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); + LSTR MSG_INFO_SCREEN = _UxGT("Schermata info"); + LSTR MSG_PREPARE = _UxGT("Prepara"); + LSTR MSG_TUNE = _UxGT("Regola"); + LSTR MSG_POWER_MONITOR = _UxGT("Controllo aliment."); + LSTR MSG_CURRENT = _UxGT("Corrente"); + LSTR MSG_VOLTAGE = _UxGT("Tensione"); + LSTR MSG_POWER = _UxGT("Potenza"); + LSTR MSG_START_PRINT = _UxGT("Avvia stampa"); + LSTR MSG_BUTTON_NEXT = _UxGT("Prossimo"); + LSTR MSG_BUTTON_INIT = _UxGT("Inizializza"); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Stampa"); + LSTR MSG_BUTTON_RESET = _UxGT("Resetta"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignora"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Annulla"); + LSTR MSG_BUTTON_DONE = _UxGT("Fatto"); + LSTR MSG_BUTTON_BACK = _UxGT("Indietro"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Procedi"); + LSTR MSG_BUTTON_SKIP = _UxGT("Salta"); + LSTR MSG_PAUSING = _UxGT("Messa in pausa..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausa stampa"); + LSTR MSG_RESUME_PRINT = _UxGT("Riprendi stampa"); + LSTR MSG_HOST_START_PRINT = _UxGT("Host Avvio"); + LSTR MSG_STOP_PRINT = _UxGT("Arresta stampa"); + LSTR MSG_END_LOOPS = _UxGT("Fine cicli di rip."); + LSTR MSG_PRINTING_OBJECT = _UxGT("Stampa Oggetto"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella Oggetto"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Canc. Oggetto ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Ripresa da PowerLoss"); + LSTR MSG_MEDIA_MENU = _UxGT("Stampa da media"); + LSTR MSG_NO_MEDIA = _UxGT("Media non presente"); + LSTR MSG_DWELL = _UxGT("Sospensione..."); + LSTR MSG_USERWAIT = _UxGT("Premi tasto.."); + LSTR MSG_PRINT_PAUSED = _UxGT("Stampa sospesa"); + LSTR MSG_PRINTING = _UxGT("Stampa..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Stampa Annullata"); + LSTR MSG_PRINT_DONE = _UxGT("Stampa Eseguita"); + LSTR MSG_NO_MOVE = _UxGT("Nessun Movimento"); + LSTR MSG_KILLED = _UxGT("UCCISO. "); + LSTR MSG_STOPPED = _UxGT("ARRESTATO. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Ritrai mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Scamb. Ritrai mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Ritrai V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Salta mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Avanza mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Scamb. Avanza mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Avanza V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Scamb. Avanza V"); + LSTR MSG_AUTORETRACT = _UxGT("AutoRitrai"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lunghezza scambio"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra scambio"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lunghezza spurgo"); + LSTR MSG_TOOL_CHANGE = _UxGT("Cambio utensile"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Velocità innesco"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Velocità ritrazione"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Parcheggia testa"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Velocità ventola"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Tempo ventola"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Migrazione utensile"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migrazione"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Ultimo estrusore"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migra a *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Cambia filam. *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Carica filamento"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Carica filamento *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Rimuovi filamento"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Rimuovi filam. *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Rimuovi tutto"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Collega media"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambia media"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Rilascia media"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z probe fuori piatto"); + LSTR MSG_SKEW_FACTOR = _UxGT("Fattore distorsione"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Autotest BLTouch"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Resetta BLTouch"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Estendi BLTouch"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("BLTouch modo SW"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("BLTouch modo 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("BLTouch modo OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("BLTouch modo mem."); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Metti BLTouch a 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Metti BLTouch a OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Segnala modo"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERICOLO: impostazioni errate possono cause danni! Procedo comunque?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Inizializ.TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test Z offset"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Memorizzare"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estendi TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Estendi Sonda-Z"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Ritrai BLTouch"); + LSTR MSG_MANUAL_STOW = _UxGT("Ritrai Sonda-Z"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s prima"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Offsets sonda"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Offset X sonda"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Offset Y sonda"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z sonda"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Muovi ugel.su letto"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Totali"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Interrompi se FC"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 characters + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP RIDONDANTE"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TEMP FUORI CONTROLLO"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("TEMP PIAT.FUORI CTRL"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("T.CAMERA FUORI CTRL"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("RAFFREDAM.FUORI CTRL"); + LSTR MSG_COOLING_FAILED = _UxGT("Raffreddam. fallito"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MASSIMA"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); + LSTR MSG_HALTED = _UxGT("STAMPANTE FERMATA"); + LSTR MSG_PLEASE_RESET = _UxGT("Riavviare prego"); + LSTR MSG_SHORT_DAY = _UxGT("g"); // One character + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character + LSTR MSG_HEATING = _UxGT("Riscaldamento..."); + LSTR MSG_COOLING = _UxGT("Raffreddamento.."); + LSTR MSG_BED_HEATING = _UxGT("Risc. piatto..."); + LSTR MSG_BED_COOLING = _UxGT("Raffr. piatto..."); + LSTR MSG_PROBE_HEATING = _UxGT("Risc. sonda..."); + LSTR MSG_PROBE_COOLING = _UxGT("Raffr. sonda..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Risc. camera..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Raffr. camera..."); + LSTR MSG_LASER_COOLING = _UxGT("Raffr. laser..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibraz. Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibra X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibra Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibra Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra centro"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Impostaz. Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto calibrazione"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Imp. altezza Delta"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Offset sonda-Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonale"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Altezza"); + LSTR MSG_DELTA_RADIUS = _UxGT("Raggio"); + LSTR MSG_INFO_MENU = _UxGT("Info su stampante"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info. stampante"); + LSTR MSG_3POINT_LEVELING = _UxGT("Livel. a 3 punti"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Livel. Lineare"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Livel. Bilineare"); + LSTR MSG_UBL_LEVELING = _UxGT("Livel.piatto unific."); + LSTR MSG_MESH_LEVELING = _UxGT("Livel. Mesh"); + LSTR MSG_MESH_DONE = _UxGT("Sond.mesh eseguito"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Statistiche"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info. scheda"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistori"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Estrusori"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocollo"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Controllo fuga: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Controllo fuga: ON"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Timeout inatt.ugello"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luci Case"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA"); + LSTR MSG_CASE_LIGHT = _UxGT("Luci Case"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Contat. stampa"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo totale"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Contat. stampa"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Stampe"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Durata"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Più lungo"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Estruso"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Stampe"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Durata"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Più lungo"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Estruso"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp min"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp max"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alimentatore"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("STAMPA IN PAUSA"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARICA FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("RIMUOVI FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPZIONI RIPRESA:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Spurga di più"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Riprendi stampa"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp min"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp max"); + LSTR MSG_INFO_PSU = _UxGT("Alimentatore"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); + LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); + LSTR MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("STAMPA IN PAUSA"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARICA FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("RIMUOVI FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPZIONI RIPRESA:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Spurga di più"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Riprendi stampa"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SCELTA FILAMENTO"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Agg.firmware MMU!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU chiede attenz."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU riprendi"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU ripresa..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU carica"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU carica tutto"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Carica fino ugello"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU espelli"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU espelli ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU scarica"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Caric.fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Esplus.filam. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Scaric.filam. ..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Tutto"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Azzera MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Azzeramento MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Rimuovi, click"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SCELTA FILAMENTO"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Agg.firmware MMU!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU chiede attenz."); + LSTR MSG_MMU2_RESUME = _UxGT("MMU riprendi"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU ripresa..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU carica"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU carica tutto"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Carica fino ugello"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU espelli"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU espelli ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU scarica"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Caric.fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Esplus.filam. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Scaric.filam. ..."); + LSTR MSG_MMU2_ALL = _UxGT("Tutto"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + LSTR MSG_MMU2_RESET = _UxGT("Azzera MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Azzeramento MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Rimuovi, click"); - PROGMEM Language_Str MSG_MIX = _UxGT("Miscela"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Componente ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Miscelatore"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradiente"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Gradiente pieno"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Alterna miscela"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Ciclo miscela"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Miscela gradiente"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Inverti gradiente"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("V-tool attivo"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("V-tool iniziale"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("V-tool finale"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("V-tool alias"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Ripristina V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit mix V-tool"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools ripristin."); - PROGMEM Language_Str MSG_START_Z = _UxGT("Z inizio:"); - PROGMEM Language_Str MSG_END_Z = _UxGT("Z fine:"); + LSTR MSG_MIX = _UxGT("Miscela"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente ="); + LSTR MSG_MIXER = _UxGT("Miscelatore"); + LSTR MSG_GRADIENT = _UxGT("Gradiente"); + LSTR MSG_FULL_GRADIENT = _UxGT("Gradiente pieno"); + LSTR MSG_TOGGLE_MIX = _UxGT("Alterna miscela"); + LSTR MSG_CYCLE_MIX = _UxGT("Ciclo miscela"); + LSTR MSG_GRADIENT_MIX = _UxGT("Miscela gradiente"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Inverti gradiente"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("V-tool attivo"); + LSTR MSG_START_VTOOL = _UxGT("V-tool iniziale"); + LSTR MSG_END_VTOOL = _UxGT("V-tool finale"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("V-tool alias"); + LSTR MSG_RESET_VTOOLS = _UxGT("Ripristina V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Commit mix V-tool"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools ripristin."); + LSTR MSG_START_Z = _UxGT("Z inizio:"); + LSTR MSG_END_Z = _UxGT("Z fine:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Giochi"); - 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"); + LSTR MSG_GAMES = _UxGT("Giochi"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Indice pag. errato"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Vel. pag. errata"); + LSTR MSG_BAD_PAGE = _UxGT("Indice pag. errato"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Vel. pag. errata"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Modif.password"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login richiesto"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Impostaz.password"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Inserisci cifra"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Imp./Modif.password"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Elimina password"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("La password è "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Ricominciare"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Ricordati di mem.!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Password eliminata"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Modif.password"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Login richiesto"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Impostaz.password"); + LSTR MSG_ENTER_DIGIT = _UxGT("Inserisci cifra"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Imp./Modif.password"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Elimina password"); + LSTR MSG_PASSWORD_SET = _UxGT("La password è "); + LSTR MSG_START_OVER = _UxGT("Ricominciare"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Ricordati di mem.!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Password eliminata"); // // 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_3_LINE("Premi per", "riprendere", "la stampa")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcheggiando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Attendere avvio", "del cambio", "di filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserisci il", "filamento e premi", "per continuare")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premi per", "riscaldare ugello")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Riscaldam. ugello", "Attendere prego...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Attendere", "l'espulsione", "del filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Attendere", "il caricamento", "del filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Attendere", "lo spurgo", "del filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Premi x terminare", "lo spurgo", "del filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Attendere", "la ripresa", "della stampa...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Premi per", "riprendere", "la stampa")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcheggiando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Attendere avvio", "del cambio", "di filamento")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserisci il", "filamento e premi", "per continuare")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premi per", "riscaldare ugello")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Riscaldam. ugello", "Attendere prego...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Attendere", "l'espulsione", "del filamento")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Attendere", "il caricamento", "del filamento")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Attendere", "lo spurgo", "del filamento")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Premi x terminare", "lo spurgo", "del filamento")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Attendere", "la ripresa", "della stampa...")); #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premi x continuare")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Attendere...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Inserisci e premi")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Riscalda ugello")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Riscaldamento...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Espulsione...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Caricamento...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spurgo filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Premi x terminare")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Ripresa...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premi x continuare")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Attendere...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Inserisci e premi")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Riscalda ugello")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Riscaldamento...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Espulsione...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Caricamento...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spurgo filamento")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Premi x terminare")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Ripresa...")); #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Driver TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Correnti driver"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Soglia modo ibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorless homing"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stealthchop"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Stealthchop"); + LSTR MSG_TMC_DRIVERS = _UxGT("Driver TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Correnti driver"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Soglia modo ibrido"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorless homing"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stealthchop"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Stealthchop"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Resetta"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" tra:"); + LSTR MSG_SERVICE_RESET = _UxGT("Resetta"); + LSTR MSG_SERVICE_IN = _UxGT(" tra:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Gioco"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); + LSTR MSG_BACKLASH = _UxGT("Gioco"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout inattività, temperatura diminuita. Premere OK per riscaldare e riprendere di nuovo."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Timeout inattività, temperatura diminuita. Premere OK per riscaldare e riprendere di nuovo."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Riscalda"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Riscaldando..."); - PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Riscaldato"); + LSTR MSG_REHEAT = _UxGT("Riscalda"); + LSTR MSG_REHEATING = _UxGT("Riscaldando..."); + LSTR MSG_REHEATDONE = _UxGT("Riscaldato"); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Wizard Z offset"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Altezza di riferimento sonda"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Spostati in posizione di rilevazione"); + LSTR MSG_PROBE_WIZARD = _UxGT("Wizard Z offset"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Altezza di riferimento sonda"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Spostati in posizione di rilevazione"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Suoni"); + LSTR MSG_SOUND = _UxGT("Suoni"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Alto destra"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); + LSTR MSG_TOP_LEFT = _UxGT("Alto sinistra"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); + LSTR MSG_TOP_RIGHT = _UxGT("Alto destra"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver invertito"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" driver invertito"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("Scheda SD"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("Disco USB"); + LSTR MSG_SD_CARD = _UxGT("Scheda SD"); + LSTR MSG_USB_DISK = _UxGT("Disco USB"); } diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index c0fe2451b0..5864280dd5 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -34,229 +34,229 @@ namespace Language_jp_kana { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 3; - PROGMEM Language_Str LANGUAGE = _UxGT("Japanese"); + constexpr uint8_t CHARSIZE = 3; + LSTR LANGUAGE = _UxGT("Japanese"); // This is just to show the potential benefit of Unicode. // This translation can be improved by using the full charset of unicode codeblock U+30A0 to U+30FF. // 片仮名表示定義 - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" ジュンビカンリョウ"); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("メディアガソウニュウサレマシタ"); // "Card inserted" - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("メディアガアリマセン"); // "Card removed" - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("メディアノトリダシ"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("エンドストップ"); // "Endstops" // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("メイン"); // "Main" - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("ジドウカイシ"); // "Autostart" - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("モーターデンゲン オフ"); // "Disable steppers" - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("デバッグメニュー"); // "Debug Menu" - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("プログレスバー テスト"); // "Progress Bar Test" - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("ゲンテンフッキ"); // "Auto home" - 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_LEVEL_BED_HOMING = _UxGT("ゲンテンフッキチュウ"); // "Homing XYZ" - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("レベリングカイシ"); // "Click to Begin" - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("ツギノソクテイテンヘ"); // "Next Point" - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("レベリングカンリョウ"); // "Leveling Done!" - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("キジュンオフセットセッテイ"); // "Set home offsets" - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("オフセットガテキヨウサレマシタ"); // "Offsets applied" - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("キジュンセット"); // "Set origin" + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" ジュンビカンリョウ"); + LSTR MSG_MEDIA_INSERTED = _UxGT("メディアガソウニュウサレマシタ"); // "Card inserted" + LSTR MSG_MEDIA_REMOVED = _UxGT("メディアガアリマセン"); // "Card removed" + LSTR MSG_RELEASE_MEDIA = _UxGT("メディアノトリダシ"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("エンドストップ"); // "Endstops" // Max length 8 characters + LSTR MSG_MAIN = _UxGT("メイン"); // "Main" + LSTR MSG_RUN_AUTO_FILES = _UxGT("ジドウカイシ"); // "Autostart" + LSTR MSG_DISABLE_STEPPERS = _UxGT("モーターデンゲン オフ"); // "Disable steppers" + LSTR MSG_DEBUG_MENU = _UxGT("デバッグメニュー"); // "Debug Menu" + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("プログレスバー テスト"); // "Progress Bar Test" + LSTR MSG_AUTO_HOME = _UxGT("ゲンテンフッキ"); // "Auto home" + LSTR MSG_AUTO_HOME_X = _UxGT("Xジク ゲンテンフッキ"); // "Home X" + LSTR MSG_AUTO_HOME_Y = _UxGT("Yジク ゲンテンフッキ"); // "Home Y" + LSTR MSG_AUTO_HOME_Z = _UxGT("Zジク ゲンテンフッキ"); // "Home Z" + LSTR MSG_LEVEL_BED_HOMING = _UxGT("ゲンテンフッキチュウ"); // "Homing XYZ" + LSTR MSG_LEVEL_BED_WAITING = _UxGT("レベリングカイシ"); // "Click to Begin" + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("ツギノソクテイテンヘ"); // "Next Point" + LSTR MSG_LEVEL_BED_DONE = _UxGT("レベリングカンリョウ"); // "Leveling Done!" + LSTR MSG_SET_HOME_OFFSETS = _UxGT("キジュンオフセットセッテイ"); // "Set home offsets" + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("オフセットガテキヨウサレマシタ"); // "Offsets applied" + LSTR MSG_SET_ORIGIN = _UxGT("キジュンセット"); // "Set origin" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" ヨネツ"); // "Preheat " PREHEAT_1_LABEL - PROGMEM Language_Str MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" ヨネツ ~"); // "Preheat " PREHEAT_1_LABEL - PROGMEM Language_Str MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" ヨネツノズル"); // " Nozzle" - PROGMEM Language_Str MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" ヨネツノズル ~"); // " Nozzle" - PROGMEM Language_Str MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" スベテヨネツ"); // " All" - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" ベッドヨネツ"); // " Bed" - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" ヨネツセッテイ"); // " conf" + LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" ヨネツ"); // "Preheat " PREHEAT_1_LABEL + LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" ヨネツ ~"); // "Preheat " PREHEAT_1_LABEL + LSTR MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" ヨネツノズル"); // " Nozzle" + LSTR MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" ヨネツノズル ~"); // " Nozzle" + LSTR MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" スベテヨネツ"); // " All" + LSTR MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" ベッドヨネツ"); // " Bed" + LSTR MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" ヨネツセッテイ"); // " conf" - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("$ ヨネツ"); // "Preheat " PREHEAT_1_LABEL - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("$ ヨネツ ~"); // "Preheat " PREHEAT_1_LABEL - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("$ ヨネツノズル"); // " Nozzle" - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("$ ヨネツノズル ~"); // " Nozzle" - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("$ スベテヨネツ"); // " All" - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("$ ベッドヨネツ"); // " Bed" - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("$ ヨネツセッテイ"); // " conf" + LSTR MSG_PREHEAT_M = _UxGT("$ ヨネツ"); // "Preheat " PREHEAT_1_LABEL + LSTR MSG_PREHEAT_M_H = _UxGT("$ ヨネツ ~"); // "Preheat " PREHEAT_1_LABEL + LSTR MSG_PREHEAT_M_END = _UxGT("$ ヨネツノズル"); // " Nozzle" + LSTR MSG_PREHEAT_M_END_E = _UxGT("$ ヨネツノズル ~"); // " Nozzle" + LSTR MSG_PREHEAT_M_ALL = _UxGT("$ スベテヨネツ"); // " All" + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("$ ベッドヨネツ"); // " Bed" + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("$ ヨネツセッテイ"); // " conf" #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("カネツテイシ"); // "Cooldown" - 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" - PROGMEM Language_Str MSG_RETRACT = _UxGT("ヒキコミセッテイ"); // "Retract" - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("ジクイドウ"); // "Move axis" - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("ベッドレベリング"); // "Bed leveling" - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("ベッドレベリング"); // "Level bed" + LSTR MSG_COOLDOWN = _UxGT("カネツテイシ"); // "Cooldown" + LSTR MSG_SWITCH_PS_ON = _UxGT("デンゲン オン"); // "Switch power on" + LSTR MSG_SWITCH_PS_OFF = _UxGT("デンゲン オフ"); // "Switch power off" + LSTR MSG_EXTRUDE = _UxGT("オシダシ"); // "Extrude" + LSTR MSG_RETRACT = _UxGT("ヒキコミセッテイ"); // "Retract" + LSTR MSG_MOVE_AXIS = _UxGT("ジクイドウ"); // "Move axis" + LSTR MSG_BED_LEVELING = _UxGT("ベッドレベリング"); // "Bed leveling" + LSTR MSG_LEVEL_BED = _UxGT("ベッドレベリング"); // "Level bed" - PROGMEM Language_Str MSG_MOVING = _UxGT("イドウチュウ"); // "Moving..." - PROGMEM Language_Str MSG_FREE_XY = _UxGT("XYジク カイホウ"); // "Free XY" - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Xジク イドウ"); // "Move X" - 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_N_MM = _UxGT("%smm イドウ"); // "Move 0.025mm" - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT(" 100mm イドウ"); // "Move 100mm" - PROGMEM Language_Str MSG_SPEED = _UxGT("ソクド"); // "Speed" - PROGMEM Language_Str MSG_BED_Z = _UxGT("Zオフセット"); // "Bed Z" - PROGMEM Language_Str MSG_NOZZLE = _UxGT("ノズル"); // "Nozzle" - PROGMEM Language_Str MSG_BED = _UxGT("ベッド"); // "Bed" - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("ファンソクド"); // "Fan speed" - PROGMEM Language_Str MSG_FLOW = _UxGT("トシュツリョウ"); // "Flow" - PROGMEM Language_Str MSG_CONTROL = _UxGT("セイギョ"); // "Control" - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" サイテイ"); // " Min" - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" サイコウ"); // " Max" - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" ファクター"); // " 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_SELECT = _UxGT("センタク"); // "Select" - PROGMEM Language_Str MSG_SELECT_E = _UxGT("センタク *"); - PROGMEM Language_Str MSG_ACC = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" - PROGMEM Language_Str MSG_JERK = _UxGT("ヤクドウ mm/s"); // "Jerk" - PROGMEM Language_Str MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_A; // "Va-jerk" - PROGMEM Language_Str MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_B; // "Vb-jerk" - PROGMEM Language_Str MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_C; // "Vc-jerk" - PROGMEM Language_Str MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_I; // "Va-jerk" - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_J; // "Vb-jerk" - PROGMEM Language_Str MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_K; // "Vc-jerk" - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("ステップ/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("ステップ/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("ステップ/mm"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("エクストルーダー ヤクド"); // "Ve-jerk" - PROGMEM Language_Str MSG_VMAX_A = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax A" - PROGMEM Language_Str MSG_VMAX_B = _UxGT("サイダイオクリソクド ") LCD_STR_B; // "Vmax B" - PROGMEM Language_Str MSG_VMAX_C = _UxGT("サイダイオクリソクド ") LCD_STR_C; // "Vmax C" - PROGMEM Language_Str MSG_VMAX_I = _UxGT("サイダイオクリソクド ") LCD_STR_I; // "Vmax I" - PROGMEM Language_Str MSG_VMAX_J = _UxGT("サイダイオクリソクド ") LCD_STR_J; // "Vmax J" - PROGMEM Language_Str MSG_VMAX_K = _UxGT("サイダイオクリソクド ") LCD_STR_K; // "Vmax K" - PROGMEM Language_Str MSG_VMAX_E = _UxGT("サイダイオクリソクド ") LCD_STR_E; // "Vmax E" - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" - PROGMEM Language_Str MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" - PROGMEM Language_Str MSG_AMAX = _UxGT("サイダイカソクド "); // "Amax " - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("ヒキコミカソクド"); // "A-retract" - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("イドウカソクド"); // "A-travel" - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("オンド"); // "Temperature" - PROGMEM Language_Str MSG_MOTION = _UxGT("ウゴキセッテイ"); // "Motion" - PROGMEM Language_Str MSG_FILAMENT = _UxGT("フィラメント"); // "Filament" - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("フィラメントチョッケイ"); // "Fil. Dia." - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("フィラメントチョッケイ *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCDコントラスト"); // "LCD contrast" - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("EEPROMヘホゾン"); // "Store memory" - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("EEPROMカラヨミコミ"); // "Load memory" - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("セッテイリセット"); // "Restore Defaults" - PROGMEM Language_Str MSG_REFRESH = LCD_STR_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_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_MEDIA_MENU = _UxGT("メディアカラプリント"); // "Print from SD" - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("メディアガアリマセン"); // "Card removed" - PROGMEM Language_Str MSG_DWELL = _UxGT("キュウシ"); // "Sleep..." - PROGMEM Language_Str MSG_USERWAIT = _UxGT("ツヅケルニハクリックシテクダサイ"); // "Wait for user..." - 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. " - PROGMEM Language_Str MSG_STOPPED = _UxGT("テイシシマシタ"); // "STOPPED. " - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("ヒキコミリョウ mm"); // "Retract mm" - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("ヒキコミリョウS mm"); // "Swap Re.mm" - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("ヒキコミソクド mm/s"); // "Retract V" - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("ノズルタイヒ mm"); // "Hop mm" - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("ホショウリョウ mm"); // "Unretr. mm" - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("ホショウリョウS mm"); // "S Unretr. mm" - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("ホショウソクド mm/s"); // "Unretract V" - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("ジドウヒキコミ"); // "Auto-Retract" - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("フィラメントコウカン"); // "Change filament" - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("メディアサイヨミコミ"); // "Init. SD card" - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("メディアコウカン"); // "Change SD card" - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Zプローブ ベッドガイ"); // "Z probe out. bed" - 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_HOME_FIRST = _UxGT("サキニ %s%s%s ヲフッキサセテクダサイ"); // "Home ... first" - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Zオフセット"); // "Z Offset" - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Xジク ビドウ"); // "Babystep X" - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Yジク ビドウ"); // "Babystep Y" - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Zジク ビドウ"); // "Babystep Z" - 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("エラー:ジョウチョウサーミスターキノウ"); // "Err: REDUNDANT TEMP" - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ネツボウソウ"); // "THERMAL RUNAWAY" - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("エラー:サイコウオンチョウカ"); // "Err: MAXTEMP" - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("エラー:サイテイオンミマン"); // "Err: MINTEMP" - PROGMEM Language_Str MSG_HALTED = _UxGT("プリンターハテイシシマシタ"); // "PRINTER HALTED" - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("リセットシテクダサイ"); // "Please reset" - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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_BED_HEATING = _UxGT("ベッド カネツチュウ"); // "Bed Heating..." - 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" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Zジク コウセイ"); // "Calibrate Z" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("チュウシン コウセイ"); // "Calibrate Center" - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("コノプリンターニツイテ"); // "About Printer" - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("プリンタージョウホウ"); // "Printer Info" - 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_BAUDRATE = _UxGT("ボーレート"); // "Baud" - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("プロトコル"); // "Protocol" - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("キョウタイナイショウメイ"); // "Case light" - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("プリントスウ "); // "Print Count" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("カンリョウスウ"); // "Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("プリントジカンルイケイ"); // "Total print time" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("サイチョウプリントジカン"); // "Longest job time" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("フィラメントシヨウリョウルイケイ"); // "Extruded total" - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("セッテイサイテイオン"); // "Min Temp" - 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_A = LCD_STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E DACシュツリョク %"); // "E Driver %" - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("EEPROMヘホゾン"); // "Store memory" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("イチジテイシ"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("プリントサイカイ"); // "Resume print" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("コウカンヲカイシシマス", "シバラクオマチクダサイ")); // "Wait for start of the filament" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("フィラメントヌキダシチュウ", "シバラクオマチクダサイ")); // "Wait for filament unload" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("フィラメントヲソウニュウシ,", "クリックスルトゾッコウシマス")); // "Insert filament and press button" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("フィラメントソウテンチュウ", "シバラクオマチクダサイ")); // "Wait for filament load" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("プリントヲサイカイシマス", "シバラクオマチクダサイ")); // "Wait for print to resume" + LSTR MSG_MOVING = _UxGT("イドウチュウ"); // "Moving..." + LSTR MSG_FREE_XY = _UxGT("XYジク カイホウ"); // "Free XY" + LSTR MSG_MOVE_X = _UxGT("Xジク イドウ"); // "Move X" + LSTR MSG_MOVE_Y = _UxGT("Yジク イドウ"); // "Move Y" + LSTR MSG_MOVE_Z = _UxGT("Zジク イドウ"); // "Move Z" + LSTR MSG_MOVE_E = _UxGT("エクストルーダー"); // "Extruder" + LSTR MSG_MOVE_N_MM = _UxGT("%smm イドウ"); // "Move 0.025mm" + LSTR MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" + LSTR MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" + LSTR MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" + LSTR MSG_MOVE_100MM = _UxGT(" 100mm イドウ"); // "Move 100mm" + LSTR MSG_SPEED = _UxGT("ソクド"); // "Speed" + LSTR MSG_BED_Z = _UxGT("Zオフセット"); // "Bed Z" + LSTR MSG_NOZZLE = _UxGT("ノズル"); // "Nozzle" + LSTR MSG_BED = _UxGT("ベッド"); // "Bed" + LSTR MSG_FAN_SPEED = _UxGT("ファンソクド"); // "Fan speed" + LSTR MSG_FLOW = _UxGT("トシュツリョウ"); // "Flow" + LSTR MSG_CONTROL = _UxGT("セイギョ"); // "Control" + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" サイテイ"); // " Min" + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" サイコウ"); // " Max" + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" ファクター"); // " Fact" + LSTR MSG_AUTOTEMP = _UxGT("ジドウオンドセイギョ"); // "Autotemp" + LSTR MSG_LCD_ON = _UxGT("オン"); // "On" + LSTR MSG_LCD_OFF = _UxGT("オフ"); // "Off" + LSTR MSG_SELECT = _UxGT("センタク"); // "Select" + LSTR MSG_SELECT_E = _UxGT("センタク *"); + LSTR MSG_ACC = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" + LSTR MSG_JERK = _UxGT("ヤクドウ mm/s"); // "Jerk" + LSTR MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_B; // "Vb-jerk" + LSTR MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_C; // "Vc-jerk" + LSTR MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_I; // "Va-jerk" + LSTR MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_J; // "Vb-jerk" + LSTR MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_K; // "Vc-jerk" + LSTR MSG_A_STEPS = LCD_STR_A _UxGT("ステップ/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT("ステップ/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT("ステップ/mm"); + LSTR MSG_VE_JERK = _UxGT("エクストルーダー ヤクド"); // "Ve-jerk" + LSTR MSG_VMAX_A = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax A" + LSTR MSG_VMAX_B = _UxGT("サイダイオクリソクド ") LCD_STR_B; // "Vmax B" + LSTR MSG_VMAX_C = _UxGT("サイダイオクリソクド ") LCD_STR_C; // "Vmax C" + LSTR MSG_VMAX_I = _UxGT("サイダイオクリソクド ") LCD_STR_I; // "Vmax I" + LSTR MSG_VMAX_J = _UxGT("サイダイオクリソクド ") LCD_STR_J; // "Vmax J" + LSTR MSG_VMAX_K = _UxGT("サイダイオクリソクド ") LCD_STR_K; // "Vmax K" + LSTR MSG_VMAX_E = _UxGT("サイダイオクリソクド ") LCD_STR_E; // "Vmax E" + LSTR MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" + LSTR MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" + LSTR MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" + LSTR MSG_ACCELERATION = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" + LSTR MSG_AMAX = _UxGT("サイダイカソクド "); // "Amax " + LSTR MSG_A_RETRACT = _UxGT("ヒキコミカソクド"); // "A-retract" + LSTR MSG_A_TRAVEL = _UxGT("イドウカソクド"); // "A-travel" + LSTR MSG_TEMPERATURE = _UxGT("オンド"); // "Temperature" + LSTR MSG_MOTION = _UxGT("ウゴキセッテイ"); // "Motion" + LSTR MSG_FILAMENT = _UxGT("フィラメント"); // "Filament" + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("フィラメントチョッケイ"); // "Fil. Dia." + LSTR MSG_FILAMENT_DIAM_E = _UxGT("フィラメントチョッケイ *"); + LSTR MSG_CONTRAST = _UxGT("LCDコントラスト"); // "LCD contrast" + LSTR MSG_STORE_EEPROM = _UxGT("EEPROMヘホゾン"); // "Store memory" + LSTR MSG_LOAD_EEPROM = _UxGT("EEPROMカラヨミコミ"); // "Load memory" + LSTR MSG_RESTORE_DEFAULTS = _UxGT("セッテイリセット"); // "Restore Defaults" + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("リフレッシュ"); // "Refresh" + LSTR MSG_INFO_SCREEN = _UxGT("ジョウホウガメン"); // "Info screen" + LSTR MSG_PREPARE = _UxGT("ジュンビセッテイ"); // "Prepare" + LSTR MSG_TUNE = _UxGT("チョウセイ"); // "Tune" + LSTR MSG_PAUSE_PRINT = _UxGT("イチジテイシ"); // "Pause print" + LSTR MSG_RESUME_PRINT = _UxGT("プリントサイカイ"); // "Resume print" + LSTR MSG_STOP_PRINT = _UxGT("プリントテイシ"); // "Stop print" + LSTR MSG_MEDIA_MENU = _UxGT("メディアカラプリント"); // "Print from SD" + LSTR MSG_NO_MEDIA = _UxGT("メディアガアリマセン"); // "Card removed" + LSTR MSG_DWELL = _UxGT("キュウシ"); // "Sleep..." + LSTR MSG_USERWAIT = _UxGT("ツヅケルニハクリックシテクダサイ"); // "Wait for user..." + LSTR MSG_PRINT_ABORTED = _UxGT("プリントガチュウシサレマシタ"); // "Print aborted" + LSTR MSG_NO_MOVE = _UxGT("ウゴキマセン"); // "No move." + LSTR MSG_KILLED = _UxGT("ヒジョウテイシ"); // "KILLED. " + LSTR MSG_STOPPED = _UxGT("テイシシマシタ"); // "STOPPED. " + LSTR MSG_CONTROL_RETRACT = _UxGT("ヒキコミリョウ mm"); // "Retract mm" + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("ヒキコミリョウS mm"); // "Swap Re.mm" + LSTR MSG_CONTROL_RETRACTF = _UxGT("ヒキコミソクド mm/s"); // "Retract V" + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("ノズルタイヒ mm"); // "Hop mm" + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("ホショウリョウ mm"); // "Unretr. mm" + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("ホショウリョウS mm"); // "S Unretr. mm" + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("ホショウソクド mm/s"); // "Unretract V" + LSTR MSG_AUTORETRACT = _UxGT("ジドウヒキコミ"); // "Auto-Retract" + LSTR MSG_FILAMENTCHANGE = _UxGT("フィラメントコウカン"); // "Change filament" + LSTR MSG_ATTACH_MEDIA = _UxGT("メディアサイヨミコミ"); // "Init. SD card" + LSTR MSG_CHANGE_MEDIA = _UxGT("メディアコウカン"); // "Change SD card" + LSTR MSG_ZPROBE_OUT = _UxGT("Zプローブ ベッドガイ"); // "Z probe out. bed" + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch ジコシンダン"); // "BLTouch Self-Test" + LSTR MSG_BLTOUCH_RESET = _UxGT("BLTouch リセット"); // "Reset BLTouch" + LSTR MSG_HOME_FIRST = _UxGT("サキニ %s%s%s ヲフッキサセテクダサイ"); // "Home ... first" + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Zオフセット"); // "Z Offset" + LSTR MSG_BABYSTEP_X = _UxGT("Xジク ビドウ"); // "Babystep X" + LSTR MSG_BABYSTEP_Y = _UxGT("Yジク ビドウ"); // "Babystep Y" + LSTR MSG_BABYSTEP_Z = _UxGT("Zジク ビドウ"); // "Babystep Z" + LSTR MSG_ENDSTOP_ABORT = _UxGT("イドウゲンカイケンチキノウ"); // "Endstop abort" + LSTR MSG_HEATING_FAILED_LCD = _UxGT("カネツシッパイ"); // "Heating failed" + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("エラー:ジョウチョウサーミスターキノウ"); // "Err: REDUNDANT TEMP" + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ネツボウソウ"); // "THERMAL RUNAWAY" + LSTR MSG_ERR_MAXTEMP = _UxGT("エラー:サイコウオンチョウカ"); // "Err: MAXTEMP" + LSTR MSG_ERR_MINTEMP = _UxGT("エラー:サイテイオンミマン"); // "Err: MINTEMP" + LSTR MSG_HALTED = _UxGT("プリンターハテイシシマシタ"); // "PRINTER HALTED" + LSTR MSG_PLEASE_RESET = _UxGT("リセットシテクダサイ"); // "Please reset" + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("カネツチュウ"); // "Heating..." + LSTR MSG_BED_HEATING = _UxGT("ベッド カネツチュウ"); // "Bed Heating..." + LSTR MSG_DELTA_CALIBRATE = _UxGT("デルタ コウセイ"); // "Delta Calibration" + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Xジク コウセイ"); // "Calibrate X" + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Yジク コウセイ"); // "Calibrate Y" + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Zジク コウセイ"); // "Calibrate Z" + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("チュウシン コウセイ"); // "Calibrate Center" + LSTR MSG_INFO_MENU = _UxGT("コノプリンターニツイテ"); // "About Printer" + LSTR MSG_INFO_PRINTER_MENU = _UxGT("プリンタージョウホウ"); // "Printer Info" + LSTR MSG_INFO_STATS_MENU = _UxGT("プリントジョウキョウ"); // "Printer Stats" + LSTR MSG_INFO_BOARD_MENU = _UxGT("セイギョケイジョウホウ"); // "Board Info" + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("サーミスター"); // "Thermistors" + LSTR MSG_INFO_EXTRUDERS = _UxGT("エクストルーダースウ"); // "Extruders" + LSTR MSG_INFO_BAUDRATE = _UxGT("ボーレート"); // "Baud" + LSTR MSG_INFO_PROTOCOL = _UxGT("プロトコル"); // "Protocol" + LSTR MSG_CASE_LIGHT = _UxGT("キョウタイナイショウメイ"); // "Case light" + LSTR MSG_INFO_PRINT_COUNT = _UxGT("プリントスウ "); // "Print Count" + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("カンリョウスウ"); // "Completed" + LSTR MSG_INFO_PRINT_TIME = _UxGT("プリントジカンルイケイ"); // "Total print time" + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("サイチョウプリントジカン"); // "Longest job time" + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("フィラメントシヨウリョウルイケイ"); // "Extruded total" + LSTR MSG_INFO_MIN_TEMP = _UxGT("セッテイサイテイオン"); // "Min Temp" + LSTR MSG_INFO_MAX_TEMP = _UxGT("セッテイサイコウオン"); // "Max Temp" + LSTR MSG_INFO_PSU = _UxGT("デンゲンシュベツ"); // "Power Supply" + LSTR MSG_DRIVE_STRENGTH = _UxGT("モータークドウリョク"); // "Drive Strength" + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" + LSTR MSG_DAC_PERCENT_E = _UxGT("E DACシュツリョク %"); // "E Driver %" + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("EEPROMヘホゾン"); // "Store memory" + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("イチジテイシ"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("プリントサイカイ"); // "Resume print" + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("コウカンヲカイシシマス", "シバラクオマチクダサイ")); // "Wait for start of the filament" + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("フィラメントヌキダシチュウ", "シバラクオマチクダサイ")); // "Wait for filament unload" + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("フィラメントヲソウニュウシ,", "クリックスルトゾッコウシマス")); // "Insert filament and press button" + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("フィラメントソウテンチュウ", "シバラクオマチクダサイ")); // "Wait for filament load" + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("プリントヲサイカイシマス", "シバラクオマチクダサイ")); // "Wait for print to resume" - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("マチガッタプリンター"); // "Wrong printer" + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("マチガッタプリンター"); // "Wrong printer" - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("セッテイカンリ"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("ショウサイセッテイ"); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("コショカイフク"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROMショキカ"); + LSTR MSG_CONFIGURATION = _UxGT("セッテイカンリ"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("ショウサイセッテイ"); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("コショカイフク"); + LSTR MSG_INIT_EEPROM = _UxGT("EEPROMショキカ"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("ツギヘ"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("ショキカ"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("ストップ"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("プリント"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("リセット"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("キャンセル"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("カンリョウ"); + LSTR MSG_BUTTON_NEXT = _UxGT("ツギヘ"); + LSTR MSG_BUTTON_INIT = _UxGT("ショキカ"); + LSTR MSG_BUTTON_STOP = _UxGT("ストップ"); + LSTR MSG_BUTTON_PRINT = _UxGT("プリント"); + LSTR MSG_BUTTON_RESET = _UxGT("リセット"); + LSTR MSG_BUTTON_CANCEL = _UxGT("キャンセル"); + LSTR MSG_BUTTON_DONE = _UxGT("カンリョウ"); - PROGMEM Language_Str MSG_YES = _UxGT("ハイ"); - PROGMEM Language_Str MSG_NO = _UxGT("イイエ"); - PROGMEM Language_Str MSG_BACK = _UxGT("モドリ"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("ソクド"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("ステップ/mm"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("ユーザーコマンド"); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("プリントガイチジテイシサレマシタ"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("プリントチュウ..."); + LSTR MSG_YES = _UxGT("ハイ"); + LSTR MSG_NO = _UxGT("イイエ"); + LSTR MSG_BACK = _UxGT("モドリ"); + LSTR MSG_VELOCITY = _UxGT("ソクド"); + LSTR MSG_STEPS_PER_MM = _UxGT("ステップ/mm"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("ユーザーコマンド"); + LSTR MSG_PRINT_PAUSED = _UxGT("プリントガイチジテイシサレマシタ"); + LSTR MSG_PRINTING = _UxGT("プリントチュウ..."); } diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 20700896c1..4ecdd5bb2d 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -30,77 +30,77 @@ namespace Language_ko_KR { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Korean"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Korean"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" 준비."); - PROGMEM Language_Str MSG_BACK = _UxGT("뒤로"); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("카드 삽입됨"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("카드 제거됨"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("엔드스탑"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("소프트 엔드스탑"); - PROGMEM Language_Str MSG_MAIN = _UxGT("뒤로"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("고급 설정"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("설정"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("자동 시작"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("모터 정지"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("디버깅 메뉴"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("프로그레스바 테스트"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("오토홈"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X 홈으로"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y 홈으로"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z 홈으로"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ 홈으로"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("누르면 시작합니다"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("다음 Point"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("레벨링 완료!"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" 준비."); + LSTR MSG_BACK = _UxGT("뒤로"); + LSTR MSG_MEDIA_INSERTED = _UxGT("카드 삽입됨"); + LSTR MSG_MEDIA_REMOVED = _UxGT("카드 제거됨"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("엔드스탑"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("소프트 엔드스탑"); + LSTR MSG_MAIN = _UxGT("뒤로"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("고급 설정"); + LSTR MSG_CONFIGURATION = _UxGT("설정"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("자동 시작"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("모터 정지"); + LSTR MSG_DEBUG_MENU = _UxGT("디버깅 메뉴"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("프로그레스바 테스트"); + LSTR MSG_AUTO_HOME = _UxGT("오토홈"); + LSTR MSG_AUTO_HOME_X = _UxGT("X 홈으로"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Y 홈으로"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Z 홈으로"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("XYZ 홈으로"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("누르면 시작합니다"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("다음 Point"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("레벨링 완료!"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("예열하기 - ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("예열하기 - ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("예열하기 - ") PREHEAT_1_LABEL _UxGT(" 노즐"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("예열하기 - ") PREHEAT_1_LABEL _UxGT(" 노즐 ~"); + LSTR MSG_PREHEAT_1 = _UxGT("예열하기 - ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("예열하기 - ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("예열하기 - ") PREHEAT_1_LABEL _UxGT(" 노즐"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("예열하기 - ") PREHEAT_1_LABEL _UxGT(" 노즐 ~"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("예열하기 - $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("예열하기 - $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("예열하기 - $ 노즐"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("예열하기 - $ 노즐 ~"); + LSTR MSG_PREHEAT_M = _UxGT("예열하기 - $"); + LSTR MSG_PREHEAT_M_H = _UxGT("예열하기 - $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("예열하기 - $ 노즐"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("예열하기 - $ 노즐 ~"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Custom 예열"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("식히기"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("스위치 전원 켜기"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("스위치 전원 끄기"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("밀어내기"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("당기기"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("축 이동"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("베드 레벨링"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("미러 사본"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("오토레벨링 하기"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("노즐"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("노즐 ~"); - PROGMEM Language_Str MSG_BED = _UxGT("베드"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("펜 속도"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("펜 속도 ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("엑스트라 펜 속도"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("엑스트라 펜 속도 ~"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("온도"); - PROGMEM Language_Str MSG_MOTION = _UxGT("동작"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("설정 저장하기"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("설정 읽어오기"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("설정 되돌리기"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM 초기화"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("새로고침"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("처음으로"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("준비하기"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("일시정지"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("재시작"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("출력중지"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("SD 카드출력"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD 카드없음"); - PROGMEM Language_Str MSG_DWELL = _UxGT("슬립모드..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("일시 정지됨"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("출력중..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("취소됨"); - PROGMEM Language_Str MSG_KILLED = _UxGT("죽음. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("멈춤. "); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("잘못된 프린터"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Custom 예열"); + LSTR MSG_COOLDOWN = _UxGT("식히기"); + LSTR MSG_SWITCH_PS_ON = _UxGT("스위치 전원 켜기"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("스위치 전원 끄기"); + LSTR MSG_EXTRUDE = _UxGT("밀어내기"); + LSTR MSG_RETRACT = _UxGT("당기기"); + LSTR MSG_MOVE_AXIS = _UxGT("축 이동"); + LSTR MSG_BED_LEVELING = _UxGT("베드 레벨링"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("미러 사본"); + LSTR MSG_UBL_DOING_G29 = _UxGT("오토레벨링 하기"); + LSTR MSG_NOZZLE = _UxGT("노즐"); + LSTR MSG_NOZZLE_N = _UxGT("노즐 ~"); + LSTR MSG_BED = _UxGT("베드"); + LSTR MSG_FAN_SPEED = _UxGT("펜 속도"); + LSTR MSG_FAN_SPEED_N = _UxGT("펜 속도 ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("엑스트라 펜 속도"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("엑스트라 펜 속도 ~"); + LSTR MSG_TEMPERATURE = _UxGT("온도"); + LSTR MSG_MOTION = _UxGT("동작"); + LSTR MSG_STORE_EEPROM = _UxGT("설정 저장하기"); + LSTR MSG_LOAD_EEPROM = _UxGT("설정 읽어오기"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("설정 되돌리기"); + LSTR MSG_INIT_EEPROM = _UxGT("EEPROM 초기화"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("새로고침"); + LSTR MSG_INFO_SCREEN = _UxGT("처음으로"); + LSTR MSG_PREPARE = _UxGT("준비하기"); + LSTR MSG_PAUSE_PRINT = _UxGT("일시정지"); + LSTR MSG_RESUME_PRINT = _UxGT("재시작"); + LSTR MSG_STOP_PRINT = _UxGT("출력중지"); + LSTR MSG_MEDIA_MENU = _UxGT("SD 카드출력"); + LSTR MSG_NO_MEDIA = _UxGT("SD 카드없음"); + LSTR MSG_DWELL = _UxGT("슬립모드..."); + LSTR MSG_PRINT_PAUSED = _UxGT("일시 정지됨"); + LSTR MSG_PRINTING = _UxGT("출력중..."); + LSTR MSG_PRINT_ABORTED = _UxGT("취소됨"); + LSTR MSG_KILLED = _UxGT("죽음. "); + LSTR MSG_STOPPED = _UxGT("멈춤. "); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("잘못된 프린터"); } diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 1eef4ca424..786fa88298 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -34,199 +34,199 @@ namespace Language_nl { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; - PROGMEM Language_Str LANGUAGE = _UxGT("Dutch"); + constexpr uint8_t CHARSIZE = 1; + LSTR LANGUAGE = _UxGT("Dutch"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" gereed."); - PROGMEM Language_Str MSG_BACK = _UxGT("Terug"); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Kaart ingestoken"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Kaart verwijderd"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Hoofdmenu"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren uit"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Menu"); // accepted English terms - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Vooruitgang Test"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" gereed."); + LSTR MSG_BACK = _UxGT("Terug"); + LSTR MSG_MEDIA_INSERTED = _UxGT("Kaart ingestoken"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Kaart verwijderd"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Hoofdmenu"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren uit"); + LSTR MSG_DEBUG_MENU = _UxGT("Debug Menu"); // accepted English terms + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Vooruitgang Test"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klik voor begin"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Volgende Plaats"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Bed level kompl."); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Zet home offsets"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("H offset toegep."); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nulpunt instellen"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klik voor begin"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Volgende Plaats"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Bed level kompl."); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Zet home offsets"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("H offset toegep."); + LSTR MSG_SET_ORIGIN = _UxGT("Nulpunt instellen"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" voorverwarmen"); - PROGMEM Language_Str MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" voorverw. ~"); - PROGMEM Language_Str MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" voorverw. Einde"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" voorverw. Einde ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" voorverw. aan"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" voorverw. Bed"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" verw. conf"); + LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" voorverwarmen"); + LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" voorverw. ~"); + LSTR MSG_PREHEAT_1_END = PREHEAT_1_LABEL _UxGT(" voorverw. Einde"); + LSTR MSG_PREHEAT_1_END_E = PREHEAT_1_LABEL _UxGT(" voorverw. Einde ~"); + LSTR MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" voorverw. aan"); + LSTR MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" voorverw. Bed"); + LSTR MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" verw. conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("$ voorverwarmen"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("$ voorverw. ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("$ voorverw. Einde"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("$ voorverw. Einde ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("$ voorverw. aan"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("$ voorverw. Bed"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("$ verw. conf"); + LSTR MSG_PREHEAT_M = _UxGT("$ voorverwarmen"); + LSTR MSG_PREHEAT_M_H = _UxGT("$ voorverw. ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("$ voorverw. Einde"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("$ voorverw. Einde ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("$ voorverw. aan"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("$ voorverw. Bed"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("$ verw. conf"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Afkoelen"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Stroom aan"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Stroom uit"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrude"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retract"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("As verplaatsen"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bed Leveling"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Level bed"); + LSTR MSG_COOLDOWN = _UxGT("Afkoelen"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Stroom aan"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Stroom uit"); + LSTR MSG_EXTRUDE = _UxGT("Extrude"); + LSTR MSG_RETRACT = _UxGT("Retract"); + LSTR MSG_MOVE_AXIS = _UxGT("As verplaatsen"); + LSTR MSG_BED_LEVELING = _UxGT("Bed Leveling"); + LSTR MSG_LEVEL_BED = _UxGT("Level bed"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Verplaatsen..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Vrij XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Verplaats X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Verplaats Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Verplaats Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Verplaats %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Verplaats 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Snelheid"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Bed"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan snelheid"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fan snelheid ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flow"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flow ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Aan"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Uit"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Selecteer"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Selecteer *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Versn"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatuur"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Beweging"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); // accepted english dutch - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); // accepted english dutch - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD contrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Geheugen opslaan"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Geheugen laden"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Noodstop reset"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ververs"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info scherm"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Voorbereiden"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Afstellen"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Print pauzeren"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Print hervatten"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Print stoppen"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Print van SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Geen SD kaart"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Slapen..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Wachten..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Print afgebroken"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Geen beweging."); - PROGMEM Language_Str MSG_KILLED = _UxGT("Afgebroken. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("Gestopt. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retract mm"); // accepted English term in Dutch - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Ruil Retract mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retract F"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Ruil Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretr. FR"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Verv. Filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Verv. Filament *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Init. SD kaart"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Verv. SD Kaart"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z probe uit. bed"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Zelf-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s Eerst"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Offset"); // accepted English term in Dutch - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystap X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystap Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystap Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop afbr."); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Voorverw. fout"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Redun. temp fout"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Therm. wegloop"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: Max. temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: Min. temp"); - PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER GESTOPT"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reset A.U.B."); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only. Keep English standard - 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("Voorwarmen..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Bed voorverw..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Calibratie"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibreer X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibreer Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibreer Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibreer Midden"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibratie"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Zet Delta Hoogte"); + LSTR MSG_MOVING = _UxGT("Verplaatsen..."); + LSTR MSG_FREE_XY = _UxGT("Vrij XY"); + LSTR MSG_MOVE_X = _UxGT("Verplaats X"); + LSTR MSG_MOVE_Y = _UxGT("Verplaats Y"); + LSTR MSG_MOVE_Z = _UxGT("Verplaats Z"); + LSTR MSG_MOVE_E = _UxGT("Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Extruder *"); + LSTR MSG_MOVE_N_MM = _UxGT("Verplaats %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Verplaats 100mm"); + LSTR MSG_SPEED = _UxGT("Snelheid"); + LSTR MSG_BED_Z = _UxGT("Bed Z"); + LSTR MSG_NOZZLE = _UxGT("Nozzle"); + LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); + LSTR MSG_BED = _UxGT("Bed"); + LSTR MSG_FAN_SPEED = _UxGT("Fan snelheid"); + LSTR MSG_FAN_SPEED_N = _UxGT("Fan snelheid ~"); + LSTR MSG_FLOW = _UxGT("Flow"); + LSTR MSG_FLOW_N = _UxGT("Flow ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("Aan"); + LSTR MSG_LCD_OFF = _UxGT("Uit"); + LSTR MSG_SELECT = _UxGT("Selecteer"); + LSTR MSG_SELECT_E = _UxGT("Selecteer *"); + LSTR MSG_ACC = _UxGT("Versn"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatuur"); + LSTR MSG_MOTION = _UxGT("Beweging"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_ADVANCE_K = _UxGT("Advance K"); // accepted english dutch + LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); // accepted english dutch + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_CONTRAST = _UxGT("LCD contrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Geheugen opslaan"); + LSTR MSG_LOAD_EEPROM = _UxGT("Geheugen laden"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Noodstop reset"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Ververs"); + LSTR MSG_INFO_SCREEN = _UxGT("Info scherm"); + LSTR MSG_PREPARE = _UxGT("Voorbereiden"); + LSTR MSG_TUNE = _UxGT("Afstellen"); + LSTR MSG_PAUSE_PRINT = _UxGT("Print pauzeren"); + LSTR MSG_RESUME_PRINT = _UxGT("Print hervatten"); + LSTR MSG_STOP_PRINT = _UxGT("Print stoppen"); + LSTR MSG_MEDIA_MENU = _UxGT("Print van SD"); + LSTR MSG_NO_MEDIA = _UxGT("Geen SD kaart"); + LSTR MSG_DWELL = _UxGT("Slapen..."); + LSTR MSG_USERWAIT = _UxGT("Wachten..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Print afgebroken"); + LSTR MSG_NO_MOVE = _UxGT("Geen beweging."); + LSTR MSG_KILLED = _UxGT("Afgebroken. "); + LSTR MSG_STOPPED = _UxGT("Gestopt. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retract mm"); // accepted English term in Dutch + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Ruil Retract mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retract F"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Ruil Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretr. FR"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Verv. Filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Verv. Filament *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Init. SD kaart"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Verv. SD Kaart"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z probe uit. bed"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Zelf-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s Eerst"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z Offset"); // accepted English term in Dutch + LSTR MSG_BABYSTEP_X = _UxGT("Babystap X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystap Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystap Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop afbr."); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Voorverw. fout"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Redun. temp fout"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("Therm. wegloop"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: Max. temp"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: Min. temp"); + LSTR MSG_HALTED = _UxGT("PRINTER GESTOPT"); + LSTR MSG_PLEASE_RESET = _UxGT("Reset A.U.B."); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only. Keep English standard + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Voorwarmen..."); + LSTR MSG_BED_HEATING = _UxGT("Bed voorverw..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Calibratie"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibreer X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibreer Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibreer Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibreer Midden"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibratie"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Zet Delta Hoogte"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case licht"); + LSTR MSG_CASE_LIGHT = _UxGT("Case licht"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Printed Aantal"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Totaal Voltooid"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Totale Printtijd"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Langste Printtijd"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Totaal Extrudeert"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Printed Aantal"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Totaal Voltooid"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Totale Printtijd"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Langste Printtijd"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totaal Extrudeert"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Aantal"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Voltooid"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Printtijd "); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Langste"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Aantal"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Voltooid"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Printtijd "); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Langste"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); // accepted English term in Dutch + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); // accepted English term in Dutch - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Motorstroom"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Motorstroom"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC Opslaan"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Hervat print"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); // accepted English term + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC Opslaan"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Hervat print"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); // accepted English term // // 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 // Up to 3 lines - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Wacht voor start", "filament te", "verwisselen")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Wacht voor", "filament uit", "te laden")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klik knop om...", "verw. nozzle.")); //nozzle accepted English term - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozzle verw.", "Wacht a.u.b.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Laad filament", "en druk knop", "om verder...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Wacht voor", "filament te", "laden")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Wacht voor print", "om verder", "te gaan")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Wacht voor start", "filament te", "verwisselen")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Wacht voor", "filament uit", "te laden")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klik knop om...", "verw. nozzle.")); //nozzle accepted English term + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozzle verw.", "Wacht a.u.b.")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Laad filament", "en druk knop", "om verder...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Wacht voor", "filament te", "laden")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Wacht voor print", "om verder", "te gaan")); #else // Up to 2 lines - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Wacht voor", "start...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wacht voor", "uitladen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klik knop om...", "verw. nozzle.")); //nozzle accepted English term - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Verwarmen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("Laad filament", "en druk knop")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Wacht voor", "inladen...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wacht voor", "printing...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Wacht voor", "start...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wacht voor", "uitladen...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Klik knop om...", "verw. nozzle.")); //nozzle accepted English term + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Verwarmen...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("Laad filament", "en druk knop")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Wacht voor", "inladen...")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wacht voor", "printing...")); #endif } diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index c1620a8fa6..3e19150a77 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -40,671 +40,671 @@ namespace Language_pl { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Polski"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Polski"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); - //PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("TAK"); - PROGMEM Language_Str MSG_NO = _UxGT("NIE"); - PROGMEM Language_Str MSG_BACK = _UxGT("Wstecz"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Przerywanie..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); - //PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu główne"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Ustawienie zaawansowane"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguracja"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Wyłącz silniki"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu Debugowania"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Testowy pasek postępu"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Pozycja zerowa"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Zeruj X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); - //PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknij by rozp."); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Następny punkt"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); - //PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); - //PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); - //PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); - //PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); + //LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("TAK"); + LSTR MSG_NO = _UxGT("NIE"); + LSTR MSG_BACK = _UxGT("Wstecz"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Przerywanie..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); + LSTR MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + //LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); + LSTR MSG_MAIN = _UxGT("Menu główne"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Ustawienie zaawansowane"); + LSTR MSG_CONFIGURATION = _UxGT("Konfiguracja"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Wyłącz silniki"); + LSTR MSG_DEBUG_MENU = _UxGT("Menu Debugowania"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Testowy pasek postępu"); + LSTR MSG_AUTO_HOME = _UxGT("Pozycja zerowa"); + LSTR MSG_AUTO_HOME_X = _UxGT("Zeruj X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); + //LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Kliknij by rozp."); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Następny punkt"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); + //LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + //LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + //LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); + LSTR MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); + //LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Rozgrzej ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Rozgrzej ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" Dysza"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" Dysza ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" wsz."); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" stół"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" ustaw."); + LSTR MSG_PREHEAT_1 = _UxGT("Rozgrzej ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Rozgrzej ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" Dysza"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" Dysza ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" wsz."); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" stół"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Rozgrzej ") PREHEAT_1_LABEL _UxGT(" ustaw."); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Rozgrzej $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Rozgrzej $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Rozgrzej $ Dysza"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Rozgrzej $ Dysza ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Rozgrzej $ wsz."); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Rozgrzej $ stół"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Rozgrzej $ ustaw."); + LSTR MSG_PREHEAT_M = _UxGT("Rozgrzej $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Rozgrzej $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Rozgrzej $ Dysza"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Rozgrzej $ Dysza ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Rozgrzej $ wsz."); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Rozgrzej $ stół"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Rozgrzej $ ustaw."); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Rozgrzej własne ust."); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Chłodzenie"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Rozgrzej własne ust."); + LSTR MSG_COOLDOWN = _UxGT("Chłodzenie"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Częstotliwość"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Sterowanie Lasera"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); - //PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); - //PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); - //PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); - //PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); - //PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); - //PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); - //PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); - //PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); - //PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Ekstruzja"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Wycofanie"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Ruch osi"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Narożniki poziomowania"); - //PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); - //PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); - //PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); - //PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Edycja siatki zatrzymana"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punkt pomiarowy"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Indeks X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Indeks Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Wartość Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punky"); - //PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylenie"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Tryb IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkowanie"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); - //PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); - //PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); - //PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Przesuwanie do następnego"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Aktywacja UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Dezaktywacja UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temperatura stołu"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temperatura stołu"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temperatura dyszy"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temperatura dyszy"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Edycja siatki"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edycja własnej siatki"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Dostrajanie siatki"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec edycji siati"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Buduj własna siatkę"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Buduj siatkę"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Buduj siatkę na zimno"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Dostrojenie wysokości siatki"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Wartość wysokości"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sprawdzenie siatki"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Sprawdzenie własnej siatki"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Nagrzewanie stołu"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Napełnianie ręczne..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Napełnij kreśloną długością"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Napełnianie zakończone"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Przewane"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Opuszczanie G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Kontynuuj tworzenie siatki"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Poziomowanie siatką"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Poziomowaie 3-punktowe"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Poziomowaie według siatki"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Poziomuj siatkę"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Punkty boczne"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Rodzaj mapy"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Wyslij mapę siatki"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Wyslij do Hosta"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Wyslij do CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Kopia poza drukarką"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Wyslij info UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Stopień wypełnienia"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ręczne wypełnienie"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Inteligentne wypełnienie"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Wypełnienie siatki"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Unieważnij wszystko"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Unieważnij najbliższy"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Dostrajaj wszystko"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Dostrajaj najbliższy"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Przechowywanie siatki"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot Pamięci"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Załaduj siatkę stołu"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Zapisz siatkę stołu"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Siatka %i załadowana"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Siatka %i zapisana"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Brak magazynu"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Błąd: Zapis UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Bład: Odczyt UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Przesunięcie Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Przesunięcie Z zatrzymane"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Krok po kroku"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Tworzenie zimnej siatki"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligentne wypełnienie"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Sprawdzenie siatki"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Dostrojenie wszystkiego"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Sprawdzenie siatki"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Dostrojenie wszystkiego"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Zapis siatki stołu"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Częstotliwość"); + LSTR MSG_LASER_MENU = _UxGT("Sterowanie Lasera"); + LSTR MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); + LSTR MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); + LSTR MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); + //LSTR MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + //LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + //LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + //LSTR MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + //LSTR MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + //LSTR MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + //LSTR MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + //LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + //LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); + LSTR MSG_EXTRUDE = _UxGT("Ekstruzja"); + LSTR MSG_RETRACT = _UxGT("Wycofanie"); + LSTR MSG_MOVE_AXIS = _UxGT("Ruch osi"); + LSTR MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); + LSTR MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); + LSTR MSG_BED_TRAMMING = _UxGT("Narożniki poziomowania"); + //LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + //LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + //LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); + //LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); + LSTR MSG_MESH_EDITOR = _UxGT("Edytor siatki"); + LSTR MSG_EDIT_MESH = _UxGT("Edycja siatki"); + LSTR MSG_EDITING_STOPPED = _UxGT("Edycja siatki zatrzymana"); + LSTR MSG_PROBING_POINT = _UxGT("Punkt pomiarowy"); + LSTR MSG_MESH_X = _UxGT("Indeks X"); + LSTR MSG_MESH_Y = _UxGT("Indeks Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Wartość Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); + LSTR MSG_M48_TEST = _UxGT("M48 Test sondy"); + LSTR MSG_M48_POINT = _UxGT("M48 Punky"); + //LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); + LSTR MSG_M48_DEVIATION = _UxGT("Odchylenie"); + LSTR MSG_IDEX_MENU = _UxGT("Tryb IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkowanie"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); + //LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); + //LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); + //LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Przesuwanie do następnego"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Aktywacja UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Dezaktywacja UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Temperatura stołu"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temperatura stołu"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temperatura dyszy"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temperatura dyszy"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Edycja siatki"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edycja własnej siatki"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Dostrajanie siatki"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec edycji siati"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Buduj własna siatkę"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Buduj siatkę"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Buduj siatkę na zimno"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Dostrojenie wysokości siatki"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Wartość wysokości"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sprawdzenie siatki"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Sprawdzenie własnej siatki"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Nagrzewanie stołu"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Napełnianie ręczne..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Napełnij kreśloną długością"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Napełnianie zakończone"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Przewane"); + LSTR MSG_G26_LEAVING = _UxGT("Opuszczanie G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Kontynuuj tworzenie siatki"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Poziomowanie siatką"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Poziomowaie 3-punktowe"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Poziomowaie według siatki"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Poziomuj siatkę"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Punkty boczne"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Rodzaj mapy"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Wyslij mapę siatki"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Wyslij do Hosta"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Wyslij do CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Kopia poza drukarką"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Wyslij info UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Stopień wypełnienia"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ręczne wypełnienie"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Inteligentne wypełnienie"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Wypełnienie siatki"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Unieważnij wszystko"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Unieważnij najbliższy"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Dostrajaj wszystko"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Dostrajaj najbliższy"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Przechowywanie siatki"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot Pamięci"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Załaduj siatkę stołu"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Zapisz siatkę stołu"); + LSTR MSG_MESH_LOADED = _UxGT("Siatka %i załadowana"); + LSTR MSG_MESH_SAVED = _UxGT("Siatka %i zapisana"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Brak magazynu"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Błąd: Zapis UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Bład: Odczyt UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Przesunięcie Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Przesunięcie Z zatrzymane"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Krok po kroku"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Tworzenie zimnej siatki"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Inteligentne wypełnienie"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Sprawdzenie siatki"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Dostrojenie wszystkiego"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Sprawdzenie siatki"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Dostrojenie wszystkiego"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Zapis siatki stołu"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Sterowanie LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Światła"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Ustawienia świateł"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Czerwony"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Pomarańczowy"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Zółty"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Zielony"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Niebieski"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indygo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Biały"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanał ="); - //PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); - //PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Własne światła"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Czerwony"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zielony"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Niebieski"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Biały"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Jasność"); + LSTR MSG_LED_CONTROL = _UxGT("Sterowanie LED"); + LSTR MSG_LEDS = _UxGT("Światła"); + LSTR MSG_LED_PRESETS = _UxGT("Ustawienia świateł"); + LSTR MSG_SET_LEDS_RED = _UxGT("Czerwony"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Pomarańczowy"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Zółty"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Zielony"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Niebieski"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indygo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Biały"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanał ="); + //LSTR MSG_LEDS2 = _UxGT("Lights #2"); + //LSTR MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Własne światła"); + LSTR MSG_INTENSITY_R = _UxGT("Czerwony"); + LSTR MSG_INTENSITY_G = _UxGT("Zielony"); + LSTR MSG_INTENSITY_B = _UxGT("Niebieski"); + LSTR MSG_INTENSITY_W = _UxGT("Biały"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Jasność"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Ruch..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Swobodne XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Przesuń w X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Przesuń w Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Przesuń w Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Przesuń co 100 mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Predkość"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Stół Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dysza"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dysza ~"); - //PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); - PROGMEM Language_Str MSG_BED = _UxGT("Stół"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Obudowa"); - //PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); - //PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); - //PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); - //PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); - //PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); - //PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); - //PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); - //PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); - //PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Przepływ"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Przepływ ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Ustawienia"); - //PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - //PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto. temperatura"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Wł."); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Wył."); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); - //PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - //PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); - //PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - //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("Wybierz"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Wybierz *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Przyspieszenie"); - PROGMEM Language_Str MSG_JERK = _UxGT("Zryw"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Zryw V") LCD_STR_A; - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Zryw V") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Zryw V") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Zryw V") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Zryw Ve"); - //PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Prędkość (V)"); + LSTR MSG_MOVING = _UxGT("Ruch..."); + LSTR MSG_FREE_XY = _UxGT("Swobodne XY"); + LSTR MSG_MOVE_X = _UxGT("Przesuń w X"); + LSTR MSG_MOVE_Y = _UxGT("Przesuń w Y"); + LSTR MSG_MOVE_Z = _UxGT("Przesuń w Z"); + LSTR MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); + LSTR MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); + LSTR MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); + LSTR MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); + LSTR MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); + LSTR MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); + LSTR MSG_MOVE_100MM = _UxGT("Przesuń co 100 mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); + LSTR MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); + LSTR MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); + LSTR MSG_SPEED = _UxGT("Predkość"); + LSTR MSG_BED_Z = _UxGT("Stół Z"); + LSTR MSG_NOZZLE = _UxGT("Dysza"); + LSTR MSG_NOZZLE_N = _UxGT("Dysza ~"); + //LSTR MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); + LSTR MSG_BED = _UxGT("Stół"); + LSTR MSG_CHAMBER = _UxGT("Obudowa"); + //LSTR MSG_COOLER = _UxGT("Laser Coolant"); + //LSTR MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + //LSTR MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + //LSTR MSG_LASER = _UxGT("Laser"); + LSTR MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); + LSTR MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); + //LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); + //LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + //LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + //LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + //LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); + LSTR MSG_FLOW = _UxGT("Przepływ"); + LSTR MSG_FLOW_N = _UxGT("Przepływ ~"); + LSTR MSG_CONTROL = _UxGT("Ustawienia"); + //LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + //LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); + LSTR MSG_AUTOTEMP = _UxGT("Auto. temperatura"); + LSTR MSG_LCD_ON = _UxGT("Wł."); + LSTR MSG_LCD_OFF = _UxGT("Wył."); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); + //LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + //LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + //LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + //LSTR MSG_PID_P = _UxGT("PID-P"); + //LSTR MSG_PID_P_E = _UxGT("PID-P *"); + //LSTR MSG_PID_I = _UxGT("PID-I"); + //LSTR MSG_PID_I_E = _UxGT("PID-I *"); + //LSTR MSG_PID_D = _UxGT("PID-D"); + //LSTR MSG_PID_D_E = _UxGT("PID-D *"); + //LSTR MSG_PID_C = _UxGT("PID-C"); + //LSTR MSG_PID_C_E = _UxGT("PID-C *"); + //LSTR MSG_PID_F = _UxGT("PID-F"); + //LSTR MSG_PID_F_E = _UxGT("PID-F *"); + LSTR MSG_SELECT = _UxGT("Wybierz"); + LSTR MSG_SELECT_E = _UxGT("Wybierz *"); + LSTR MSG_ACC = _UxGT("Przyspieszenie"); + LSTR MSG_JERK = _UxGT("Zryw"); + LSTR MSG_VA_JERK = _UxGT("Zryw V") LCD_STR_A; + LSTR MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("Zryw V") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("Zryw V") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("Zryw V") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("Zryw Ve"); + //LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + LSTR MSG_VELOCITY = _UxGT("Prędkość (V)"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vskok min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); + LSTR MSG_VTRAV_MIN = _UxGT("Vskok min"); + LSTR MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-wycofanie"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-przesuń."); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); - //PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("kroki/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" kroki/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroki/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroki/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Ruch"); - //PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; - //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; - //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Wsuń 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("Kontrast LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); - //PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); - //PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); - //PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); - //PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Ekran główny"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Przygotuj"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Strojenie"); - //PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power monitor"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Natężenie"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Napięcie"); - PROGMEM Language_Str MSG_POWER = _UxGT("Moc"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start wydruku"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Następny"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inic."); - //PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drukuj"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetuj"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Przerwij"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Gotowe"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Wstecz"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Kontynuuj"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Pomiń"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Wstrzymywanie..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Wznowienie"); - //PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop"); - //PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Karta SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Brak karty"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Uśpij..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Oczekiwanie..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druk wstrzymany"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Drukowanie..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druk przerwany"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druk zakończony"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Brak ruchu"); - PROGMEM Language_Str MSG_KILLED = _UxGT("Ubity. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("Zatrzymany. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Wycofaj mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Z Wycof. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Wycofaj V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); - //PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); - //PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); - //PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); - //PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); - //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); - //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); - //PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Wsuń Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Wysuń Filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Wysuń Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Wysuń wszystkie"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Inicjal. karty SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Zmiana karty SD"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); - //PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - //PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - //PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - //PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - //PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - //PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); - //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("Najpierw Home %s%s%s"); - //PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); - //PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); - //PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); - //PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - //PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - //PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Błąd temperatury"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); - //PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); - //PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); - PROGMEM Language_Str MSG_HALTED = _UxGT("Drukarka zatrzym."); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); - //PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("g"); // One character only - //PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Rozgrzewanie..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Chłodzenie..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); - //PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe Heating..."); - //PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); - //PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibruj Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibruj środek"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Ustawienia delty"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibrowanie"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ustaw wysokość delty"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Przesun. Z sondy"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Ukośne ramię"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Wysokość"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Promień"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("O drukarce"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info drukarki"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); - //PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); - //PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statystyki"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Ekstrudery"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Predkość USB"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokół"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); - //PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_A_RETRACT = _UxGT("A-wycofanie"); + LSTR MSG_A_TRAVEL = _UxGT("A-przesuń."); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); + //LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); + LSTR MSG_STEPS_PER_MM = _UxGT("kroki/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" kroki/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" kroki/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" kroki/mm"); + LSTR MSG_E_STEPS = _UxGT("E kroki/mm"); + LSTR MSG_EN_STEPS = _UxGT("* kroki/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Ruch"); + //LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; + //LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + //LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); + //LSTR MSG_ADVANCE_K = _UxGT("Advance K"); + //LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); + LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); + LSTR MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); + LSTR MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); + //LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + //LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + //LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + //LSTR MSG_SETTINGS_STORED = _UxGT("Settings Stored"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); + LSTR MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); + LSTR MSG_INFO_SCREEN = _UxGT("Ekran główny"); + LSTR MSG_PREPARE = _UxGT("Przygotuj"); + LSTR MSG_TUNE = _UxGT("Strojenie"); + //LSTR MSG_POWER_MONITOR = _UxGT("Power monitor"); + LSTR MSG_CURRENT = _UxGT("Natężenie"); + LSTR MSG_VOLTAGE = _UxGT("Napięcie"); + LSTR MSG_POWER = _UxGT("Moc"); + LSTR MSG_START_PRINT = _UxGT("Start wydruku"); + LSTR MSG_BUTTON_NEXT = _UxGT("Następny"); + LSTR MSG_BUTTON_INIT = _UxGT("Inic."); + //LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Drukuj"); + LSTR MSG_BUTTON_RESET = _UxGT("Resetuj"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Przerwij"); + LSTR MSG_BUTTON_DONE = _UxGT("Gotowe"); + LSTR MSG_BUTTON_BACK = _UxGT("Wstecz"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Kontynuuj"); + LSTR MSG_BUTTON_SKIP = _UxGT("Pomiń"); + LSTR MSG_PAUSING = _UxGT("Wstrzymywanie..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); + LSTR MSG_RESUME_PRINT = _UxGT("Wznowienie"); + //LSTR MSG_HOST_START_PRINT = _UxGT("Host Start"); + LSTR MSG_STOP_PRINT = _UxGT("Stop"); + //LSTR MSG_END_LOOPS = _UxGT("End Repeat Loops"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); + LSTR MSG_MEDIA_MENU = _UxGT("Karta SD"); + LSTR MSG_NO_MEDIA = _UxGT("Brak karty"); + LSTR MSG_DWELL = _UxGT("Uśpij..."); + LSTR MSG_USERWAIT = _UxGT("Oczekiwanie..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Druk wstrzymany"); + LSTR MSG_PRINTING = _UxGT("Drukowanie..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Druk przerwany"); + LSTR MSG_PRINT_DONE = _UxGT("Druk zakończony"); + LSTR MSG_NO_MOVE = _UxGT("Brak ruchu"); + LSTR MSG_KILLED = _UxGT("Ubity. "); + LSTR MSG_STOPPED = _UxGT("Zatrzymany. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Wycofaj mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Z Wycof. mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Wycofaj V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); + //LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); + //LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); + LSTR MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); + //LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + //LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + //LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + //LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + //LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + //LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + //LSTR MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + //LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + //LSTR MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + //LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Wsuń Filament *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Wysuń Filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Wysuń Filament *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Wysuń wszystkie"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Inicjal. karty SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Zmiana karty SD"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); + LSTR MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); + //LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); + //LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); + //LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + //LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + //LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + //LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + //LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + //LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + //LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + //LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); + //LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + //LSTR MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + //LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + //LSTR MSG_TOUCHMI_SAVE = _UxGT("Save"); + //LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + //LSTR MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + //LSTR MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + LSTR MSG_HOME_FIRST = _UxGT("Najpierw Home %s%s%s"); + //LSTR MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + //LSTR MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + //LSTR MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); + //LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + //LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + //LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Błąd temperatury"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); + //LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + //LSTR MSG_COOLING_FAILED = _UxGT("Cooling Failed"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); + LSTR MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); + LSTR MSG_HALTED = _UxGT("Drukarka zatrzym."); + LSTR MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); + //LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("g"); // One character only + //LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Rozgrzewanie..."); + LSTR MSG_COOLING = _UxGT("Chłodzenie..."); + LSTR MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); + LSTR MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); + //LSTR MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + //LSTR MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); + //LSTR MSG_LASER_COOLING = _UxGT("Laser Cooling..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibruj Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibruj środek"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Ustawienia delty"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibrowanie"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ustaw wysokość delty"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Przesun. Z sondy"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Ukośne ramię"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Wysokość"); + LSTR MSG_DELTA_RADIUS = _UxGT("Promień"); + LSTR MSG_INFO_MENU = _UxGT("O drukarce"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info drukarki"); + LSTR MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); + //LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); + //LSTR MSG_MESH_DONE = _UxGT("Mesh probing done"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Statystyki"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Ekstrudery"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Predkość USB"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokół"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); + //LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Niepoprawna drukarka"); + LSTR MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Niepoprawna drukarka"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Ukończono"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Czas druku"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najdł. druk"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Ukończono"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Czas druku"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdł. druk"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Ukończono"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Razem"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najdł. druk"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Ukończono"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Razem"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdł. druk"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #endif - //PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - //PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Zasilacz"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Siła %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Siła %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC BŁĄD POŁĄCZENIA"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("ZMIEŃ FILAMENT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("WYDRUK WSTRZYMANY"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("WSUŃ FILAMENT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("WYSUŃ FILAMENT"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCJE WZNOWIENIA:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Oczyść więcej"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Kontynuuj"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Dysza: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Czujnik filamentu"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dystans do czujnika mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Zerowanie nieudane"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); + //LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + //LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + LSTR MSG_INFO_PSU = _UxGT("Zasilacz"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Siła %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC BŁĄD POŁĄCZENIA"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ZMIEŃ FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("WYDRUK WSTRZYMANY"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("WSUŃ FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("WYSUŃ FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCJE WZNOWIENIA:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Oczyść więcej"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Kontynuuj"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Dysza: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Czujnik filamentu"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dystans do czujnika mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Zerowanie nieudane"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); - //PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Wznawianie..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Wsuń filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Wsuń wszystko"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Wsuń do dyszy"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Wysuń filament"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Wysuń filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Wysuń filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Wsuwanie fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Wszystko"); - //PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetuj MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); + //LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); + LSTR MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); + LSTR MSG_MMU2_RESUMING = _UxGT("Wznawianie..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Wsuń filament"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Wsuń wszystko"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Wsuń do dyszy"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Wysuń filament"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Wysuń filament ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Wysuń filament"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Wsuwanie fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); + LSTR MSG_MMU2_ALL = _UxGT("Wszystko"); + //LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Resetuj MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); - PROGMEM Language_Str MSG_MIX = _UxGT("Miks"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mikser"); - //PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); - //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("Odwrotny 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:"); + LSTR MSG_MIX = _UxGT("Miks"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); + LSTR MSG_MIXER = _UxGT("Mikser"); + //LSTR MSG_GRADIENT = _UxGT("Gradient"); + LSTR MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); + //LSTR MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + //LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Odwrotny gradient"); + //LSTR MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + //LSTR MSG_START_VTOOL = _UxGT("Start V-tool"); + //LSTR MSG_END_VTOOL = _UxGT(" End V-tool"); + //LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + //LSTR MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + //LSTR MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + //LSTR MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + //LSTR MSG_START_Z = _UxGT("Start Z:"); + //LSTR MSG_END_Z = _UxGT(" End Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Gry"); - //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"); + LSTR MSG_GAMES = _UxGT("Gry"); + //LSTR MSG_BRICKOUT = _UxGT("Brickout"); + //LSTR MSG_INVADERS = _UxGT("Invaders"); + //LSTR MSG_SNAKE = _UxGT("Sn4k3"); + //LSTR MSG_MAZE = _UxGT("Maze"); - //PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); - //PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + //LSTR MSG_BAD_PAGE = _UxGT("Bad page index"); + //LSTR MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Wprowadź cyfrę"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Ustaw/zmień hasło"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Usuń hasło"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Hasło to "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Od nowa"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Pamiętaj by zapisać!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Hasło usunięte"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); + LSTR MSG_ENTER_DIGIT = _UxGT("Wprowadź cyfrę"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Ustaw/zmień hasło"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Usuń hasło"); + LSTR MSG_PASSWORD_SET = _UxGT("Hasło to "); + LSTR MSG_START_OVER = _UxGT("Od nowa"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Pamiętaj by zapisać!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Hasło usunięte"); // // 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("Nacisnik przycisk", "by wznowić drukowanie")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Czekam na", "zmianę filamentu", "by wystartować")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Włóż filament", "i naciśnij przycisk", "by kontynuować")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Naciśnij przycisk", "by nagrzać dyszę")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nagrzewanie dyszy", "Proszę czekać...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Czekam na", "wyjęcie filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Czekam na", "włożenie filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Czekam na", "oczyszczenie filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kliknij by zakończyć", "oczyszczanie filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Czekam na", "wznowienie wydruku...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nacisnik przycisk", "by wznowić drukowanie")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Czekam na", "zmianę filamentu", "by wystartować")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Włóż filament", "i naciśnij przycisk", "by kontynuować")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Naciśnij przycisk", "by nagrzać dyszę")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nagrzewanie dyszy", "Proszę czekać...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Czekam na", "wyjęcie filamentu")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Czekam na", "włożenie filamentu")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Czekam na", "oczyszczenie filamentu")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kliknij by zakończyć", "oczyszczanie filamentu")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Czekam na", "wznowienie wydruku...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknij by kontynuować")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Proszę czekać...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Włóż i kliknij")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknij by nagrzać")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Nagrzewanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Wysuwanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Wsuwanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Oczyszczanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknij by kontynuować")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkowanie...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Proszę czekać...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Włóż i kliknij")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknij by nagrzać")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Nagrzewanie...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Wysuwanie...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Wsuwanie...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Oczyszczanie...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); - //PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); - //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_CORRECTION = _UxGT("Korekcja"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); + LSTR MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); + //LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); + //LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + //LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + //LSTR MSG_SERVICE_RESET = _UxGT("Reset"); + //LSTR MSG_SERVICE_IN = _UxGT(" in:"); + //LSTR MSG_BACKLASH = _UxGT("Backlash"); + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekcja"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); #if ENABLED(TOUCH_UI_FTDI_EVE) - //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); + //LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); #else - //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + //LSTR MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); #endif - //PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); - //PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + //LSTR MSG_REHEAT = _UxGT("Reheat"); + //LSTR MSG_REHEATING = _UxGT("Reheating..."); - //PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); - //PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); - //PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + //LSTR MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + //LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + //LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Dźwięk"); + LSTR MSG_SOUND = _UxGT("Dźwięk"); - //PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); - //PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); - //PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); - //PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); + //LSTR MSG_TOP_LEFT = _UxGT("Top Left"); + //LSTR MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + //LSTR MSG_TOP_RIGHT = _UxGT("Top Right"); + //LSTR MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); - //PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); + //LSTR MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 630f38e2d9..13f62f693b 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -34,141 +34,141 @@ namespace Language_pt { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Portuguese"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Portuguese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desactivar motores"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ir para origem"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Ir para origem X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Ir para origem Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Ir para origem Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Indo para origem"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Click para iniciar"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Próximo ponto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Pronto !"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Definir desvio"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets aplicados"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Definir origem"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); + LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Desactivar motores"); + LSTR MSG_AUTO_HOME = _UxGT("Ir para origem"); + LSTR MSG_AUTO_HOME_X = _UxGT("Ir para origem X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Ir para origem Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Ir para origem Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Indo para origem"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Click para iniciar"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Próximo ponto"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Pronto !"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Definir desvio"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets aplicados"); + LSTR MSG_SET_ORIGIN = _UxGT("Definir origem"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL _UxGT(" Bico"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL _UxGT(" Bico ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Pre-aq. ") PREHEAT_1_LABEL _UxGT(" Tudo"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Pre-aq. ") PREHEAT_1_LABEL _UxGT(" ") LCD_STR_THERMOMETER _UxGT("Base"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Definições ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL _UxGT(" Bico"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL _UxGT(" Bico ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Pre-aq. ") PREHEAT_1_LABEL _UxGT(" Tudo"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Pre-aq. ") PREHEAT_1_LABEL _UxGT(" ") LCD_STR_THERMOMETER _UxGT("Base"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Definições ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Pre-aquecer $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Pre-aquecer $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Pre-aquecer $ Bico"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Pre-aquecer $ Bico ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Pre-aq. $ Tudo"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Pre-aq. $ ") LCD_STR_THERMOMETER _UxGT("Base"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Definições $"); + LSTR MSG_PREHEAT_M = _UxGT("Pre-aquecer $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Pre-aquecer $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Pre-aquecer $ Bico"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Pre-aquecer $ Bico ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Pre-aq. $ Tudo"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Pre-aq. $ ") LCD_STR_THERMOMETER _UxGT("Base"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Definições $"); #endif - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Arrefecer"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Ligar"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Desligar"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudir"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retrair"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixo"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Mover Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Mover Extrusor *"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); - PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Bico"); - PROGMEM Language_Str MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" Bico ~"); - PROGMEM Language_Str MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" Base"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. ventoinha"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. ventoinha ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxo"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxo ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Controlo"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retracção"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-movimento"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passo/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passo/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passo/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passo/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E em mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Diam."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Diam. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Guardar na memoria"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Carregar da memoria"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. de emergen."); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Recarregar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Monitorizar"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Afinar"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impressão"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Retomar impressão"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Parar impressão"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprimir do SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sem cartão SD"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Em espera..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Á espera de ordem"); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impressão cancelada"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sem movimento"); - PROGMEM Language_Str MSG_KILLED = _UxGT("EMERGÊNCIA. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("PARADO. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT(" Retrair mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Troca Retrair mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT(" Retrair V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT(" Levantar mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT(" DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Troca DesRet mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT(" DesRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT(" Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Trocar filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Trocar filamento *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Inici. cartão SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Trocar cartão SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sensor fora/base"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desvio Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Fim de curso"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: T Máxima"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: T Mínima"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Aquecendo..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Aquecendo base..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibração Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + LSTR MSG_COOLDOWN = _UxGT("Arrefecer"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Ligar"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Desligar"); + LSTR MSG_EXTRUDE = _UxGT("Extrudir"); + LSTR MSG_RETRACT = _UxGT("Retrair"); + LSTR MSG_MOVE_AXIS = _UxGT("Mover eixo"); + LSTR MSG_MOVE_X = _UxGT("Mover X"); + LSTR MSG_MOVE_Y = _UxGT("Mover Y"); + LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mover 100mm"); + LSTR MSG_SPEED = _UxGT("Velocidade"); + LSTR MSG_BED_Z = _UxGT("Base Z"); + LSTR MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Bico"); + LSTR MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" Bico ~"); + LSTR MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" Base"); + LSTR MSG_FAN_SPEED = _UxGT("Vel. ventoinha"); + LSTR MSG_FAN_SPEED_N = _UxGT("Vel. ventoinha ~"); + LSTR MSG_FLOW = _UxGT("Fluxo"); + LSTR MSG_FLOW_N = _UxGT("Fluxo ~"); + LSTR MSG_CONTROL = _UxGT("Controlo"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_A_RETRACT = _UxGT("A-retracção"); + LSTR MSG_A_TRAVEL = _UxGT("A-movimento"); + LSTR MSG_STEPS_PER_MM = _UxGT("Passo/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passo/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passo/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passo/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passo/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passo/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passo/mm"); + LSTR MSG_E_STEPS = _UxGT("E passo/mm"); + LSTR MSG_EN_STEPS = _UxGT("* passo/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movimento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E em mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Diam."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Diam. *"); + LSTR MSG_CONTRAST = _UxGT("Contraste"); + LSTR MSG_STORE_EEPROM = _UxGT("Guardar na memoria"); + LSTR MSG_LOAD_EEPROM = _UxGT("Carregar da memoria"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Rest. de emergen."); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Recarregar"); + LSTR MSG_INFO_SCREEN = _UxGT("Monitorizar"); + LSTR MSG_PREPARE = _UxGT("Preparar"); + LSTR MSG_TUNE = _UxGT("Afinar"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausar impressão"); + LSTR MSG_RESUME_PRINT = _UxGT("Retomar impressão"); + LSTR MSG_STOP_PRINT = _UxGT("Parar impressão"); + LSTR MSG_MEDIA_MENU = _UxGT("Imprimir do SD"); + LSTR MSG_NO_MEDIA = _UxGT("Sem cartão SD"); + LSTR MSG_DWELL = _UxGT("Em espera..."); + LSTR MSG_USERWAIT = _UxGT("Á espera de ordem"); + LSTR MSG_PRINT_ABORTED = _UxGT("Impressão cancelada"); + LSTR MSG_NO_MOVE = _UxGT("Sem movimento"); + LSTR MSG_KILLED = _UxGT("EMERGÊNCIA. "); + LSTR MSG_STOPPED = _UxGT("PARADO. "); + LSTR MSG_CONTROL_RETRACT = _UxGT(" Retrair mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Troca Retrair mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT(" Retrair V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT(" Levantar mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT(" DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Troca DesRet mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT(" DesRet V"); + LSTR MSG_AUTORETRACT = _UxGT(" Auto-Retract"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Trocar filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Trocar filamento *"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Inici. cartão SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Trocar cartão SD"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sensor fora/base"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Desvio Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Fim de curso"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: T Máxima"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: T Mínima"); + LSTR MSG_HEATING = _UxGT("Aquecendo..."); + LSTR MSG_BED_HEATING = _UxGT("Aquecendo base..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibração Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Fim de curso"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Fim de curso"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Superior Direto"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); + LSTR MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); + LSTR MSG_TOP_RIGHT = _UxGT("Superior Direto"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); } diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 21be3a2931..f5ab03c44a 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -31,465 +31,465 @@ namespace Language_pt_br { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Portuguese (BR)"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Portuguese (BR)"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pronto."); - PROGMEM Language_Str MSG_YES = _UxGT("SIM"); - PROGMEM Language_Str MSG_NO = _UxGT("NÃO"); - PROGMEM Language_Str MSG_BACK = _UxGT("Voltar"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Abortando..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); - PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("Cartão liberado"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Aguardando cartão"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro de leitura"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB removido"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB falhou"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Fins de curso"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Fins curso"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Config. Avançada"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuração"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Início automático"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Desabilit. motores"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu Debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Testar Barra Progres"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ir a origem XYZ"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Ir na origem X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Ir na origem Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Ir na origem Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto alinhar Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Indo para origem"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Clique para Iniciar"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Próximo Ponto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Fim nivelação!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Suavizar altura"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Compensar origem"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Alteração aplicada"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ajustar Origem"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronto."); + LSTR MSG_YES = _UxGT("SIM"); + LSTR MSG_NO = _UxGT("NÃO"); + LSTR MSG_BACK = _UxGT("Voltar"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abortando..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); + LSTR MSG_MEDIA_RELEASED = _UxGT("Cartão liberado"); + LSTR MSG_MEDIA_WAITING = _UxGT("Aguardando cartão"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro de leitura"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB removido"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB falhou"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Fins de curso"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Fins curso"); + LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Config. Avançada"); + LSTR MSG_CONFIGURATION = _UxGT("Configuração"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Início automático"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Desabilit. motores"); + LSTR MSG_DEBUG_MENU = _UxGT("Menu Debug"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Testar Barra Progres"); + LSTR MSG_AUTO_HOME = _UxGT("Ir a origem XYZ"); + LSTR MSG_AUTO_HOME_X = _UxGT("Ir na origem X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Ir na origem Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Ir na origem Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto alinhar Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Indo para origem"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Clique para Iniciar"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Próximo Ponto"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Fim nivelação!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Suavizar altura"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Compensar origem"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Alteração aplicada"); + LSTR MSG_SET_ORIGIN = _UxGT("Ajustar Origem"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Extrusora ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Extrusora ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Pre-aq.Todo ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Pre-aq.Mesa ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Ajustar ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1 = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Pre-aquecer ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Extrusora ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_END_E = _UxGT("Extrusora ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_ALL = _UxGT("Pre-aq.Todo ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Pre-aq.Mesa ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Ajustar ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Pre-aquecer $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Pre-aquecer $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Extrusora $"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Extrusora $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Pre-aq.Todo $"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Pre-aq.Mesa $"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Ajustar $"); + LSTR MSG_PREHEAT_M = _UxGT("Pre-aquecer $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Pre-aquecer $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Extrusora $"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Extrusora $ ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Pre-aq.Todo $"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Pre-aq.Mesa $"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Ajustar $"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Customizar Pre-aq."); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Esfriar"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Ligar"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Desligar"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrusar"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retrair"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixo"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelação Mesa"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Mesa"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Próximo Canto"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor de Malha"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Malha"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Fim da Edição"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sondando ponto"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comando customizado"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Teste de sonda"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Ponto"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicação"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Cópia espelhada"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Controle Total"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2o bico X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2o bico Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2o bico Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Executando G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Nivel. Mesa Unif."); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Fazer malha manual"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Calçar e calibrar"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Medir"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Remover e calibrar"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Movendo para Próximo"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Ativar UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desativar UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Mesa"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Mesa"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Extrusora"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Extrusora"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Malha"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Editar Malha Custom"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste Fino da Malha"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Fim da Edição"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Montar Malha Custom"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Montar "); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Customizar Pre-aq."); + LSTR MSG_COOLDOWN = _UxGT("Esfriar"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Ligar"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Desligar"); + LSTR MSG_EXTRUDE = _UxGT("Extrusar"); + LSTR MSG_RETRACT = _UxGT("Retrair"); + LSTR MSG_MOVE_AXIS = _UxGT("Mover eixo"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelação Mesa"); + LSTR MSG_LEVEL_BED = _UxGT("Nivelar Mesa"); + LSTR MSG_BED_TRAMMING = _UxGT("Nivelar Cantos"); + LSTR MSG_NEXT_CORNER = _UxGT("Próximo Canto"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor de Malha"); + LSTR MSG_EDIT_MESH = _UxGT("Editar Malha"); + LSTR MSG_EDITING_STOPPED = _UxGT("Fim da Edição"); + LSTR MSG_PROBING_POINT = _UxGT("Sondando ponto"); + LSTR MSG_MESH_X = _UxGT("Índice X"); + LSTR MSG_MESH_Y = _UxGT("Índice Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valor Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comando customizado"); + LSTR MSG_M48_TEST = _UxGT("M48 Teste de sonda"); + LSTR MSG_M48_POINT = _UxGT("M48 Ponto"); + LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicação"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Cópia espelhada"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Controle Total"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2o bico X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2o bico Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2o bico Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Executando G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Nivel. Mesa Unif."); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Fazer malha manual"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Calçar e calibrar"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Medir"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Remover e calibrar"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Movendo para Próximo"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Ativar UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Desativar UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Temp. Mesa"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp. Mesa"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp. Extrusora"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp. Extrusora"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Editar Malha"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Editar Malha Custom"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Ajuste Fino da Malha"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Fim da Edição"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Montar Malha Custom"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Montar "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Montar $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Checar $"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Montar $"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Checar $"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Montar Malha fria"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajustar Altura"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Quant. de Altura"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malha"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malha Custom"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Aquecendo Mesa"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Aquecendo Ext."); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Cancelado"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("G26 Saindo"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malha"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelação da Malha"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelação 3 pontos"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelação Grid"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malha"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Cantos"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Salvar Mapa da Malha"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar Para Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Salvar Malha CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Salvar Backup"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Informação do UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Qtd de Enchimento"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Enchimento Manual"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Enchimento Smart"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Preencher malha"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar tudo"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar próximo"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Ajuste Fino de Todos"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ajustar Mais Próximo"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Armazenamento Malha"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Slot de Memória"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ler Malha"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Salvar Malha"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Malha %i carregada"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Malha %i salva"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sem armazenamento"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro ao salvar UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro no restauro UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Compensação Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Compensação Z parou"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL passo a passo"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Montar Malha fria"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Enchimento Smart"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Validar Malha"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajuste Fino de Todos"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Validar Malha"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajuste Fino de Todos"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Salvar Malha"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Montar Malha fria"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Ajustar Altura"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Quant. de Altura"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malha"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malha Custom"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Aquecendo Mesa"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Aquecendo Ext."); + LSTR MSG_G26_CANCELED = _UxGT("G26 Cancelado"); + LSTR MSG_G26_LEAVING = _UxGT("G26 Saindo"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malha"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Nivelação da Malha"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelação 3 pontos"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelação Grid"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malha"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Cantos"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Salvar Mapa da Malha"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar Para Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Salvar Malha CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Salvar Backup"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Informação do UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Qtd de Enchimento"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Enchimento Manual"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Enchimento Smart"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Preencher malha"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar tudo"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar próximo"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Ajuste Fino de Todos"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Ajustar Mais Próximo"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Armazenamento Malha"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot de Memória"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Ler Malha"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Salvar Malha"); + LSTR MSG_MESH_LOADED = _UxGT("Malha %i carregada"); + LSTR MSG_MESH_SAVED = _UxGT("Malha %i salva"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Sem armazenamento"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Erro ao salvar UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Erro no restauro UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Compensação Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Compensação Z parou"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL passo a passo"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Montar Malha fria"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Enchimento Smart"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Validar Malha"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Ajuste Fino de Todos"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Validar Malha"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Ajuste Fino de Todos"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Salvar Malha"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Controle do LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Luz"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Configuração da Luz"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Luz Vermelha"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Luz Laranja"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Luz Amarela"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Luz Verde"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Luz Azul"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Luz Indigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Luz Violeta"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Luz Branca"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Luz Padrão"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luz Customizada"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidade Vermelho"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidade Verde"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidade Azul"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensidade Branco"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brilho"); + LSTR MSG_LED_CONTROL = _UxGT("Controle do LED"); + LSTR MSG_LEDS = _UxGT("Luz"); + LSTR MSG_LED_PRESETS = _UxGT("Configuração da Luz"); + LSTR MSG_SET_LEDS_RED = _UxGT("Luz Vermelha"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Luz Laranja"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Luz Amarela"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Luz Verde"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Luz Azul"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Luz Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Luz Violeta"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Luz Branca"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Luz Padrão"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Luz Customizada"); + LSTR MSG_INTENSITY_R = _UxGT("Intensidade Vermelho"); + LSTR MSG_INTENSITY_G = _UxGT("Intensidade Verde"); + LSTR MSG_INTENSITY_B = _UxGT("Intensidade Azul"); + LSTR MSG_INTENSITY_W = _UxGT("Intensidade Branco"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brilho"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Movendo..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Liberar XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Mover Extrusor"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Mover Extrusor *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Extrus. mto fria"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Mover %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bocal"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Bocal ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Mesa"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. Ventoinha"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. Ventoinha ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("+Vel. Ventoinha"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("+Vel. Ventoinha ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Vazão"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Vazão ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Controle"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Máx"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fator"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temp. Automática"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Ligado"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Desligado"); - PROGMEM Language_Str MSG_SELECT = _UxGT("Selecionar"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Selecionar *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Acel."); - PROGMEM Language_Str MSG_JERK = _UxGT("Arrancada"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("arrancada V") LCD_STR_A; - PROGMEM Language_Str MSG_VB_JERK = _UxGT("arrancada V") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("arrancada V") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("arrancada V") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("arrancada V") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("arrancada V") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("arrancada VE"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desv. Junção"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VDeslocamento min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Aceleração"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Retrair A"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Movimento A"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passo/mm"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("Passo ") LCD_STR_A _UxGT("/mm"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("Passo ") LCD_STR_B _UxGT("/mm"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("Passo ") LCD_STR_C _UxGT("/mm"); - PROGMEM Language_Str MSG_I_STEPS = _UxGT("Passo ") LCD_STR_I _UxGT("/mm"); - PROGMEM Language_Str MSG_J_STEPS = _UxGT("Passo ") LCD_STR_J _UxGT("/mm"); - PROGMEM Language_Str MSG_K_STEPS = _UxGT("Passo ") LCD_STR_K _UxGT("/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Extrusão em mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diâmetro Fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diâmetro Fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarr. mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carregar mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avanço K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avanço K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Contraste"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Salvar Configuração"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Ler Configuração"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restauro seguro"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Iniciar EEPROM"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Atualiz. SD"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetar Impressora"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Atualização"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Informações"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Ajustar"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Iniciar Impressão"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Prox."); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Iniciar"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Parar"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimir"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetar"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Pronto"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Voltar"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Continuar"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impressão"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Continuar impressão"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Parar impressão"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimindo objeto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impressão"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Imprimir do SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sem cartão SD"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Dormindo..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Clique para retomar"); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Impressão Pausada"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimindo..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impressão Abortada"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sem movimento"); - PROGMEM Language_Str MSG_KILLED = _UxGT("PARADA DE EMERGÊNCIA"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("PAROU. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retrair mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Retrair Troca mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retrair V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saltar mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Des-Retrair mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Des-RetTroca mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Des-Retrair V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Des-RetTroca V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Retração Automática"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Distancia Retração"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Distancia Purga"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Mudar Ferramenta"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Preparar Veloc."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Veloc. Retração"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Standby bico"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Trocar Filamento"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Trocar Filamento *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Carregar Filamento"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Carregar Filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Descarreg. Filamento"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Descarreg. Filamento *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Descarregar Todos"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciar SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Trocar SD"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Liberar SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda fora da mesa"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Fator de Cisalho"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Testar BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reiniciar BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Recolher BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Estender BLTouch"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda-Z"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Recolher Sonda-Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Home %s%s%s Primeiro"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Compensar Sonda"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Compensar Sonda em X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Compensar Sonda em Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Compensar Sonda em Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Passinho X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Passinho Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Passinho Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Abortar Fim de Curso"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ESCAPE TÉRMICO"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ESCAPE TÉRMICO MESA"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ESCAPE TÉRMICO CAMARA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Erro:Temp Máxima"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Erro:Temp Mínima"); - PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESSORA PAROU"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Favor resetar"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Aquecendo..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Resfriando..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Aquecendo mesa..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Esfriando mesa..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Aquecendo Câmara..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Esfriando Câmara..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibrar Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Configuração Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-Calibração"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Calibrar Altura"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Desloc. Sonda Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Haste Diagonal"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Raio"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Sobre"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Impressora"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelamento 3 pontos"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelamento Linear"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelamento Bilinear"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelamento UBL"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelamento da Malha"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. da Placa"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusoras"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Taxa de Transmissão"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); + LSTR MSG_MOVING = _UxGT("Movendo..."); + LSTR MSG_FREE_XY = _UxGT("Liberar XY"); + LSTR MSG_MOVE_X = _UxGT("Mover X"); + LSTR MSG_MOVE_Y = _UxGT("Mover Y"); + LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); + LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Extrus. mto fria"); + LSTR MSG_MOVE_N_MM = _UxGT("Mover %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Mover 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Mover 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Mover 100mm"); + LSTR MSG_SPEED = _UxGT("Velocidade"); + LSTR MSG_BED_Z = _UxGT("Base Z"); + LSTR MSG_NOZZLE = _UxGT("Bocal"); + LSTR MSG_NOZZLE_N = _UxGT("Bocal ~"); + LSTR MSG_BED = _UxGT("Mesa"); + LSTR MSG_FAN_SPEED = _UxGT("Vel. Ventoinha"); + LSTR MSG_FAN_SPEED_N = _UxGT("Vel. Ventoinha ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("+Vel. Ventoinha"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("+Vel. Ventoinha ~"); + LSTR MSG_FLOW = _UxGT("Vazão"); + LSTR MSG_FLOW_N = _UxGT("Vazão ~"); + LSTR MSG_CONTROL = _UxGT("Controle"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Máx"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fator"); + LSTR MSG_AUTOTEMP = _UxGT("Temp. Automática"); + LSTR MSG_LCD_ON = _UxGT("Ligado"); + LSTR MSG_LCD_OFF = _UxGT("Desligado"); + LSTR MSG_SELECT = _UxGT("Selecionar"); + LSTR MSG_SELECT_E = _UxGT("Selecionar *"); + LSTR MSG_ACC = _UxGT("Acel."); + LSTR MSG_JERK = _UxGT("Arrancada"); + LSTR MSG_VA_JERK = _UxGT("arrancada V") LCD_STR_A; + LSTR MSG_VB_JERK = _UxGT("arrancada V") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("arrancada V") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("arrancada V") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("arrancada V") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("arrancada V") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("arrancada VE"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desv. Junção"); + LSTR MSG_VELOCITY = _UxGT("Velocidade"); + LSTR MSG_VTRAV_MIN = _UxGT("VDeslocamento min"); + LSTR MSG_ACCELERATION = _UxGT("Aceleração"); + LSTR MSG_A_RETRACT = _UxGT("Retrair A"); + LSTR MSG_A_TRAVEL = _UxGT("Movimento A"); + LSTR MSG_STEPS_PER_MM = _UxGT("Passo/mm"); + LSTR MSG_A_STEPS = _UxGT("Passo ") LCD_STR_A _UxGT("/mm"); + LSTR MSG_B_STEPS = _UxGT("Passo ") LCD_STR_B _UxGT("/mm"); + LSTR MSG_C_STEPS = _UxGT("Passo ") LCD_STR_C _UxGT("/mm"); + LSTR MSG_I_STEPS = _UxGT("Passo ") LCD_STR_I _UxGT("/mm"); + LSTR MSG_J_STEPS = _UxGT("Passo ") LCD_STR_J _UxGT("/mm"); + LSTR MSG_K_STEPS = _UxGT("Passo ") LCD_STR_K _UxGT("/mm"); + LSTR MSG_E_STEPS = _UxGT("E/mm"); + LSTR MSG_EN_STEPS = _UxGT("*/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_MOTION = _UxGT("Movimento"); + LSTR MSG_FILAMENT = _UxGT("Filamento"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("Extrusão em mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Diâmetro Fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Diâmetro Fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Descarr. mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Carregar mm"); + LSTR MSG_ADVANCE_K = _UxGT("Avanço K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Avanço K *"); + LSTR MSG_CONTRAST = _UxGT("Contraste"); + LSTR MSG_STORE_EEPROM = _UxGT("Salvar Configuração"); + LSTR MSG_LOAD_EEPROM = _UxGT("Ler Configuração"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restauro seguro"); + LSTR MSG_INIT_EEPROM = _UxGT("Iniciar EEPROM"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Atualiz. SD"); + LSTR MSG_RESET_PRINTER = _UxGT("Resetar Impressora"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Atualização"); + LSTR MSG_INFO_SCREEN = _UxGT("Informações"); + LSTR MSG_PREPARE = _UxGT("Preparar"); + LSTR MSG_TUNE = _UxGT("Ajustar"); + LSTR MSG_START_PRINT = _UxGT("Iniciar Impressão"); + LSTR MSG_BUTTON_NEXT = _UxGT("Prox."); + LSTR MSG_BUTTON_INIT = _UxGT("Iniciar"); + LSTR MSG_BUTTON_STOP = _UxGT("Parar"); + LSTR MSG_BUTTON_PRINT = _UxGT("Imprimir"); + LSTR MSG_BUTTON_RESET = _UxGT("Resetar"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Cancelar"); + LSTR MSG_BUTTON_DONE = _UxGT("Pronto"); + LSTR MSG_BUTTON_BACK = _UxGT("Voltar"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Continuar"); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausar impressão"); + LSTR MSG_RESUME_PRINT = _UxGT("Continuar impressão"); + LSTR MSG_STOP_PRINT = _UxGT("Parar impressão"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimindo objeto"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impressão"); + LSTR MSG_MEDIA_MENU = _UxGT("Imprimir do SD"); + LSTR MSG_NO_MEDIA = _UxGT("Sem cartão SD"); + LSTR MSG_DWELL = _UxGT("Dormindo..."); + LSTR MSG_USERWAIT = _UxGT("Clique para retomar"); + LSTR MSG_PRINT_PAUSED = _UxGT("Impressão Pausada"); + LSTR MSG_PRINTING = _UxGT("Imprimindo..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Impressão Abortada"); + LSTR MSG_NO_MOVE = _UxGT("Sem movimento"); + LSTR MSG_KILLED = _UxGT("PARADA DE EMERGÊNCIA"); + LSTR MSG_STOPPED = _UxGT("PAROU. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retrair mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Retrair Troca mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retrair V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saltar mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Des-Retrair mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Des-RetTroca mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Des-Retrair V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Des-RetTroca V"); + LSTR MSG_AUTORETRACT = _UxGT("Retração Automática"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Distancia Retração"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Distancia Purga"); + LSTR MSG_TOOL_CHANGE = _UxGT("Mudar Ferramenta"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Preparar Veloc."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Veloc. Retração"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Standby bico"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Trocar Filamento"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Trocar Filamento *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Carregar Filamento"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Carregar Filamento *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Descarreg. Filamento"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Descarreg. Filamento *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Descarregar Todos"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Trocar SD"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Liberar SD"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda fora da mesa"); + LSTR MSG_SKEW_FACTOR = _UxGT("Fator de Cisalho"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Testar BLTouch"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reiniciar BLTouch"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Recolher BLTouch"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Estender BLTouch"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda-Z"); + LSTR MSG_MANUAL_STOW = _UxGT("Recolher Sonda-Z"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s Primeiro"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Compensar Sonda"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Compensar Sonda em X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Compensar Sonda em Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Compensar Sonda em Z"); + LSTR MSG_BABYSTEP_X = _UxGT("Passinho X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Passinho Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Passinho Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Abortar Fim de Curso"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ESCAPE TÉRMICO"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ESCAPE TÉRMICO MESA"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ESCAPE TÉRMICO CAMARA"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Erro:Temp Máxima"); + LSTR MSG_ERR_MINTEMP = _UxGT("Erro:Temp Mínima"); + LSTR MSG_HALTED = _UxGT("IMPRESSORA PAROU"); + LSTR MSG_PLEASE_RESET = _UxGT("Favor resetar"); + LSTR MSG_SHORT_DAY = _UxGT("d"); + LSTR MSG_SHORT_HOUR = _UxGT("h"); + LSTR MSG_SHORT_MINUTE = _UxGT("m"); + LSTR MSG_HEATING = _UxGT("Aquecendo..."); + LSTR MSG_COOLING = _UxGT("Resfriando..."); + LSTR MSG_BED_HEATING = _UxGT("Aquecendo mesa..."); + LSTR MSG_BED_COOLING = _UxGT("Esfriando mesa..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Aquecendo Câmara..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Esfriando Câmara..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibrar Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Configuração Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-Calibração"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Calibrar Altura"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Desloc. Sonda Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Haste Diagonal"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Altura"); + LSTR MSG_DELTA_RADIUS = _UxGT("Raio"); + LSTR MSG_INFO_MENU = _UxGT("Sobre"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Impressora"); + LSTR MSG_3POINT_LEVELING = _UxGT("Nivelamento 3 pontos"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Nivelamento Linear"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Nivelamento Bilinear"); + LSTR MSG_UBL_LEVELING = _UxGT("Nivelamento UBL"); + LSTR MSG_MESH_LEVELING = _UxGT("Nivelamento da Malha"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info. da Placa"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrusoras"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Taxa de Transmissão"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Impressora"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Intensidade Brilho"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); + LSTR MSG_CASE_LIGHT = _UxGT("Luz da Impressora"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Intensidade Brilho"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total de Impressões"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Realizadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo de Impressão"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Trabalho Mais longo"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total de Extrusão"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total de Impressões"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Realizadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo de Impressão"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Trabalho Mais longo"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total de Extrusão"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Qtd de Impressões"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Realizadas"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo de Impressão"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Maior trabalho"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("T. Extrusão"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Qtd de Impressões"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Realizadas"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo de Impressão"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Maior trabalho"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("T. Extrusão"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Força do Motor"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escrever EEPROM DAC"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("TROCA DE FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESSÃO PAUSADA"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARREGAR FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARREG. FILAMENTO"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Config. de Retomada"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar mais"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar Impressão"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bocal: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor filamento"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Falha ao ir à origem"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Falha ao sondar"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Força do Motor"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escrever EEPROM DAC"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("TROCA DE FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESSÃO PAUSADA"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARREGAR FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARREG. FILAMENTO"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Config. de Retomada"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar mais"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continuar Impressão"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bocal: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Sensor filamento"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Falha ao ir à origem"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Falha ao sondar"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLHER FILAMENTO"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLHER FILAMENTO"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Continuar Impressão"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Continuando..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Carregar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Carregar Todos"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Carregar para bocal"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejetar Filamento"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Ejetar Filamento ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Liberar Filamento"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Carregando Fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejetando Fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Carregando Fil...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Todos"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetar MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetando MMU..."); + LSTR MSG_MMU2_RESUME = _UxGT("Continuar Impressão"); + LSTR MSG_MMU2_RESUMING = _UxGT("Continuando..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Carregar Filamento"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Carregar Todos"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Carregar para bocal"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Ejetar Filamento"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Ejetar Filamento ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Liberar Filamento"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Carregando Fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejetando Fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Carregando Fil...."); + LSTR MSG_MMU2_ALL = _UxGT("Todos"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + LSTR MSG_MMU2_RESET = _UxGT("Resetar MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Resetando MMU..."); - PROGMEM Language_Str MSG_GAMES = _UxGT("Jogos"); - 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("Labirinto"); + LSTR MSG_GAMES = _UxGT("Jogos"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Labirinto"); #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Aperte o botão para", "continuar impressão")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperando o", "inicio da", "troca de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Coloque filamento", "pressione o botão", "para continuar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pressione o botão", "p/ aquecer o bocal")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Aquecendo o bocal", "Aguarde...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Esperando", "remoção de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Esperando", "filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere pela", "purga de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Clique para finaliz.", "purga de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impressão", "continuar")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Aperte o botão para", "continuar impressão")); + LSTR MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Esperando o", "inicio da", "troca de filamento")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Coloque filamento", "pressione o botão", "para continuar...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Pressione o botão", "p/ aquecer o bocal")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Aquecendo o bocal", "Aguarde...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Esperando", "remoção de filamento")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Esperando", "filamento")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere pela", "purga de filamento")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Clique para finaliz.", "purga de filamento")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impressão", "continuar")); #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Clique p. continuar")); - PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Aguarde...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insira e Clique")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Clique para Aquecer")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Aquecendo...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Ejetando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Carregando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Clique p. finalizar")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Continuando...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Clique p. continuar")); + LSTR MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Aguarde...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insira e Clique")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Clique para Aquecer")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Aquecendo...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Ejetando...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Carregando...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Clique p. finalizar")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Continuando...")); #endif - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Superior Direto"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); + LSTR MSG_TOP_LEFT = _UxGT("Superior Esquerdo"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Inferior Esquerdo"); + LSTR MSG_TOP_RIGHT = _UxGT("Superior Direto"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Inferior Direto"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibração Completa"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibração Falhou"); } diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index b1208eac25..364a83fb3f 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -32,606 +32,606 @@ namespace Language_ro { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Romanian"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Romanian"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Pregatit."); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("DA"); - PROGMEM Language_Str MSG_NO = _UxGT("NU"); - PROGMEM Language_Str MSG_BACK = _UxGT("Inapoi"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Abandon..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media Introdus"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media Inlaturat"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Astept Media"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Eroare Citire Media"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Dispozitiv USB Inlaturat"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Pornire USB Esuata"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Eroare:Subcall Overflow"); - 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("Principal"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Setari Avansate"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configurare"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Dezactivare Motoare"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Meniu Debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test Bara Progres"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Acasa"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Acasa X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Acasa Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Acasa Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Aliniere-Z"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Acasa XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Click pentru a incepe"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Urmatorul Punct"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivelare Terminata!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Inaltime"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Seteaza Offseturile Acasa"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offseturi Aplicate"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Seteaza Originea"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Pregatit."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("DA"); + LSTR MSG_NO = _UxGT("NU"); + LSTR MSG_BACK = _UxGT("Inapoi"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abandon..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Media Introdus"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Media Inlaturat"); + LSTR MSG_MEDIA_WAITING = _UxGT("Astept Media"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Eroare Citire Media"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispozitiv USB Inlaturat"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Pornire USB Esuata"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Eroare:Subcall Overflow"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); + LSTR MSG_MAIN = _UxGT("Principal"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Setari Avansate"); + LSTR MSG_CONFIGURATION = _UxGT("Configurare"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Dezactivare Motoare"); + LSTR MSG_DEBUG_MENU = _UxGT("Meniu Debug"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test Bara Progres"); + LSTR MSG_AUTO_HOME = _UxGT("Auto Acasa"); + LSTR MSG_AUTO_HOME_X = _UxGT("Acasa X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Acasa Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Acasa Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Aliniere-Z"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Acasa XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Click pentru a incepe"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Urmatorul Punct"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivelare Terminata!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Fade Inaltime"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Seteaza Offseturile Acasa"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offseturi Aplicate"); + LSTR MSG_SET_ORIGIN = _UxGT("Seteaza Originea"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preincalzeste ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preincalzeste ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Capatul"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Capatul ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Tot"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Patul"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Conf"); + LSTR MSG_PREHEAT_1 = _UxGT("Preincalzeste ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Preincalzeste ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Capatul"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Capatul ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Tot"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Patul"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preincalzeste ") PREHEAT_1_LABEL _UxGT(" Conf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Preincalzeste $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Preincalzeste $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Preincalzeste $ Capatul"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Preincalzeste $ Capatul ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Preincalzeste $ Tot"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Preincalzeste $ Patul"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Preincalzeste $ Conf"); + LSTR MSG_PREHEAT_M = _UxGT("Preincalzeste $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Preincalzeste $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preincalzeste $ Capatul"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preincalzeste $ Capatul ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preincalzeste $ Tot"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preincalzeste $ Patul"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preincalzeste $ Conf"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preincalzeste Personalizat"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Racire"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecventa"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Laser"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Puterea Laserului"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Controlul Spindle"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Puterea Spindle"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindle Invers"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Porneste"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Opreste"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudeaza"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Retracteaza"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Muta Axa"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelarea Patului"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveleaza Patul"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Niveleaza Colturile"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Urmatorul Colt"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mesh"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editeaza Mesh"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Editarea Meshului Oprita"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Punctul de Probare"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valoare Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Comenzi Personalizate"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probe Test"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("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("Doing G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Tools"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("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"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Moving to next"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activate UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Deactivate UBL"); - 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"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Done Editing Mesh"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Build Custom Mesh"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Build Mesh"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Preincalzeste Personalizat"); + LSTR MSG_COOLDOWN = _UxGT("Racire"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frecventa"); + LSTR MSG_LASER_MENU = _UxGT("Control Laser"); + LSTR MSG_LASER_POWER = _UxGT("Puterea Laserului"); + LSTR MSG_SPINDLE_MENU = _UxGT("Controlul Spindle"); + LSTR MSG_SPINDLE_POWER = _UxGT("Puterea Spindle"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindle Invers"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Porneste"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Opreste"); + LSTR MSG_EXTRUDE = _UxGT("Extrudeaza"); + LSTR MSG_RETRACT = _UxGT("Retracteaza"); + LSTR MSG_MOVE_AXIS = _UxGT("Muta Axa"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelarea Patului"); + LSTR MSG_LEVEL_BED = _UxGT("Niveleaza Patul"); + LSTR MSG_BED_TRAMMING = _UxGT("Niveleaza Colturile"); + LSTR MSG_NEXT_CORNER = _UxGT("Urmatorul Colt"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor Mesh"); + LSTR MSG_EDIT_MESH = _UxGT("Editeaza Mesh"); + LSTR MSG_EDITING_STOPPED = _UxGT("Editarea Meshului Oprita"); + LSTR MSG_PROBING_POINT = _UxGT("Punctul de Probare"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Valoare Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comenzi Personalizate"); + LSTR MSG_M48_TEST = _UxGT("M48 Probe Test"); + LSTR MSG_M48_POINT = _UxGT("M48 Point"); + LSTR MSG_M48_DEVIATION = _UxGT("Deviation"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX Mode"); + LSTR MSG_OFFSETS_MENU = _UxGT("Tool Offsets"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Doing G29"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL Tools"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Tilting Point"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manually Build Mesh"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Place Shim & Measure"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Measure"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Remove & Measure Bed"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Moving to next"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Activate UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Deactivate UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Bed Temp"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hotend Temp"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Mesh Edit"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit Custom Mesh"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Fine Tuning Mesh"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Done Editing Mesh"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Build Custom Mesh"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Build Mesh"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Build Mesh ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Validate Mesh ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Build Mesh ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validate Mesh ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Build Cold Mesh"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Adjust Mesh Height"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Height Amount"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validate Mesh"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validate Custom Mesh"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Heating Bed"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("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 Canceled"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("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"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Grid Mesh Leveling"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Level Mesh"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Side Points"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Map Type"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Output Mesh Map"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Output for Host"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Output for CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Off Imprimanta Backup"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Output UBL Info"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Fill-in Amount"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manual Fill-in"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Smart Fill-in"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Fill-in Mesh"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidate All"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidate Closest"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Fine Tune All"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Fine Tune Closest"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Storage"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("No Storage"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stopped"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Step-By-Step UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Build Cold Mesh"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Fill-in"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validate Mesh"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Fine Tune All"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validate Mesh"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Fine Tune All"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Save Bed Mesh"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Build Cold Mesh"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Adjust Mesh Height"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Height Amount"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validate Mesh"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validate Custom Mesh"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Heating Bed"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Heating Nozzle"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manual priming..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fixed Length Prime"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Done Priming"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Canceled"); + LSTR MSG_G26_LEAVING = _UxGT("Leaving G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Continue Bed Mesh"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Mesh Leveling"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Point Leveling"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Grid Mesh Leveling"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Level Mesh"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Side Points"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Map Type"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Output Mesh Map"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Output for Host"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Output for CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Off Imprimanta Backup"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Output UBL Info"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Fill-in Amount"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manual Fill-in"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart Fill-in"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Fill-in Mesh"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidate All"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidate Closest"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Fine Tune All"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Fine Tune Closest"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Storage"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Memory Slot"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Load Bed Mesh"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Save Bed Mesh"); + LSTR MSG_MESH_LOADED = _UxGT("Mesh %i Loaded"); + LSTR MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("No Storage"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stopped"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Step-By-Step UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Build Cold Mesh"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Fill-in"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validate Mesh"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Fine Tune All"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validate Mesh"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Fine Tune All"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Save Bed Mesh"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Control"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Lights"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Light Presets"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Red"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Yellow"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Green"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blue"); - 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_CUSTOM_LEDS = _UxGT("Custom Lights"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Red Intensity"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Green Intensity"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Blue Intensity"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("White Intensity"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brightness"); + LSTR MSG_LED_CONTROL = _UxGT("LED Control"); + LSTR MSG_LEDS = _UxGT("Lights"); + LSTR MSG_LED_PRESETS = _UxGT("Light Presets"); + LSTR MSG_SET_LEDS_RED = _UxGT("Red"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Yellow"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Green"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Blue"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("White"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Default"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Custom Lights"); + LSTR MSG_INTENSITY_R = _UxGT("Red Intensity"); + LSTR MSG_INTENSITY_G = _UxGT("Green Intensity"); + LSTR MSG_INTENSITY_B = _UxGT("Blue Intensity"); + LSTR MSG_INTENSITY_W = _UxGT("White Intensity"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brightness"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Moving..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Free XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Capat Prea Rece"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Move %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); - PROGMEM Language_Str MSG_BED = _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("Fan Speed ~"); - 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("Extra Fan Speed ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller Fan"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flow"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flow ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 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_PID_AUTOTUNE = _UxGT("PID Autotune"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Select"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Select *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); - PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-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("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleration"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Travel"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" steps/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Esteps/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*steps/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Motion"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Unload mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("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 Contrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Store Settings"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Load Settings"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initialize EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Update"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reset Imprimanta"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_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_POWER_MONITOR = _UxGT("Power monitor"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Intensitate"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Voltaj"); - PROGMEM Language_Str MSG_POWER = _UxGT("Putere"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start Imprimare"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Urmatorul"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Initiere"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimeaza"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reseteaza"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignora"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Anuleaza"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("OK"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Inapoi"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceed"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); - 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 Media"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("No Media"); - 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_PRINT_DONE = _UxGT("Print Done"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("No Move."); - PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPED. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retract mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Swap Length"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purge Length"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Tool Inlocuire"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Retract Speed"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto Pornit"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto Oprit"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migrare"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Inlocuire Filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Inlocuire Filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Incarcare Filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Incarcare Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Scoatere Filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Scoatere Filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Scoate Tot"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Atasare Media"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Inlocuire Media"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Eliberare Media"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Probe Past Bed"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Skew Factor"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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("Home %s%s%s First"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Probe Z Offset"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("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("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_HALTED = _UxGT("PRINTER HALTED"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - 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("Calibrate X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrate Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrate Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); - 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("Probe Z-offset"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Inaltime"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radius"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Despre Imprimanta"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info Imprimanta"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelare in 3 puncte"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelare Lineara"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelare Bilineara"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelarea Patului Unificata"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelare Mesh"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Status Imprimanta"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Informatii Placa"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistoare"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrudere"); - 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_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_MOVING = _UxGT("Moving..."); + LSTR MSG_FREE_XY = _UxGT("Free XY"); + LSTR MSG_MOVE_X = _UxGT("Move X"); + LSTR MSG_MOVE_Y = _UxGT("Move Y"); + LSTR MSG_MOVE_Z = _UxGT("Move Z"); + LSTR MSG_MOVE_E = _UxGT("Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Extruder *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Capat Prea Rece"); + LSTR MSG_MOVE_N_MM = _UxGT("Move %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Move 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Move 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Move 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Move 100mm"); + LSTR MSG_SPEED = _UxGT("Speed"); + LSTR MSG_BED_Z = _UxGT("Bed Z"); + LSTR MSG_NOZZLE = _UxGT("Nozzle"); + LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); + LSTR MSG_BED = _UxGT("Bed"); + LSTR MSG_CHAMBER = _UxGT("Enclosure"); + LSTR MSG_FAN_SPEED = _UxGT("Fan Speed"); + LSTR MSG_FAN_SPEED_N = _UxGT("Fan Speed ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fan Speed"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fan Speed ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Controller Fan"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); + LSTR MSG_FLOW = _UxGT("Flow"); + LSTR MSG_FLOW_N = _UxGT("Flow ~"); + LSTR MSG_CONTROL = _UxGT("Control"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("On"); + LSTR MSG_LCD_OFF = _UxGT("Off"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + LSTR MSG_SELECT = _UxGT("Select"); + LSTR MSG_SELECT_E = _UxGT("Select *"); + LSTR MSG_ACC = _UxGT("Accel"); + LSTR MSG_JERK = _UxGT("Jerk"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk"); + LSTR MSG_VE_JERK = _UxGT("Ve-Jerk"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + LSTR MSG_VELOCITY = _UxGT("Velocity"); + LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); + LSTR MSG_ACCELERATION = _UxGT("Acceleration"); + LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Amax *"); + LSTR MSG_A_RETRACT = _UxGT("A-Retract"); + LSTR MSG_A_TRAVEL = _UxGT("A-Travel"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); + LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" steps/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" steps/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" steps/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" steps/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" steps/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" steps/mm"); + LSTR MSG_E_STEPS = _UxGT("Esteps/mm"); + LSTR MSG_EN_STEPS = _UxGT("*steps/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperature"); + LSTR MSG_MOTION = _UxGT("Motion"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Fil. Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Fil. Dia. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Unload mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Load mm"); + LSTR MSG_ADVANCE_K = _UxGT("Advance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); + LSTR MSG_CONTRAST = _UxGT("LCD Contrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Store Settings"); + LSTR MSG_LOAD_EEPROM = _UxGT("Load Settings"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); + LSTR MSG_INIT_EEPROM = _UxGT("Initialize EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + LSTR MSG_SETTINGS_STORED = _UxGT("Settings Stored"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Media Update"); + LSTR MSG_RESET_PRINTER = _UxGT("Reset Imprimanta"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Refresh"); + LSTR MSG_INFO_SCREEN = _UxGT("Info Screen"); + LSTR MSG_PREPARE = _UxGT("Prepare"); + LSTR MSG_TUNE = _UxGT("Tune"); + LSTR MSG_POWER_MONITOR = _UxGT("Power monitor"); + LSTR MSG_CURRENT = _UxGT("Intensitate"); + LSTR MSG_VOLTAGE = _UxGT("Voltaj"); + LSTR MSG_POWER = _UxGT("Putere"); + LSTR MSG_START_PRINT = _UxGT("Start Imprimare"); + LSTR MSG_BUTTON_NEXT = _UxGT("Urmatorul"); + LSTR MSG_BUTTON_INIT = _UxGT("Initiere"); + LSTR MSG_BUTTON_STOP = _UxGT("Stop"); + LSTR MSG_BUTTON_PRINT = _UxGT("Imprimeaza"); + LSTR MSG_BUTTON_RESET = _UxGT("Reseteaza"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignora"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Anuleaza"); + LSTR MSG_BUTTON_DONE = _UxGT("OK"); + LSTR MSG_BUTTON_BACK = _UxGT("Inapoi"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Proceed"); + LSTR MSG_PAUSING = _UxGT("Pausing..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); + LSTR MSG_RESUME_PRINT = _UxGT("Resume Print"); + LSTR MSG_STOP_PRINT = _UxGT("Stop Print"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Printing Object"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Outage Recovery"); + LSTR MSG_MEDIA_MENU = _UxGT("Print from Media"); + LSTR MSG_NO_MEDIA = _UxGT("No Media"); + LSTR MSG_DWELL = _UxGT("Sleep..."); + LSTR MSG_USERWAIT = _UxGT("Click to Resume..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Print Paused"); + LSTR MSG_PRINTING = _UxGT("Printing..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Print Aborted"); + LSTR MSG_PRINT_DONE = _UxGT("Print Done"); + LSTR MSG_NO_MOVE = _UxGT("No Move."); + LSTR MSG_KILLED = _UxGT("KILLED. "); + LSTR MSG_STOPPED = _UxGT("STOPPED. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retract mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retract V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Swap Length"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Purge Length"); + LSTR MSG_TOOL_CHANGE = _UxGT("Tool Inlocuire"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime Speed"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Retract Speed"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto Pornit"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto Oprit"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migrare"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Inlocuire Filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Inlocuire Filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Incarcare Filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Incarcare Filament *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Scoatere Filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Scoatere Filament *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Scoate Tot"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Atasare Media"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Inlocuire Media"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Eliberare Media"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z Probe Past Bed"); + LSTR MSG_SKEW_FACTOR = _UxGT("Skew Factor"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("DANGER: Bad settings can cause damage! Proceed anyway?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Save"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + LSTR MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + LSTR MSG_HOME_FIRST = _UxGT("Home %s%s%s First"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Probe Z Offset"); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: REDUNDANT TEMP"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); + LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); + LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); + LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Heating..."); + LSTR MSG_COOLING = _UxGT("Cooling..."); + LSTR MSG_BED_HEATING = _UxGT("Bed Heating..."); + LSTR MSG_BED_COOLING = _UxGT("Bed Cooling..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Chamber Heating..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Chamber Cooling..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Calibration"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Calibrate X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrate Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrate Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Settings"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibration"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Set Delta Height"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Probe Z-offset"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Inaltime"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); + LSTR MSG_INFO_MENU = _UxGT("Despre Imprimanta"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info Imprimanta"); + LSTR MSG_3POINT_LEVELING = _UxGT("Nivelare in 3 puncte"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Nivelare Lineara"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Nivelare Bilineara"); + LSTR MSG_UBL_LEVELING = _UxGT("Nivelarea Patului Unificata"); + LSTR MSG_MESH_LEVELING = _UxGT("Nivelare Mesh"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Status Imprimanta"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Informatii Placa"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistoare"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrudere"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protocol"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: OFF"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: ON"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Case Light"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); + LSTR MSG_CASE_LIGHT = _UxGT("Case Light"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total Printuri"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completat"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Timp Imprimare Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extrudat"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total Printuri"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completat"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Timp Imprimare Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extrudat"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Prints"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Longest"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Prints"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temperatura Minima"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temperatura Maxima"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("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"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("RESUME OPTIONS:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purge more"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continue"); - 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("Runout Dist mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Temperatura Minima"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Temperatura Maxima"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMENT CHANGE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("PRINT PAUSED"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LOAD FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("UNLOAD FILAMENT"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("RESUME OPTIONS:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purge more"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Continue"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozzle: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout Sensor"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Resume"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Resuming..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Load"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Load All"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Load to Nozzle"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Eject"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Eject ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Unload"); - 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("MMU Resetting..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Update MMU Firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); + LSTR MSG_MMU2_RESUME = _UxGT("MMU Resume"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU Resuming..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Load"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Load All"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Load to Nozzle"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Eject"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Eject ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Unload"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Loading Fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejecting Fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Unloading Fil...."); + LSTR MSG_MMU2_ALL = _UxGT("All"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Reset MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU Resetting..."); + LSTR 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:"); + LSTR MSG_MIX = _UxGT("Mix"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Component ="); + LSTR MSG_MIXER = _UxGT("Mixer"); + LSTR MSG_GRADIENT = _UxGT("Gradient"); + LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Toggle Mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Reverse Gradient"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + LSTR MSG_START_VTOOL = _UxGT("Start V-tool"); + LSTR MSG_END_VTOOL = _UxGT(" End V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + LSTR MSG_START_Z = _UxGT("Start Z:"); + LSTR MSG_END_Z = _UxGT(" End Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Jocuri"); - 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"); + LSTR MSG_GAMES = _UxGT("Jocuri"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + LSTR MSG_BAD_PAGE = _UxGT("Bad page index"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); // // Filament Inlocuire 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("Apasa Butonul", "pentru a reveni la print")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcare...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Astept ca", "inlocuirea filamentului", "sa inceapa")); - 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_HEATING = _UxGT(MSG_2_LINE("Nozzle heating", "Please wait...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wait for", "filament unload")); - 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("Click to finish", "filament purge")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wait for print", "to resume...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Apasa Butonul", "pentru a reveni la print")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcare...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Astept ca", "inlocuirea filamentului", "sa inceapa")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Insert filament", "and press button", "to continue")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Press button", "to heat nozzle")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozzle heating", "Please wait...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Wait for", "filament unload")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Wait for", "filament load")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Wait for", "filament purge")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Click to finish", "filament purge")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Wait for print", "to resume...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Click to continue")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcare...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Va rog asteptati...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insert and Click")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Click pentru incalzire")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Incalzire...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Ejectare...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Incarcare...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Curatare...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Click pentru a termina")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Se Reia...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Click to continue")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcare...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Va rog asteptati...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Insert and Click")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Click pentru incalzire")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Incalzire...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Ejectare...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Incarcare...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Curatare...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Click pentru a termina")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Se Reia...")); #endif - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corectare"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); + LSTR MSG_TMC_CURRENT = _UxGT("Driver Current"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorless Homing"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + LSTR MSG_SERVICE_RESET = _UxGT("Reset"); + LSTR MSG_SERVICE_IN = _UxGT(" in:"); + LSTR MSG_BACKLASH = _UxGT("Backlash"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corectare"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivelare Axa X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrare"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout Incalzitor"); - PROGMEM Language_Str MSG_REHEAT = _UxGT("Reincalzire"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Reincalzire..."); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivelare Axa X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrare"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Timeout Incalzitor"); + LSTR MSG_REHEAT = _UxGT("Reincalzire"); + LSTR MSG_REHEATING = _UxGT("Reincalzire..."); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 5f5afb049c..83fd5a3ac3 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -32,880 +32,880 @@ namespace Language_ru { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Russian"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Russian"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Готов."); - PROGMEM Language_Str MSG_YES = _UxGT("Да"); - PROGMEM Language_Str MSG_NO = _UxGT("Нет"); - PROGMEM Language_Str MSG_BACK = _UxGT("Назад"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Прерывание..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD-карта вставлена"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD-карта извлечена"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Вставьте SD-карту"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Готов."); + LSTR MSG_YES = _UxGT("Да"); + LSTR MSG_NO = _UxGT("Нет"); + LSTR MSG_BACK = _UxGT("Назад"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Прерывание..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD-карта вставлена"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD-карта извлечена"); + LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD-карту"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Сбой инициализации SD"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Сбой инициализации SD"); #else - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Сбой инициализ. SD"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Сбой инициализ. SD"); #endif - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Ошибка считывания"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Ошибка считывания"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполнение вызова"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполнение вызова"); #else - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполн. вызова"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполн. вызова"); #endif - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. эндстопы"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Эндстопы"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Основное меню"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Другие настройки"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Конфигурация"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Выключить двигатели"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Меню отладки"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Тест индикатора"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Парковка XYZ"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Парковка X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Итерация: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Точность достигнута"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Нулевое положение"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Нажмите чтобы начать"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Следующая точка"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Выравнивание готово!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. эндстопы"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Эндстопы"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Основное меню"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Другие настройки"); + LSTR MSG_CONFIGURATION = _UxGT("Конфигурация"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Выключить двигатели"); + LSTR MSG_DEBUG_MENU = _UxGT("Меню отладки"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Тест индикатора"); + LSTR MSG_AUTO_HOME = _UxGT("Парковка XYZ"); + LSTR MSG_AUTO_HOME_X = _UxGT("Парковка X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); + LSTR MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); + LSTR MSG_ITERATION = _UxGT("G34 Итерация: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Точность достигнута"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Нулевое положение"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Нажмите чтобы начать"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Следующая точка"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Выравнивание готово!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; #else - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; #endif - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Установить ноль"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); + LSTR MSG_SET_ORIGIN = _UxGT("Установить ноль"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); + LSTR MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); #else - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); + LSTR MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); #endif #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Преднагрев ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрев ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" сопло"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" сопло ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" всё"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" стол"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" правка"); + LSTR MSG_PREHEAT_1 = _UxGT("Преднагрев ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Нагрев ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" сопло"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" сопло ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" всё"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" стол"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Нагрев ") PREHEAT_1_LABEL _UxGT(" правка"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Преднагрев $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Нагрев $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Нагрев $ сопло"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Нагрев $ сопло ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Нагрев $ всё"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Нагрев $ стол"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Нагрев $ правка"); + LSTR MSG_PREHEAT_M = _UxGT("Преднагрев $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Нагрев $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Нагрев $ сопло"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Нагрев $ сопло ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Нагрев $ всё"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Нагрев $ стол"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Нагрев $ правка"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрев Свой"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Охлаждение"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Управление лазером"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Нагрев Свой"); + LSTR MSG_COOLDOWN = _UxGT("Охлаждение"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Частота"); + LSTR MSG_LASER_MENU = _UxGT("Управление лазером"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпиндель"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); + LSTR MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); + LSTR MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпиндель"); + LSTR MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); + LSTR MSG_LASER_POWER = _UxGT("Мощность лазера"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); #else - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинд."); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключ.лазер"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпинд"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощн. лазера"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключ. обдув"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключ. вакуум"); + LSTR MSG_SPINDLE_MENU = _UxGT("Управление шпинд."); + LSTR MSG_LASER_TOGGLE = _UxGT("Переключ.лазер"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпинд"); + LSTR MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); + LSTR MSG_LASER_POWER = _UxGT("Мощн. лазера"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Переключ. обдув"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключ. вакуум"); #endif - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Включить питание"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Выключить питание"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Экструзия"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Втягивание"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Движение по осям"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Выравнивание стола"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Выровнять стол"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Выровнять углы"); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Следующий угол"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Включить питание"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Выключить питание"); + LSTR MSG_EXTRUDE = _UxGT("Экструзия"); + LSTR MSG_RETRACT = _UxGT("Втягивание"); + LSTR MSG_MOVE_AXIS = _UxGT("Движение по осям"); + LSTR MSG_BED_LEVELING = _UxGT("Выравнивание стола"); + LSTR MSG_LEVEL_BED = _UxGT("Выровнять стол"); + LSTR MSG_BED_TRAMMING = _UxGT("Выровнять углы"); + LSTR MSG_NEXT_CORNER = _UxGT("Следующий угол"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до срабатыв. зонда"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до срабатыв. зонда"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); #else - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до сраб. зонда"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав."); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до сраб. зонда"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав."); #endif - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хорошие точки: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Последняя Z: "); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хорошие точки: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Последняя Z: "); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение по Z"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); + LSTR MSG_MESH_EDITOR = _UxGT("Смещение по Z"); + LSTR MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); #else - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение Z"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка окончена"); + LSTR MSG_MESH_EDITOR = _UxGT("Смещение Z"); + LSTR MSG_EDITING_STOPPED = _UxGT("Правка окончена"); #endif - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Редактировать сетку"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Точка сетки"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Индекс X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Индекс Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значение Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Свои команды"); + LSTR MSG_EDIT_MESH = _UxGT("Редактировать сетку"); + LSTR MSG_PROBING_POINT = _UxGT("Точка сетки"); + LSTR MSG_MESH_X = _UxGT("Индекс X"); + LSTR MSG_MESH_Y = _UxGT("Индекс Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Значение Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Свои команды"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 тест Z-зонда"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Отклонение"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 точка"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за пределами"); + LSTR MSG_M48_TEST = _UxGT("M48 тест Z-зонда"); + LSTR MSG_M48_DEVIATION = _UxGT("Отклонение"); + LSTR MSG_M48_POINT = _UxGT("M48 точка"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за пределами"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Меню IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Размещение сопел"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто парковка"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Размножение"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Зеркальная копия"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Полный контроль"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Дублировать X-зазор"); + LSTR MSG_IDEX_MENU = _UxGT("Меню IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Размещение сопел"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто парковка"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Размножение"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Зеркальная копия"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Полный контроль"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("Дублировать X-зазор"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2-е сопло X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2-е сопло Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2-е сопло Z"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2-е сопло X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2-е сопло Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2-е сопло Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Выполняем G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Инструменты UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Настройка UBL"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Выполняем G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Инструменты UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Настройка UBL"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); #else - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу, измерить"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать, измер. стол"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу, измерить"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Убрать, измер. стол"); #endif - PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Мастер сеток UBL"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Измерение"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Двигаемся дальше"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активировать UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивировать UBL"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редактор сеток"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Править свою сетку"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("Мастер сеток UBL"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Измерение"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Двигаемся дальше"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Активировать UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивировать UBL"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Редактор сеток"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Править свою сетку"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Температура стола"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура стола"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Температура сопла"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою сетку"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка сетки завершена"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Температура стола"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура стола"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Температура сопла"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою сетку"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка сетки завершена"); #else - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" стола,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка завершена"); + LSTR MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" стола,") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка завершена"); #endif - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); #else - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Строить холод.сетку"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Строить холод.сетку"); #endif - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Правка высоты сетки"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Правка высоты сетки"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); #else - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Провер. свою сетку"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Провер. свою сетку"); #endif - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрев стола"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрев сопла"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ручная грунтовка"); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Грунт фикс. длины"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Грунтовка сделана"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 завершена"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Выйти из G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Продолжить сетку"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Выравнивание сетки"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 нагрев стола"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрев сопла"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Ручная грунтовка"); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Грунт фикс. длины"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Грунтовка сделана"); + LSTR MSG_G26_CANCELED = _UxGT("G26 завершена"); + LSTR MSG_G26_LEAVING = _UxGT("Выйти из G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Продолжить сетку"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Выравнивание сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-х точечное выравнивание"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-х точечное выравнивание"); #else - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точечное выравн."); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точечное выравн."); #endif - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Калибровка растера"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Выровнять сетку"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Крайние точки"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Тип карты"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Вывести карту сетки"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Вывести на хост"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вывести в CSV"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Калибровка растера"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Выровнять сетку"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Крайние точки"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Тип карты"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Вывести карту сетки"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Вывести на хост"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вывести в CSV"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); #else - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить снаружи"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Информация UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполн."); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить снаружи"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Информация UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполн."); #endif - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ручное заполнение"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Умное заполнение"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заполнить сетку"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Аннулировать всё"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Аннулир. ближайшую"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно править всё"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Настр. ближ. точку"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Хранилище сеток"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Слот памяти"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Загрузить сетку"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Сохранить сетку"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Сетка %i загружена"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Сетка %i сохранена"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Нет хранилища"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Ошибка: Сохран. UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Ошибка: Восстан.UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Смещение Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Смещение Z останов."); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL пошагово"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Строить холодную"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Умное заполнение"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Проверить сетку"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Точно настр. всё"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Проверить сетку"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Точно настр. всё"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Сохранить сетку"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ручное заполнение"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Умное заполнение"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Заполнить сетку"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Аннулировать всё"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Аннулир. ближайшую"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно править всё"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Настр. ближ. точку"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Хранилище сеток"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Слот памяти"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Загрузить сетку"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Сохранить сетку"); + LSTR MSG_MESH_LOADED = _UxGT("Сетка %i загружена"); + LSTR MSG_MESH_SAVED = _UxGT("Сетка %i сохранена"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Нет хранилища"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Ошибка: Сохран. UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Ошибка: Восстан.UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Смещение Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Смещение Z останов."); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL пошагово"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Строить холодную"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Умное заполнение"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Проверить сетку"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Точно настр. всё"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Проверить сетку"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Точно настр. всё"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Сохранить сетку"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Настройка подсветки"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Подсветка"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Предустановки света"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Красный"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Оранжевый"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Жёлтый"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Зелёный"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Синий"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Индиго"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Фиолетовый"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Белый"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Свет по умолчанию"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Канал ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Свет #2"); + LSTR MSG_LED_CONTROL = _UxGT("Настройка подсветки"); + LSTR MSG_LEDS = _UxGT("Подсветка"); + LSTR MSG_LED_PRESETS = _UxGT("Предустановки света"); + LSTR MSG_SET_LEDS_RED = _UxGT("Красный"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Оранжевый"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Жёлтый"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Зелёный"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Синий"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Индиго"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Фиолетовый"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Белый"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Свет по умолчанию"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); + LSTR MSG_LEDS2 = _UxGT("Свет #2"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Свет #2 предустановки"); + LSTR MSG_NEO2_PRESETS = _UxGT("Свет #2 предустановки"); #else - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Свет #2 предустан."); + LSTR MSG_NEO2_PRESETS = _UxGT("Свет #2 предустан."); #endif - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яркость"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Свой цвет подсветки"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Уровень красного"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Уровень зелёного"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Уровень синего"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Уровень белого"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Яркость"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Яркость"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Свой цвет подсветки"); + LSTR MSG_INTENSITY_R = _UxGT("Уровень красного"); + LSTR MSG_INTENSITY_G = _UxGT("Уровень зелёного"); + LSTR MSG_INTENSITY_B = _UxGT("Уровень синего"); + LSTR MSG_INTENSITY_W = _UxGT("Уровень белого"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Яркость"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Движемся..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Освободить XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Движение по X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Движение по Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Экструдер"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Экструдер *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Движение %sмм"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Движение 0.1мм"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Движение 1мм"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Движение 10мм"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Движение 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Скорость"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z стола"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Сопло ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Сопло запарковано"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); - PROGMEM Language_Str MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + LSTR MSG_MOVING = _UxGT("Движемся..."); + LSTR MSG_FREE_XY = _UxGT("Освободить XY"); + LSTR MSG_MOVE_X = _UxGT("Движение по X"); + LSTR MSG_MOVE_Y = _UxGT("Движение по Y"); + LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); + LSTR MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Экструдер"); + LSTR MSG_MOVE_EN = _UxGT("Экструдер *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); + LSTR MSG_MOVE_N_MM = _UxGT("Движение %sмм"); + LSTR MSG_MOVE_01MM = _UxGT("Движение 0.1мм"); + LSTR MSG_MOVE_1MM = _UxGT("Движение 1мм"); + LSTR MSG_MOVE_10MM = _UxGT("Движение 10мм"); + LSTR MSG_MOVE_100MM = _UxGT("Движение 100mm"); + LSTR MSG_SPEED = _UxGT("Скорость"); + LSTR MSG_BED_Z = _UxGT("Z стола"); + LSTR MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; + LSTR MSG_NOZZLE_N = _UxGT("Сопло ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Сопло запарковано"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); + LSTR MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; + LSTR MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охлажд."); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); + LSTR MSG_COOLER = _UxGT("Охлаждение лазера"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Переключ. охлажд."); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); #else - PROGMEM Language_Str MSG_COOLER = _UxGT("Охлажд. лазера"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключ. охл."); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопас.потока"); + LSTR MSG_COOLER = _UxGT("Охлажд. лазера"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Переключ. охл."); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Безопас.потока"); #endif - PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Кулер"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Сохранённый кулер ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Дополн. кулер"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Дополн. кулер ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Контроллер кулера"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холостые обороты"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Автовключение"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Рабочие обороты"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Период простоя"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Поток"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Поток ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Настройки"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С мин"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Автотемпер."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Вкл"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Выкл"); + LSTR MSG_LASER = _UxGT("Лазер"); + LSTR MSG_FAN_SPEED = _UxGT("Кулер"); + LSTR MSG_FAN_SPEED_N = _UxGT("Кулер ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Сохранённый кулер ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Дополн. кулер"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Дополн. кулер ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Контроллер кулера"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холостые обороты"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Автовключение"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Рабочие обороты"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Период простоя"); + LSTR MSG_FLOW = _UxGT("Поток"); + LSTR MSG_FLOW_N = _UxGT("Поток ~"); + LSTR MSG_CONTROL = _UxGT("Настройки"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С мин"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); + LSTR MSG_AUTOTEMP = _UxGT("Автотемпер."); + LSTR MSG_LCD_ON = _UxGT("Вкл"); + LSTR MSG_LCD_OFF = _UxGT("Выкл"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Автоподбор PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Автоподбор PID *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Подбор PID выполнен"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Сбой автоподбора. Плохой экструдер."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Сбой автоподбора. Температура повышена."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Сбой автоподбора! Завершение времени."); + LSTR MSG_PID_AUTOTUNE = _UxGT("Автоподбор PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Автоподбор PID *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Подбор PID выполнен"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Сбой автоподбора. Плохой экструдер."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Сбой автоподбора. Температура повышена."); + LSTR MSG_PID_TIMEOUT = _UxGT("Сбой автоподбора! Завершение времени."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Выбор"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Выбор *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Ускорение"); - PROGMEM Language_Str MSG_JERK = _UxGT("Рывок"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-рывок"); + LSTR MSG_SELECT = _UxGT("Выбор"); + LSTR MSG_SELECT_E = _UxGT("Выбор *"); + LSTR MSG_ACC = _UxGT("Ускорение"); + LSTR MSG_JERK = _UxGT("Рывок"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); + LSTR MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); #else - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Отклон. узла"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклон. узла"); #endif - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Скорость, мм/с"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Скор.макс *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Скор.мин"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Перемещение мин"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Ускорение, мм/с2"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Ускор.макс *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ускор.втягив."); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Ускор.путеш."); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мин."); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Шагов/мм"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E шаг/мм"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* шаг/мм"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Движение"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Филамент"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E огран.,мм") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E огран. *"); + LSTR MSG_VELOCITY = _UxGT("Скорость, мм/с"); + LSTR MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Скор.макс *"); + LSTR MSG_VMIN = _UxGT("Скор.мин"); + LSTR MSG_VTRAV_MIN = _UxGT("Перемещение мин"); + LSTR MSG_ACCELERATION = _UxGT("Ускорение, мм/с2"); + LSTR MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Ускор.макс *"); + LSTR MSG_A_RETRACT = _UxGT("Ускор.втягив."); + LSTR MSG_A_TRAVEL = _UxGT("Ускор.путеш."); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мин."); + LSTR MSG_STEPS_PER_MM = _UxGT("Шагов/мм"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); + LSTR MSG_E_STEPS = _UxGT("E шаг/мм"); + LSTR MSG_EN_STEPS = _UxGT("* шаг/мм"); + LSTR MSG_TEMPERATURE = _UxGT("Температура"); + LSTR MSG_MOTION = _UxGT("Движение"); + LSTR MSG_FILAMENT = _UxGT("Филамент"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E огран.,мм") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E огран. *"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Диам. филамента"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Диам. филамента *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Диам. филамента"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Диам. филамента *"); #else - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Диам. филам."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Диам. филам. *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Диам. филам."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Диам. филам. *"); #endif - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Загрузка, мм"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Выгрузка, мм"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Kоэф. продвиж."); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Kоэф. продвиж. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Контраст экрана"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Загрузка, мм"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Выгрузка, мм"); + LSTR MSG_ADVANCE_K = _UxGT("Kоэф. продвиж."); + LSTR MSG_ADVANCE_K_E = _UxGT("Kоэф. продвиж. *"); + LSTR MSG_CONTRAST = _UxGT("Контраст экрана"); + LSTR MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); + LSTR MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); + LSTR MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); #else - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые парам."); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализ. EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("На базовые парам."); + LSTR MSG_INIT_EEPROM = _UxGT("Инициализ. EEPROM"); #endif - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Сбой EEPROM: CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Сбой EEPROM: индекс"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Сбой EEPROM: версия"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметры сохранены"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Обновление прошивки"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Сброс принтера"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Главный экран"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Подготовить"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Настроить"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Монитор питания"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Ток"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Напряжение"); - PROGMEM Language_Str MSG_POWER = _UxGT("Мощность"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Начало печати"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Сбой EEPROM: CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Сбой EEPROM: индекс"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Сбой EEPROM: версия"); + LSTR MSG_SETTINGS_STORED = _UxGT("Параметры сохранены"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Обновление прошивки"); + LSTR MSG_RESET_PRINTER = _UxGT("Сброс принтера"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); + LSTR MSG_INFO_SCREEN = _UxGT("Главный экран"); + LSTR MSG_PREPARE = _UxGT("Подготовить"); + LSTR MSG_TUNE = _UxGT("Настроить"); + LSTR MSG_POWER_MONITOR = _UxGT("Монитор питания"); + LSTR MSG_CURRENT = _UxGT("Ток"); + LSTR MSG_VOLTAGE = _UxGT("Напряжение"); + LSTR MSG_POWER = _UxGT("Мощность"); + LSTR MSG_START_PRINT = _UxGT("Начало печати"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Дальше"); //short text for buttons - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Иниц-я"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Стоп"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Печать"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Сброс"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Игнорир."); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Отмена"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Готово"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Назад"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Продолжить"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Пропустить"); + LSTR MSG_BUTTON_NEXT = _UxGT("Дальше"); //short text for buttons + LSTR MSG_BUTTON_INIT = _UxGT("Иниц-я"); + LSTR MSG_BUTTON_STOP = _UxGT("Стоп"); + LSTR MSG_BUTTON_PRINT = _UxGT("Печать"); + LSTR MSG_BUTTON_RESET = _UxGT("Сброс"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Игнорир."); + LSTR MSG_BUTTON_CANCEL = _UxGT("Отмена"); + LSTR MSG_BUTTON_DONE = _UxGT("Готово"); + LSTR MSG_BUTTON_BACK = _UxGT("Назад"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Продолжить"); + LSTR MSG_BUTTON_SKIP = _UxGT("Пропустить"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Пауза печати"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Продолжить печать"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Старт с хоста"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Остановить печать"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Печать объекта"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Завершить объект"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Завершить объект ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Восстановение сбоя"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Печать с SD карты"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Нет SD карты"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Сон..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Продолжить..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Печать на паузе"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Печать..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Печать отменена"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Печать завершена"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Нет движения."); - PROGMEM Language_Str MSG_KILLED = _UxGT("УБИТО. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ОСТАНОВЛЕНО. "); + LSTR MSG_PAUSE_PRINT = _UxGT("Пауза печати"); + LSTR MSG_RESUME_PRINT = _UxGT("Продолжить печать"); + LSTR MSG_HOST_START_PRINT = _UxGT("Старт с хоста"); + LSTR MSG_STOP_PRINT = _UxGT("Остановить печать"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Печать объекта"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Завершить объект"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершить объект ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Восстановение сбоя"); + LSTR MSG_MEDIA_MENU = _UxGT("Печать с SD карты"); + LSTR MSG_NO_MEDIA = _UxGT("Нет SD карты"); + LSTR MSG_DWELL = _UxGT("Сон..."); + LSTR MSG_USERWAIT = _UxGT("Продолжить..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Печать на паузе"); + LSTR MSG_PRINTING = _UxGT("Печать..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Печать отменена"); + LSTR MSG_PRINT_DONE = _UxGT("Печать завершена"); + LSTR MSG_NO_MOVE = _UxGT("Нет движения."); + LSTR MSG_KILLED = _UxGT("УБИТО. "); + LSTR MSG_STOPPED = _UxGT("ОСТАНОВЛЕНО. "); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягивание, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Смена втягив., мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Возврат смены, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Возврат смены, V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягивание"); + LSTR MSG_CONTROL_RETRACT = _UxGT("Втягивание, мм"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Смена втягив., мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Возврат смены, мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Возврат смены, V"); + LSTR MSG_AUTORETRACT = _UxGT("Автовтягивание"); #else - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягив., мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Смена втяг.,мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Возвр.смены,мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Возвр.смены V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягив."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Втягив., мм"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Смена втяг.,мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Возвр.смены,мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Возвр.смены V"); + LSTR MSG_AUTORETRACT = _UxGT("Автовтягив."); #endif - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Подскок, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Втягивание V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Возврат, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Возврат V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Подскок, мм"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Втягивание V"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Возврат, мм"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Возврат V"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Поменять длины"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Поменять длины"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнительно"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнительно"); #else - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнит."); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнит."); #endif - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистить длину"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистить длину"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Смена сопел"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Поднятие по Z"); + LSTR MSG_TOOL_CHANGE = _UxGT("Смена сопел"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Поднятие по Z"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Начальная скор."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Скорость втягив."); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Начальная скор."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Скорость втягив."); #else - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Началь.скор."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Скор.втягив."); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Началь.скор."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Скор.втягив."); #endif - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Парковать голову"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Вернуть скорость"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Обороти кулера"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Время кулера"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Авто Вкл."); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Авто Выкл."); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Замена инструмента"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Авто замена"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Последний экструдер"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Замена на *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Смена филамента"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Смена филамента *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Загрузить филамент"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Парковать голову"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Вернуть скорость"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Обороти кулера"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Время кулера"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Авто Вкл."); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Авто Выкл."); + LSTR MSG_TOOL_MIGRATION = _UxGT("Замена инструмента"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Авто замена"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Последний экструдер"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Замена на *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Смена филамента"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Смена филамента *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Загрузить филамент"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Загрузить филамент *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Выгрузить филамент *"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Загрузить филамент *"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Выгрузить филамент *"); #else - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Подать филамент *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Убрать филамент *"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Подать филамент *"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Убрать филамент *"); #endif - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Выгрузить всё"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Установить SD карту"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Сменить SD карту"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Освободить SD карту"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z-зонд вне стола"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Фактор наклона"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("Z-зонд BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Тестирование BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Сброс BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Поднять BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Опустить BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Режим SW"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Режим 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Режим OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Режим сохранения"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Установить на 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Установить на OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Слив отчёта"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("ОПАСНОСТЬ: Неправильные параметры приводят к повреждениям! Продолжить?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("Z-Зонд TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Инициализация"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Тест Z-смещения"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Сохранить"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Установить TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Установить зонд"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Загрузить зонд"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Сначала паркуй %s%s%s"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Смещения Z-зонда"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Выгрузить всё"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Установить SD карту"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Сменить SD карту"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Освободить SD карту"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z-зонд вне стола"); + LSTR MSG_SKEW_FACTOR = _UxGT("Фактор наклона"); + LSTR MSG_BLTOUCH = _UxGT("Z-зонд BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Тестирование BLTouch"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Сброс BLTouch"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Поднять BLTouch"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Опустить BLTouch"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Режим SW"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Режим 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Режим OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Режим сохранения"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Установить на 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Установить на OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Слив отчёта"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("ОПАСНОСТЬ: Неправильные параметры приводят к повреждениям! Продолжить?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("Z-Зонд TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Инициализация"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Тест Z-смещения"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Сохранить"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Установить TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Установить зонд"); + LSTR MSG_MANUAL_STOW = _UxGT("Загрузить зонд"); + LSTR MSG_HOME_FIRST = _UxGT("Сначала паркуй %s%s%s"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Смещения Z-зонда"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); #else - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); #endif - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Микрошаг X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Ошибка:Избыточная Т"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("УТЕЧКА ОХЛАЖДЕНИЯ"); - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХЛАДИТЬ НЕ УДАЛОСЬ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); - PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Сделайте сброс"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("ч"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("м"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрев..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Охлаждение..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрев стола..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охлаждение стола..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрев зонда..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охлаждение зонда..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охладжение камеры..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охлаждение лазера..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калибровка Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калибровать X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровать Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калибровать Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровать центр"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); + LSTR MSG_BABYSTEP_X = _UxGT("Микрошаг X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Ошибка:Избыточная Т"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("УТЕЧКА ОХЛАЖДЕНИЯ"); + LSTR MSG_COOLING_FAILED = _UxGT("ОХЛАДИТЬ НЕ УДАЛОСЬ"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); + LSTR MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); + LSTR MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); + LSTR MSG_PLEASE_RESET = _UxGT("Сделайте сброс"); + LSTR MSG_SHORT_DAY = _UxGT("д"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("ч"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("м"); // One character only + LSTR MSG_HEATING = _UxGT("Нагрев..."); + LSTR MSG_COOLING = _UxGT("Охлаждение..."); + LSTR MSG_BED_HEATING = _UxGT("Нагрев стола..."); + LSTR MSG_BED_COOLING = _UxGT("Охлаждение стола..."); + LSTR MSG_PROBE_HEATING = _UxGT("Нагрев зонда..."); + LSTR MSG_PROBE_COOLING = _UxGT("Охлаждение зонда..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Охладжение камеры..."); + LSTR MSG_LASER_COOLING = _UxGT("Охлаждение лазера..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Калибровка Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Калибровать X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровать Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Калибровать Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калибровать центр"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); #else - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); #endif - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Высота"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радиус"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("О принтере"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Данные принтера"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); + LSTR MSG_DELTA_HEIGHT = _UxGT("Высота"); + LSTR MSG_DELTA_RADIUS = _UxGT("Радиус"); + LSTR MSG_INFO_MENU = _UxGT("О принтере"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Данные принтера"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точечное выравнивание"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Линейное выравнивание"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Билинейное выравнивание"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-точечное выравнивание"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Линейное выравнивание"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Билинейное выравнивание"); #else - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точ. выравнив."); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Линейное выравн."); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Билин. выравнив."); + LSTR MSG_3POINT_LEVELING = _UxGT("3-точ. выравнив."); + LSTR MSG_LINEAR_LEVELING = _UxGT("Линейное выравн."); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Билин. выравнив."); #endif - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Управление UBL"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); + LSTR MSG_UBL_LEVELING = _UxGT("Управление UBL"); + LSTR MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондирование выполнено"); + LSTR MSG_MESH_DONE = _UxGT("Зондирование выполнено"); #else - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); + LSTR MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); #endif - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Данные платы"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Термисторы"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Экструдеры"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Скорость,БОД"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Протокол"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Данные платы"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Термисторы"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Экструдеры"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Скорость,БОД"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Протокол"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль утечки Т: Выкл"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Контроль утечки Т: Вкл"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Время простоя хотенда"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль утечки Т: Выкл"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контроль утечки Т: Вкл"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Время простоя хотенда"); #else - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Контр.утечки Т:Выкл"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Контр.утечки Т:Вкл"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Время прост.хот-а"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контр.утечки Т:Выкл"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контр.утечки Т:Вкл"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Время прост.хот-а"); #endif - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Подсветка корпуса"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); + LSTR MSG_CASE_LIGHT = _UxGT("Подсветка корпуса"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Длина филамента"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Длина филамента"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Напечатано"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Выдавлено"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Напечатано"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Общее время"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Выдавлено"); #endif - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Мин. ") LCD_STR_THERMOMETER; - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("БП"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Сила привода"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМЕНА ФИЛАМЕНТА"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("ПЕЧАТЬ НА ПАУЗЕ"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ЗАГРУЗКА ФИЛАМЕНТА"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("ВЫГРУЗКА ФИЛАМЕНТА"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ОПЦИИ ПРОДОЛЖЕНИЯ:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Выдавить ещё"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Возобновить печать"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопла: "); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Мин. ") LCD_STR_THERMOMETER; + LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; + LSTR MSG_INFO_PSU = _UxGT("БП"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила привода"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); + LSTR MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМЕНА ФИЛАМЕНТА"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("ПЕЧАТЬ НА ПАУЗЕ"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ЗАГРУЗКА ФИЛАМЕНТА"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("ВЫГРУЗКА ФИЛАМЕНТА"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ОПЦИИ ПРОДОЛЖЕНИЯ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Выдавить ещё"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Возобновить печать"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопла: "); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч. филамента"); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч. филамента"); #else - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч.филам."); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч.филам."); #endif - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("До конца, мм"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Ошибка парковки"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Ошибка зондирования"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("До конца, мм"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Ошибка парковки"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Ошибка зондирования"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ВЫБИРЕТЕ ФИЛАМЕНТ"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("Настройки MMU"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ВЫБИРЕТЕ ФИЛАМЕНТ"); + LSTR MSG_MMU2_MENU = _UxGT("Настройки MMU"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Обновить прошивку MMU!"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Обновить прошивку MMU!"); #else - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Обнови прошивку MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Обнови прошивку MMU"); #endif - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU требует внимания"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Продолжить печать"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Продолжение..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Загрузить филамент"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Загрузить всё"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Загрузить в сопло"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Извлечь филамент"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Извлечь филамент ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Выгрузить филамент"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Загрузка %i..."); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU требует внимания"); + LSTR MSG_MMU2_RESUME = _UxGT("Продолжить печать"); + LSTR MSG_MMU2_RESUMING = _UxGT("Продолжение..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Загрузить филамент"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Загрузить всё"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Загрузить в сопло"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Извлечь филамент"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Извлечь филамент ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Выгрузить филамент"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Загрузка %i..."); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлечение филамента..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлечение филамента..."); #else - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлеч.филамента..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлеч.филамента..."); #endif - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Выгрузка...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Всё"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Филамент ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Перезапуск MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Удалите и нажмите"); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Выгрузка...."); + LSTR MSG_MMU2_ALL = _UxGT("Всё"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Филамент ~"); + LSTR MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Перезапуск MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Удалите и нажмите"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MIX = _UxGT("Смешивание"); + LSTR MSG_MIX = _UxGT("Смешивание"); #else - PROGMEM Language_Str MSG_MIX = _UxGT("Смешив."); + LSTR MSG_MIX = _UxGT("Смешив."); #endif - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Смеситель"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градиент"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Полный градиент"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Цикличное смешивание"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градиент смешивания"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Сменить градиент"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); + LSTR MSG_MIXER = _UxGT("Смеситель"); + LSTR MSG_GRADIENT = _UxGT("Градиент"); + LSTR MSG_FULL_GRADIENT = _UxGT("Полный градиент"); + LSTR MSG_CYCLE_MIX = _UxGT("Цикличное смешивание"); + LSTR MSG_GRADIENT_MIX = _UxGT("Градиент смешивания"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Сменить градиент"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключить смешивание"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Активация В-инструм."); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Начало В-инструмента"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Конец В-инструмента"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инструмента"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Сброс В-инструментов"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструменты"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструменты сброшены"); + LSTR MSG_TOGGLE_MIX = _UxGT("Переключить смешивание"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Активация В-инструм."); + LSTR MSG_START_VTOOL = _UxGT("Начало В-инструмента"); + LSTR MSG_END_VTOOL = _UxGT("Конец В-инструмента"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инструмента"); + LSTR MSG_RESET_VTOOLS = _UxGT("Сброс В-инструментов"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструменты"); + LSTR MSG_VTOOLS_RESET = _UxGT("В-инструменты сброшены"); #else - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Перекл. смешивание"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив.В-инструм."); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("В-инструм.нач."); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("В-инструм.кон."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инстр."); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Сброс В-инструм."); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструм."); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-инструм. сброшены"); + LSTR MSG_TOGGLE_MIX = _UxGT("Перекл. смешивание"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Актив.В-инструм."); + LSTR MSG_START_VTOOL = _UxGT("В-инструм.нач."); + LSTR MSG_END_VTOOL = _UxGT("В-инструм.кон."); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Псевдоним В-инстр."); + LSTR MSG_RESET_VTOOLS = _UxGT("Сброс В-инструм."); + LSTR MSG_COMMIT_VTOOL = _UxGT("Смешать В-инструм."); + LSTR MSG_VTOOLS_RESET = _UxGT("В-инструм. сброшены"); #endif - PROGMEM Language_Str MSG_START_Z = _UxGT("Начало Z"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Конец Z"); + LSTR MSG_START_Z = _UxGT("Начало Z"); + LSTR MSG_END_Z = _UxGT(" Конец Z"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Игры"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Кирпичи"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Вторжение"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Змейка"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Лабиринт"); + LSTR MSG_GAMES = _UxGT("Игры"); + LSTR MSG_BRICKOUT = _UxGT("Кирпичи"); + LSTR MSG_INVADERS = _UxGT("Вторжение"); + LSTR MSG_SNAKE = _UxGT("Змейка"); + LSTR MSG_MAZE = _UxGT("Лабиринт"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Плохой индекс страницы"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Плохая скорость страницы"); + LSTR MSG_BAD_PAGE = _UxGT("Плохой индекс страницы"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Плохая скорость страницы"); #else - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Плохая страница"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Плохая скор.стран."); + LSTR MSG_BAD_PAGE = _UxGT("Плохая страница"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Плохая скор.стран."); #endif - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Редактировать пароль"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Нужен логин"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Настройки пароля"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Введите цифру"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Смените пароль"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Удалить пароль"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Пароль это "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Старт через"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Редактировать пароль"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Нужен логин"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Настройки пароля"); + LSTR MSG_ENTER_DIGIT = _UxGT("Введите цифру"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Смените пароль"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Удалить пароль"); + LSTR MSG_PASSWORD_SET = _UxGT("Пароль это "); + LSTR MSG_START_OVER = _UxGT("Старт через"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни для сохранения!"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни для сохранения!"); #else - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни, сохрани!"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни, сохрани!"); #endif - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль удалён"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Пароль удалён"); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); #if LCD_HEIGHT >= 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Нажмите кнопку", "для продолжения", "печати")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Ожидайте начала", "смены филамента")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставьте филамент", "и нажмите кнопку", "для продолжения")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_3_LINE("Нажмите кнопку", "для нагрева", "сопла...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Нагрев сопла", "Ждите...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Ожидайте", "выгрузки", "филамента")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Ожидайте", "загрузки", "филамента")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Ожидайте", "экструзии", "филамента")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Нажмите кнопку", "для завершения", "очистки филамента")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Ожидайте", "возобновления", "печати")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Нажмите кнопку", "для продолжения", "печати")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Ожидайте начала", "смены филамента")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставьте филамент", "и нажмите кнопку", "для продолжения")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_3_LINE("Нажмите кнопку", "для нагрева", "сопла...")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Нагрев сопла", "Ждите...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Ожидайте", "выгрузки", "филамента")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Ожидайте", "загрузки", "филамента")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Ожидайте", "экструзии", "филамента")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Нажмите кнопку", "для завершения", "очистки филамента")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Ожидайте", "возобновления", "печати")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Продолжить печать")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Ожидайте...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Вставь и нажми")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Нагреть сопло")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Нагрев...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Выгрузка...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Загрузка...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Выдавливание...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Завершить очистку")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Возобновление...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Продолжить печать")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Ожидайте...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Вставь и нажми")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Нагреть сопло")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Нагрев...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Выгрузка...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Загрузка...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Выдавливание...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Завершить очистку")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Возобновление...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Драйвера TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Ток двигателей"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Гибридный режим"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Режим без эндстопов"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Режим драйвера"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим вкл"); + LSTR MSG_TMC_DRIVERS = _UxGT("Драйвера TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Ток двигателей"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Гибридный режим"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Режим без эндстопов"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Режим драйвера"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим вкл"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Сброс"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" в:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Люфт"); - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Исправление"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Сглаживание"); + LSTR MSG_SERVICE_RESET = _UxGT("Сброс"); + LSTR MSG_SERVICE_IN = _UxGT(" в:"); + LSTR MSG_BACKLASH = _UxGT("Люфт"); + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Исправление"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Сглаживание"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Уровень оси X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Авто калибровка"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Уровень оси X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Авто калибровка"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Время нагревателя вышло"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Время нагревателя вышло"); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Время нагрев. вышло"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Время нагрев. вышло"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Возобновить нагрев"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Нагрев..."); + LSTR MSG_REHEAT = _UxGT("Возобновить нагрев"); + LSTR MSG_REHEATING = _UxGT("Нагрев..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); + LSTR MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); #else - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондир.контр.точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движ. к точке зондир."); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондир.контр.точки Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Движ. к точке зондир."); #endif - PROGMEM Language_Str MSG_SOUND = _UxGT("Звук"); + LSTR MSG_SOUND = _UxGT("Звук"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Верхний левый"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Нижний левый"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Верхний правый"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижний правый"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); + LSTR MSG_TOP_LEFT = _UxGT("Верхний левый"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Нижний левый"); + LSTR MSG_TOP_RIGHT = _UxGT("Верхний правый"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Нижний правый"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Карта"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); + LSTR MSG_SD_CARD = _UxGT("SD Карта"); + LSTR MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 284fb9554a..4fe67494e2 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -43,713 +43,713 @@ namespace Language_sk { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Slovenčina"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Slovenčina"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" pripravená."); - PROGMEM Language_Str MSG_YES = _UxGT("ÁNO"); - PROGMEM Language_Str MSG_NO = _UxGT("NIE"); - PROGMEM Language_Str MSG_BACK = _UxGT("Naspäť"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Ruším..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Čakám na kartu"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Inicial. SD zlyhala"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Hlavná ponuka"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Pokročilé nastav."); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfigurácia"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Auto-štart"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Uvolniť motory"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Ponuka ladenia"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. priebehu"); - PROGMEM Language_Str MSG_HOMING = _UxGT("Parkovanie"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Domovská pozícia"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Domov os X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Domov os Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Domov os ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Domov os ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Domov os ") LCD_STR_K; - PROGMEM Language_Str MSG_FILAMENT_SET = _UxGT("Nastav. filamentu"); - PROGMEM Language_Str MSG_FILAMENT_MAN = _UxGT("Správa filamentu"); - PROGMEM Language_Str MSG_LEVBED_FL = _UxGT("Ľavý predný"); - PROGMEM Language_Str MSG_LEVBED_FR = _UxGT("Pravý predný"); - PROGMEM Language_Str MSG_LEVBED_C = _UxGT("Stred"); - PROGMEM Language_Str MSG_LEVBED_BL = _UxGT("Ľavý zadný"); - PROGMEM Language_Str MSG_LEVBED_BR = _UxGT("Pravý zadný"); - PROGMEM Language_Str MSG_MANUAL_MESH = _UxGT("Ručná mriežka"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto-zarovn. Z"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterácia G34: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Klesajúca presnosť!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Dosiahnutá presnosť"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Parkovanie XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknutím začnete"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Ďalší bod"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Vyrovnanie hotové!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Výška rovnania"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastav. dom. ofsety"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = LCD_STR_I _UxGT(" Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSET_J = LCD_STR_J _UxGT(" Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSET_K = LCD_STR_K _UxGT(" Ofset"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Vyberte začiatok"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Posl. hodnota "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pripravená."); + LSTR MSG_YES = _UxGT("ÁNO"); + LSTR MSG_NO = _UxGT("NIE"); + LSTR MSG_BACK = _UxGT("Naspäť"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Ruším..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); + LSTR MSG_MEDIA_WAITING = _UxGT("Čakám na kartu"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Inicial. SD zlyhala"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); + LSTR MSG_MAIN = _UxGT("Hlavná ponuka"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Pokročilé nastav."); + LSTR MSG_CONFIGURATION = _UxGT("Konfigurácia"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto-štart"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Uvolniť motory"); + LSTR MSG_DEBUG_MENU = _UxGT("Ponuka ladenia"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. priebehu"); + LSTR MSG_HOMING = _UxGT("Parkovanie"); + LSTR MSG_AUTO_HOME = _UxGT("Domovská pozícia"); + LSTR MSG_AUTO_HOME_X = _UxGT("Domov os X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Domov os Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); + LSTR MSG_AUTO_HOME_I = _UxGT("Domov os ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Domov os ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Domov os ") LCD_STR_K; + LSTR MSG_FILAMENT_SET = _UxGT("Nastav. filamentu"); + LSTR MSG_FILAMENT_MAN = _UxGT("Správa filamentu"); + LSTR MSG_LEVBED_FL = _UxGT("Ľavý predný"); + LSTR MSG_LEVBED_FR = _UxGT("Pravý predný"); + LSTR MSG_LEVBED_C = _UxGT("Stred"); + LSTR MSG_LEVBED_BL = _UxGT("Ľavý zadný"); + LSTR MSG_LEVBED_BR = _UxGT("Pravý zadný"); + LSTR MSG_MANUAL_MESH = _UxGT("Ručná mriežka"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto-zarovn. Z"); + LSTR MSG_ITERATION = _UxGT("Iterácia G34: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Klesajúca presnosť!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Dosiahnutá presnosť"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Parkovanie XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Kliknutím začnete"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Ďalší bod"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Vyrovnanie hotové!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Výška rovnania"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Nastav. dom. ofsety"); + LSTR MSG_HOME_OFFSET_X = _UxGT("X Ofset"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); + LSTR MSG_HOME_OFFSET_I = LCD_STR_I _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSET_J = LCD_STR_J _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSET_K = LCD_STR_K _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); + LSTR MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); + LSTR MSG_SELECT_ORIGIN = _UxGT("Vyberte začiatok"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Posl. hodnota "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Zahriať ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Zahriať ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" hotend"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" hotend ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" všetko"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" podlož"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" nast."); + LSTR MSG_PREHEAT_1 = _UxGT("Zahriať ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Zahriať ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" hotend"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" hotend ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" všetko"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" podlož"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Zahriať ") PREHEAT_1_LABEL _UxGT(" nast."); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Zahriať $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Zahriať $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Zahriať $ hotend"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Zahriať $ hotend ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Zahriať $ všetko"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Zahriať $ podlož"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Zahriať $ nast."); + LSTR MSG_PREHEAT_M = _UxGT("Zahriať $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Zahriať $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Zahriať $ hotend"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Zahriať $ hotend ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Zahriať $ všetko"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Zahriať $ podlož"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Zahriať $ nast."); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Vlastná teplota"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Schladiť"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Vlastná teplota"); + LSTR MSG_COOLDOWN = _UxGT("Schladiť"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Nastavenie lasera"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Nastavenie vretena"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon lasera"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Výkon vretena"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Prepnúť laser"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Prepnúť ofuk"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test. impulz ms"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Vystreliť impulz"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Chyba chladenia"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Prepnúť vreteno"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Dopredný chod"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spätný chod"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnúť napájanie"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Vypnúť napájanie"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Vytlačiť (extr.)"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Vytiahnuť (retr.)"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Posunúť osy"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Vyrovnať rohy"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Ďalší roh"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Koniec úprav siete"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Skúšam bod"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Vlastné príkazy"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Bod"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda mimo hraníc"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchýlka"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX režim"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Ofset nástrojov"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-parkovanie"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikácia"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrkadlená kópia"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplik. medz.-X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Vykonávam G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Nástroje UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); - PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmerajte"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Odstráňte a zmerajte"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Presun na ďalší"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivovať UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Deaktivovať UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Teplota podložky"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Teplota podložky"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Teplota hotendu"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Teplota hotendu"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Úprava siete bodov"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Upraviť vlastnú sieť"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Doladiť sieť bodov"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec úprav siete"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Vlastná sieť"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Vytvoriť sieť"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Sieť bodov ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Studená sieť bodov"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Upraviť výšku siete"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Výška"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Skontrolovať sieť"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Kontrola siete ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Kontrola vlast.siete"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 ohrev podlž."); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 ohrev trysky"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ručné čistenie..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Čistenie pevn. dĺž."); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Čistenie dokončené"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 zrušený"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Opúšťam G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Pokračovať v sieti"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Sieťové rovnanie"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-bodové rovnanie"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Vyrovnať podložku"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Postranné body"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Typ siete bodov"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Exportovať sieť"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Export do hosta"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Export do CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Externá záloha"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Info. o výst. UBL"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Hustota mriežky"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ručné vyplnenie"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Chytré vyplnenie"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Vyplniť mriežku"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Zrušiť všetko"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Zrušiť najbližší"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Upraviť všetky"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Upraviť najbližší"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Úložisko sietí"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Pamäťový slot"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Načítať sieť bodov"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Uložiť sieť bodov"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Sieť %i načítaná"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Sieť %i uložená"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Nedostatok miesta"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Chyba: Ukladanie UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Chyba: Obnovenie UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Ofset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Koniec kompenz. Z"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Postupné UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Studená sieť bodov"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Chytré vyplnenie"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Skontrolovať sieť"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Upraviť všetky"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Skontrolovať sieť"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Upraviť všetky"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Uložiť sieť bodov"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); + LSTR MSG_LASER_MENU = _UxGT("Nastavenie lasera"); + LSTR MSG_SPINDLE_MENU = _UxGT("Nastavenie vretena"); + LSTR MSG_LASER_POWER = _UxGT("Výkon lasera"); + LSTR MSG_SPINDLE_POWER = _UxGT("Výkon vretena"); + LSTR MSG_LASER_TOGGLE = _UxGT("Prepnúť laser"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Prepnúť ofuk"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Test. impulz ms"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Vystreliť impulz"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Chyba chladenia"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Prepnúť vreteno"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Dopredný chod"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spätný chod"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Zapnúť napájanie"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Vypnúť napájanie"); + LSTR MSG_EXTRUDE = _UxGT("Vytlačiť (extr.)"); + LSTR MSG_RETRACT = _UxGT("Vytiahnuť (retr.)"); + LSTR MSG_MOVE_AXIS = _UxGT("Posunúť osy"); + LSTR MSG_BED_LEVELING = _UxGT("Vyrovnanie podložky"); + LSTR MSG_LEVEL_BED = _UxGT("Vyrovnať podložku"); + LSTR MSG_BED_TRAMMING = _UxGT("Vyrovnať rohy"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Zdvyhnite podl., kým sa nezopne sonda"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Rohy sú vrámci odchyl. Vyrovnajte podl."); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Dobré body: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Ďalší roh"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); + LSTR MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); + LSTR MSG_EDITING_STOPPED = _UxGT("Koniec úprav siete"); + LSTR MSG_PROBING_POINT = _UxGT("Skúšam bod"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Hodnota Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Vlastné príkazy"); + LSTR MSG_M48_TEST = _UxGT("M48 Test sondy"); + LSTR MSG_M48_POINT = _UxGT("M48 Bod"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda mimo hraníc"); + LSTR MSG_M48_DEVIATION = _UxGT("Odchýlka"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX režim"); + LSTR MSG_OFFSETS_MENU = _UxGT("Ofset nástrojov"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-parkovanie"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikácia"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrkadlená kópia"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplik. medz.-X"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Vykonávam G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Nástroje UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); + LSTR MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Zmerajte"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Odstráňte a zmerajte"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Presun na ďalší"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivovať UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Deaktivovať UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Teplota podložky"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Teplota podložky"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Teplota hotendu"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Teplota hotendu"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Úprava siete bodov"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Upraviť vlastnú sieť"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Doladiť sieť bodov"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec úprav siete"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Vlastná sieť"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Vytvoriť sieť"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Sieť bodov ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Studená sieť bodov"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Upraviť výšku siete"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Výška"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Skontrolovať sieť"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Kontrola siete ($)"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Kontrola vlast.siete"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 ohrev podlž."); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 ohrev trysky"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Ručné čistenie..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Čistenie pevn. dĺž."); + LSTR MSG_G26_PRIME_DONE = _UxGT("Čistenie dokončené"); + LSTR MSG_G26_CANCELED = _UxGT("G26 zrušený"); + LSTR MSG_G26_LEAVING = _UxGT("Opúšťam G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Pokračovať v sieti"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Sieťové rovnanie"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-bodové rovnanie"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Vyrovnať podložku"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Postranné body"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Typ siete bodov"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Exportovať sieť"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Export do hosta"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Export do CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Externá záloha"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Info. o výst. UBL"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Hustota mriežky"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ručné vyplnenie"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Chytré vyplnenie"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Vyplniť mriežku"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Zrušiť všetko"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Zrušiť najbližší"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Upraviť všetky"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Upraviť najbližší"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Úložisko sietí"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Pamäťový slot"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Načítať sieť bodov"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Uložiť sieť bodov"); + LSTR MSG_MESH_LOADED = _UxGT("Sieť %i načítaná"); + LSTR MSG_MESH_SAVED = _UxGT("Sieť %i uložená"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Nedostatok miesta"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Chyba: Ukladanie UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Chyba: Obnovenie UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Ofset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Koniec kompenz. Z"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Postupné UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Studená sieť bodov"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Chytré vyplnenie"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Skontrolovať sieť"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Upraviť všetky"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Skontrolovať sieť"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Upraviť všetky"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Uložiť sieť bodov"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Nastavenie LED"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Svetlo"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Predvolby svetla"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Červená"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Oranžová"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Žltá"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Zelená"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Modrá"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fialová"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Biela"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Obnoviť nastavenie"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanál ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Svetlo #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Predvolby svetla #2"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Jas"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Vlastná farba"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Inten. červenej"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Inten. zelenej"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Inten. modrej"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Inten. bielej"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Jas"); + LSTR MSG_LED_CONTROL = _UxGT("Nastavenie LED"); + LSTR MSG_LEDS = _UxGT("Svetlo"); + LSTR MSG_LED_PRESETS = _UxGT("Predvolby svetla"); + LSTR MSG_SET_LEDS_RED = _UxGT("Červená"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Oranžová"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Žltá"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Zelená"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Modrá"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Fialová"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Biela"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Obnoviť nastavenie"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanál ="); + LSTR MSG_LEDS2 = _UxGT("Svetlo #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Predvolby svetla #2"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Jas"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Vlastná farba"); + LSTR MSG_INTENSITY_R = _UxGT("Inten. červenej"); + LSTR MSG_INTENSITY_G = _UxGT("Inten. zelenej"); + LSTR MSG_INTENSITY_B = _UxGT("Inten. modrej"); + LSTR MSG_INTENSITY_W = _UxGT("Inten. bielej"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Jas"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Posúvam..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Uvolniť XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Posunúť X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Posunúť Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Posunúť Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Posunúť ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Posunúť ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Posunúť ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrudér"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrudér *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Posunúť o %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunúť o 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); - PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Posunúť o 1,0in"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Rýchlosť"); - PROGMEM Language_Str MSG_MAXSPEED = _UxGT("Max rýchl. (mm/s)"); - PROGMEM Language_Str MSG_MAXSPEED_X = _UxGT("Max rýchl. ") LCD_STR_A; - PROGMEM Language_Str MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") LCD_STR_B; - PROGMEM Language_Str MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") LCD_STR_C; - PROGMEM Language_Str MSG_MAXSPEED_E = _UxGT("Max rýchl. ") LCD_STR_E; - PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Tryska ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Tryska zaparkovaná"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); - PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); - PROGMEM Language_Str MSG_COOLER = _UxGT("Chladen. lasera"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Prepnúť chladenie"); - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Bezpeč. prietok"); - PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Rýchlosť vent. ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Rýchlosť ex. vent."); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Rýchlosť ex. vent. ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Vent. riad. jedn."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Voľno. rýchl."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto-režim"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív. rýchl."); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Doba nečinnosti"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Prietok"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Prietok ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Ovládanie"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto-teplota"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Zap"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Vyp"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Kalibrácia PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Kalibrácia PID *"); - PROGMEM Language_Str MSG_PID_CYCLE = _UxGT("Cykly PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Kal. PID dokončená"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-kal. zlyhala. Zlý extrúder."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala. Príliš vysoká tepl."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Auto-kal. zlyhala! Čas vypršal."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Vybrať"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Vybrať *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Zrýchlenie"); - PROGMEM Language_Str MSG_JERK = _UxGT("Skok"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-skok"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-skok"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-skok"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-skok"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-skok"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-skok"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-skok"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Rýchlosť"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VPrej Min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Akcelerácia"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrakt"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-prejazd"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Kroky/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" krokov/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Ekrokov/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*krokov/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Teplota"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Pohyb"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E v mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit v mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Priem. fil."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Priem. fil. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Vysunúť mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Zaviesť mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K pre posun"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K pre posun *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Uložiť nastavenie"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Načítať nastavenie"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Obnoviť nastavenie"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializ. EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Chyba: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Chyba: EEPROM Index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Chyba: Verzia EEPROM"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Nastavenie uložené"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aktualizovať z SD"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reštart. tlačiar."); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnoviť"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info. obrazovka"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Príprava tlače"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Doladenie tlače"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Monitor napájania"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Prúd"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Napätie"); - PROGMEM Language_Str MSG_POWER = _UxGT("Výkon"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Spustiť tlač"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Ďalší"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inicial."); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Zastaviť"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Tlačiť"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Vynulovať"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorovať"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Zrušiť"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Hotovo"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Naspäť"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Preskočiť"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Pozastavujem..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Obnoviť tlač"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Zastaviť tlač"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Koniec opak. sluč."); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Tlačím objekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Zrušiť objekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Obnova po výp. nap."); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tlačiť z SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Žiadna SD karta"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Spím..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Pokrač. kliknutím..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Tlač pozastavená"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Tlačím..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Tlač zrušená"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Tlač dokončená"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Žiadny pohyb."); - PROGMEM Language_Str MSG_KILLED = _UxGT("PRERUŠENÉ. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ZASTAVENÉ. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retrakt mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Výmena Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraktovať V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Zdvih Z mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retract"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Dĺžka výmeny"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Vymeniť naviac"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Dĺžka vytlačenia"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Výmena nástroja"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvihnúť Z"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Primárna rýchl."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Rýchl. retrakcie"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkovať hlavu"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Rýchl. obnovenia"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Rýchlosť vent."); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Doba fúkania"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto-Zap"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto-Vyp"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Výmena nástroja"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-výmena"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Posl. extruder"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Vymeniť za *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Vymeniť filament"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Vymeniť filament *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Zaviesť filament"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Zaviesť filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Vysunúť filament"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Vysunúť filament *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Vysunúť všetko"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Načítať SD kartu"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Vymeniť SD kartu"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Odpojiť SD kartu"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z mimo podl."); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Faktor skosenia"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Zasunúť"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Vysunúť"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Režim SW"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Režim 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Režim OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Ulož. režim"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Prepnúť do 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Prepnúť do OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Zobraziť režim"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("POZOR: Zlé nastav. môže spôsobiť poškoden. Pokračovať?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Inicializ. TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test Z ofsetu"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Uložiť"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Zasunúť TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Zasunúť sondu Z"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Vysunúť sondu Z"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Najskôr os %s%s%s domov"); - PROGMEM Language_Str MSG_ZPROBE_SETTINGS = _UxGT("Nastav. sondy"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Ofsety sondy Z"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X ofset"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y ofset"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Pos. trysku k podl."); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Chyba: REDUND. TEP."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Ochladz. zlyhalo"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); - PROGMEM Language_Str MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reštartuje ju"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); - PROGMEM Language_Str MSG_HEATING = _UxGT("Ohrev..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Ochladzovanie..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Ohrev podložky..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Ochladz. podložky..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Ohrev sondy..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Ochladz. sondy..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Ohrev komory..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Ochladz. komory..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Ochladz. lasera..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrácia"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovať X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovať Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrovať Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovať stred"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta nastavenia"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-kalibrácia"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast. výšku delty"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ofset sondy Z"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag. rameno"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Výška"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Polomer"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("O tlačiarni"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Info. o tlačiarni"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-bodové rovnanie"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineárne rovnanie"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineárne rovnanie"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL rovnanie"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mriežka dokončená"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Štatistika"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. o doske"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrudéry"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Rýchlosť"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Tepl. ochrana: VYP"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Tepl. ochrana: ZAP"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Vypr.čas nečinnosti"); + LSTR MSG_MOVING = _UxGT("Posúvam..."); + LSTR MSG_FREE_XY = _UxGT("Uvolniť XY"); + LSTR MSG_MOVE_X = _UxGT("Posunúť X"); + LSTR MSG_MOVE_Y = _UxGT("Posunúť Y"); + LSTR MSG_MOVE_Z = _UxGT("Posunúť Z"); + LSTR MSG_MOVE_I = _UxGT("Posunúť ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Posunúť ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Posunúť ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Extrudér"); + LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); + LSTR MSG_MOVE_N_MM = _UxGT("Posunúť o %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Posunúť o 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); + LSTR MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); + LSTR MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); + LSTR MSG_MOVE_1IN = _UxGT("Posunúť o 1,0in"); + LSTR MSG_SPEED = _UxGT("Rýchlosť"); + LSTR MSG_MAXSPEED = _UxGT("Max rýchl. (mm/s)"); + LSTR MSG_MAXSPEED_X = _UxGT("Max rýchl. ") LCD_STR_A; + LSTR MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") LCD_STR_B; + LSTR MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") LCD_STR_C; + LSTR MSG_MAXSPEED_E = _UxGT("Max rýchl. ") LCD_STR_E; + LSTR MSG_BED_Z = _UxGT("Výška podl."); + LSTR MSG_NOZZLE = _UxGT("Tryska"); + LSTR MSG_NOZZLE_N = _UxGT("Tryska ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Tryska zaparkovaná"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); + LSTR MSG_BED = _UxGT("Podložka"); + LSTR MSG_CHAMBER = _UxGT("Komora"); + LSTR MSG_COOLER = _UxGT("Chladen. lasera"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Prepnúť chladenie"); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Bezpeč. prietok"); + LSTR MSG_LASER = _UxGT("Laser"); + LSTR MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); + LSTR MSG_FAN_SPEED_N = _UxGT("Rýchlosť vent. ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Rýchlosť ex. vent."); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Rýchlosť ex. vent. ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Vent. riad. jedn."); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Voľno. rýchl."); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto-režim"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktív. rýchl."); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Doba nečinnosti"); + LSTR MSG_FLOW = _UxGT("Prietok"); + LSTR MSG_FLOW_N = _UxGT("Prietok ~"); + LSTR MSG_CONTROL = _UxGT("Ovládanie"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); + LSTR MSG_AUTOTEMP = _UxGT("Auto-teplota"); + LSTR MSG_LCD_ON = _UxGT("Zap"); + LSTR MSG_LCD_OFF = _UxGT("Vyp"); + LSTR MSG_PID_AUTOTUNE = _UxGT("Kalibrácia PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Kalibrácia PID *"); + LSTR MSG_PID_CYCLE = _UxGT("Cykly PID"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Kal. PID dokončená"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Auto-kal. zlyhala. Zlý extrúder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala. Príliš vysoká tepl."); + LSTR MSG_PID_TIMEOUT = _UxGT("Auto-kal. zlyhala! Čas vypršal."); + LSTR MSG_SELECT = _UxGT("Vybrať"); + LSTR MSG_SELECT_E = _UxGT("Vybrať *"); + LSTR MSG_ACC = _UxGT("Zrýchlenie"); + LSTR MSG_JERK = _UxGT("Skok"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-skok"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-skok"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-skok"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-skok"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-skok"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-skok"); + LSTR MSG_VE_JERK = _UxGT("Ve-skok"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + LSTR MSG_VELOCITY = _UxGT("Rýchlosť"); + LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("VPrej Min"); + LSTR MSG_ACCELERATION = _UxGT("Akcelerácia"); + LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Amax *"); + LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); + LSTR MSG_A_TRAVEL = _UxGT("A-prejazd"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun"); + LSTR MSG_STEPS_PER_MM = _UxGT("Kroky/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" krokov/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" krokov/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" krokov/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" krokov/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" krokov/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" krokov/mm"); + LSTR MSG_E_STEPS = _UxGT("Ekrokov/mm"); + LSTR MSG_EN_STEPS = _UxGT("*krokov/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Teplota"); + LSTR MSG_MOTION = _UxGT("Pohyb"); + LSTR MSG_FILAMENT = _UxGT("Filament"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E v mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit v mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Priem. fil."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Priem. fil. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Vysunúť mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Zaviesť mm"); + LSTR MSG_ADVANCE_K = _UxGT("K pre posun"); + LSTR MSG_ADVANCE_K_E = _UxGT("K pre posun *"); + LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); + LSTR MSG_STORE_EEPROM = _UxGT("Uložiť nastavenie"); + LSTR MSG_LOAD_EEPROM = _UxGT("Načítať nastavenie"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Obnoviť nastavenie"); + LSTR MSG_INIT_EEPROM = _UxGT("Inicializ. EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Chyba: EEPROM CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Chyba: EEPROM Index"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Chyba: Verzia EEPROM"); + LSTR MSG_SETTINGS_STORED = _UxGT("Nastavenie uložené"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Aktualizovať z SD"); + LSTR MSG_RESET_PRINTER = _UxGT("Reštart. tlačiar."); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Obnoviť"); + LSTR MSG_INFO_SCREEN = _UxGT("Info. obrazovka"); + LSTR MSG_PREPARE = _UxGT("Príprava tlače"); + LSTR MSG_TUNE = _UxGT("Doladenie tlače"); + LSTR MSG_POWER_MONITOR = _UxGT("Monitor napájania"); + LSTR MSG_CURRENT = _UxGT("Prúd"); + LSTR MSG_VOLTAGE = _UxGT("Napätie"); + LSTR MSG_POWER = _UxGT("Výkon"); + LSTR MSG_START_PRINT = _UxGT("Spustiť tlač"); + LSTR MSG_BUTTON_NEXT = _UxGT("Ďalší"); + LSTR MSG_BUTTON_INIT = _UxGT("Inicial."); + LSTR MSG_BUTTON_STOP = _UxGT("Zastaviť"); + LSTR MSG_BUTTON_PRINT = _UxGT("Tlačiť"); + LSTR MSG_BUTTON_RESET = _UxGT("Vynulovať"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorovať"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Zrušiť"); + LSTR MSG_BUTTON_DONE = _UxGT("Hotovo"); + LSTR MSG_BUTTON_BACK = _UxGT("Naspäť"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); + LSTR MSG_BUTTON_SKIP = _UxGT("Preskočiť"); + LSTR MSG_PAUSING = _UxGT("Pozastavujem..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); + LSTR MSG_RESUME_PRINT = _UxGT("Obnoviť tlač"); + LSTR MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); + LSTR MSG_STOP_PRINT = _UxGT("Zastaviť tlač"); + LSTR MSG_END_LOOPS = _UxGT("Koniec opak. sluč."); + LSTR MSG_PRINTING_OBJECT = _UxGT("Tlačím objekt"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušiť objekt"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Obnova po výp. nap."); + LSTR MSG_MEDIA_MENU = _UxGT("Tlačiť z SD"); + LSTR MSG_NO_MEDIA = _UxGT("Žiadna SD karta"); + LSTR MSG_DWELL = _UxGT("Spím..."); + LSTR MSG_USERWAIT = _UxGT("Pokrač. kliknutím..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Tlač pozastavená"); + LSTR MSG_PRINTING = _UxGT("Tlačím..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Tlač zrušená"); + LSTR MSG_PRINT_DONE = _UxGT("Tlač dokončená"); + LSTR MSG_NO_MOVE = _UxGT("Žiadny pohyb."); + LSTR MSG_KILLED = _UxGT("PRERUŠENÉ. "); + LSTR MSG_STOPPED = _UxGT("ZASTAVENÉ. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Retrakt mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Výmena Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Retraktovať V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Zdvih Z mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Retract"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Dĺžka výmeny"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Vymeniť naviac"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Dĺžka vytlačenia"); + LSTR MSG_TOOL_CHANGE = _UxGT("Výmena nástroja"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Zdvihnúť Z"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Primárna rýchl."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Rýchl. retrakcie"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkovať hlavu"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Rýchl. obnovenia"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Rýchlosť vent."); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Doba fúkania"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto-Zap"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto-Vyp"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Výmena nástroja"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-výmena"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Posl. extruder"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Vymeniť za *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Vymeniť filament"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Vymeniť filament *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Zaviesť filament"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Zaviesť filament *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Vysunúť filament"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Vysunúť filament *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Vysunúť všetko"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Načítať SD kartu"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Vymeniť SD kartu"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Odpojiť SD kartu"); + LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z mimo podl."); + LSTR MSG_SKEW_FACTOR = _UxGT("Faktor skosenia"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Self-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Zasunúť"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Vysunúť"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Režim SW"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Režim 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Režim OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Ulož. režim"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Prepnúť do 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Prepnúť do OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Zobraziť režim"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("POZOR: Zlé nastav. môže spôsobiť poškoden. Pokračovať?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Inicializ. TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test Z ofsetu"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Uložiť"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Zasunúť TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Zasunúť sondu Z"); + LSTR MSG_MANUAL_STOW = _UxGT("Vysunúť sondu Z"); + LSTR MSG_HOME_FIRST = _UxGT("Najskôr os %s%s%s domov"); + LSTR MSG_ZPROBE_SETTINGS = _UxGT("Nastav. sondy"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Ofsety sondy Z"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("X ofset"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Y ofset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z ofset"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Pos. trysku k podl."); + LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Chyba: REDUND. TEP."); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); + LSTR MSG_COOLING_FAILED = _UxGT("Ochladz. zlyhalo"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); + LSTR MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); + LSTR MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); + LSTR MSG_PLEASE_RESET = _UxGT("Reštartuje ju"); + LSTR MSG_SHORT_DAY = _UxGT("d"); + LSTR MSG_SHORT_HOUR = _UxGT("h"); + LSTR MSG_SHORT_MINUTE = _UxGT("m"); + LSTR MSG_HEATING = _UxGT("Ohrev..."); + LSTR MSG_COOLING = _UxGT("Ochladzovanie..."); + LSTR MSG_BED_HEATING = _UxGT("Ohrev podložky..."); + LSTR MSG_BED_COOLING = _UxGT("Ochladz. podložky..."); + LSTR MSG_PROBE_HEATING = _UxGT("Ohrev sondy..."); + LSTR MSG_PROBE_COOLING = _UxGT("Ochladz. sondy..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Ohrev komory..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Ochladz. komory..."); + LSTR MSG_LASER_COOLING = _UxGT("Ochladz. lasera..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrácia"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovať X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovať Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrovať Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovať stred"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta nastavenia"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto-kalibrácia"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast. výšku delty"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ofset sondy Z"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag. rameno"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Výška"); + LSTR MSG_DELTA_RADIUS = _UxGT("Polomer"); + LSTR MSG_INFO_MENU = _UxGT("O tlačiarni"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Info. o tlačiarni"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-bodové rovnanie"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Lineárne rovnanie"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilineárne rovnanie"); + LSTR MSG_UBL_LEVELING = _UxGT("UBL rovnanie"); + LSTR MSG_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); + LSTR MSG_MESH_DONE = _UxGT("Mriežka dokončená"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Štatistika"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Info. o doske"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extrudéry"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Rýchlosť"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokol"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Tepl. ochrana: VYP"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Tepl. ochrana: ZAP"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Vypr.čas nečinnosti"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Osvetlenie"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); + LSTR MSG_CASE_LIGHT = _UxGT("Osvetlenie"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončené"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia tlač"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Celkom vytlačené"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončené"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia tlač"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Celkom vytlačené"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Tlače"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Hotovo"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Čas"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačené"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Tlače"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Hotovo"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Čas"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačené"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Teplota min"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Nap. zdroj"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Budenie motorov"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Motor %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("CHYBA KOMUNIKÁ. TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Uložiť do EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMENA FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("PAUZA TLAČE"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ZAVEDENIE FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("VYSUNUTIE FILAMENTU"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("MOŽNOSTI POKRAČ.:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Vytlačiť viacej"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Obnoviť tlač"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); - PROGMEM Language_Str MSG_RUNOUT_ENABLE = _UxGT("Zapnúť senzor"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Teplota min"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); + LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Budenie motorov"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); + LSTR MSG_ERROR_TMC = _UxGT("CHYBA KOMUNIKÁ. TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Uložiť do EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("VÝMENA FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("PAUZA TLAČE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ZAVEDENIE FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("VYSUNUTIE FILAMENTU"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("MOŽNOSTI POKRAČ.:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Vytlačiť viacej"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Obnoviť tlač"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Tryska: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); + LSTR MSG_RUNOUT_ENABLE = _UxGT("Zapnúť senzor"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU2"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktualizujte FW MMU!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potrebuje zásah."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Obnoviť tlač"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Obnovovanie..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Zaviesť filament"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Zaviesť všetky"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Zaviesť po trysku"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Vysunúť filament"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Vysunúť filament ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Vyňať filament"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Zavádzanie fil. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Vysúvanie fil. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Vysúvanie fil. ..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Všetky"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reštartovať MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Reštart MMU..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Odstráňte, kliknite"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); + LSTR MSG_MMU2_MENU = _UxGT("MMU2"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Aktualizujte FW MMU!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU potrebuje zásah."); + LSTR MSG_MMU2_RESUME = _UxGT("Obnoviť tlač"); + LSTR MSG_MMU2_RESUMING = _UxGT("Obnovovanie..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Zaviesť filament"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Zaviesť všetky"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Zaviesť po trysku"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Vysunúť filament"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Vysunúť filament ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Vyňať filament"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Zavádzanie fil. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Vysúvanie fil. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Vysúvanie fil. ..."); + LSTR MSG_MMU2_ALL = _UxGT("Všetky"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + LSTR MSG_MMU2_RESET = _UxGT("Reštartovať MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("Reštart MMU..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Odstráňte, kliknite"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Zložka ~"); - PROGMEM Language_Str MSG_MIXER = _UxGT("Mixér"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Plný gradient"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Prepnúť mix"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cyklický mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradientný mix"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Otočiť gradient"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktívny V-tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Počiat. V-tool"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Konečn. V-tool"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Vynulovať V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Uložiť V-tool Mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools vynulované"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Počiat.Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT("Konečn.Z:"); + LSTR MSG_MIX = _UxGT("Mix"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Zložka ~"); + LSTR MSG_MIXER = _UxGT("Mixér"); + LSTR MSG_GRADIENT = _UxGT("Gradient"); + LSTR MSG_FULL_GRADIENT = _UxGT("Plný gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Prepnúť mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Cyklický mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradientný mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Otočiť gradient"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktívny V-tool"); + LSTR MSG_START_VTOOL = _UxGT("Počiat. V-tool"); + LSTR MSG_END_VTOOL = _UxGT("Konečn. V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("Vynulovať V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Uložiť V-tool Mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools vynulované"); + LSTR MSG_START_Z = _UxGT("Počiat.Z:"); + LSTR MSG_END_Z = _UxGT("Konečn.Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Hry"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Nájazdníci"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Had"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Bludisko"); + LSTR MSG_GAMES = _UxGT("Hry"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Nájazdníci"); + LSTR MSG_SNAKE = _UxGT("Had"); + LSTR MSG_MAZE = _UxGT("Bludisko"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Chyb. index stránky"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Chyb. rých. stránky"); + LSTR MSG_BAD_PAGE = _UxGT("Chyb. index stránky"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Chyb. rých. stránky"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Zmeniť heslo"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Vyžad. sa prihl."); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Nastavenie hesla"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Zvoľte číslo"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Zmeniť heslo"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Odstrániť heslo"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Heslo je "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Začať odznova"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Nezabudnite uložiť!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Heslo odstránené"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Zmeniť heslo"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Vyžad. sa prihl."); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Nastavenie hesla"); + LSTR MSG_ENTER_DIGIT = _UxGT("Zvoľte číslo"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Zmeniť heslo"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Odstrániť heslo"); + LSTR MSG_PASSWORD_SET = _UxGT("Heslo je "); + LSTR MSG_START_OVER = _UxGT("Začať odznova"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Nezabudnite uložiť!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Heslo odstránené"); // // 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("Stlačte tlačidlo", "pre obnovu tlače")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čakajte prosím", "na spustenie", "výmeny filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stlačte tlačidlo", "pre pokračovanie")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Stlačte tlačidlo", "pre ohrev trysky")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Ohrev trysky", "Čakajte prosím...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Čakajte prosím", "na vysunutie", "filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Čakajte prosím", "na zavedenie", "filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Čakajte prosím", "na vytlačenie", "filamentu")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Stlačte tlačidlo", "pre dokončenie", "vytláčania filam.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Čakajte prosím na", "obnovenie tlače...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Stlačte tlačidlo", "pre obnovu tlače")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Čakajte prosím", "na spustenie", "výmeny filamentu")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Vložte filament", "a stlačte tlačidlo", "pre pokračovanie")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Stlačte tlačidlo", "pre ohrev trysky")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Ohrev trysky", "Čakajte prosím...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Čakajte prosím", "na vysunutie", "filamentu")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Čakajte prosím", "na zavedenie", "filamentu")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("Čakajte prosím", "na vytlačenie", "filamentu")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Stlačte tlačidlo", "pre dokončenie", "vytláčania filam.")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Čakajte prosím na", "obnovenie tlače...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknite pre pokr.")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čakajte prosím...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte a kliknite")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknite pre ohrev")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Ohrev...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Vysúvanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Zavádzanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Vytlačovanie...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klik. pre dokonč.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Pokračovanie...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Kliknite pre pokr.")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkovanie...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Čakajte prosím...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Vložte a kliknite")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Kliknite pre ohrev")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Ohrev...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Vysúvanie...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Zavádzanie...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Vytlačovanie...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klik. pre dokonč.")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Pokračovanie...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Ovládače TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Prúd ovládača"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybridný prah"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Bezsenzor. domov"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Režim krokovania"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop zapnutý"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Vynulovať"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT("za:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Kompenz. vôle"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekcia"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Vyhladzovanie"); + LSTR MSG_TMC_DRIVERS = _UxGT("Ovládače TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Prúd ovládača"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybridný prah"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Bezsenzor. domov"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Režim krokovania"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop zapnutý"); + LSTR MSG_SERVICE_RESET = _UxGT("Vynulovať"); + LSTR MSG_SERVICE_IN = _UxGT("za:"); + LSTR MSG_BACKLASH = _UxGT("Kompenz. vôle"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekcia"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Vyhladzovanie"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Vyrovnať os X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto-kalibrovať"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Vyrovnať os X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto-kalibrovať"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Vypršal čas ohrevu, znížená teplota. Stlačte OK pre ohrev a ešte raz pre obnovu."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Vypršal čas ohrevu, znížená teplota. Stlačte OK pre ohrev a ešte raz pre obnovu."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Vypršal čas ohrevu"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Vypršal čas ohrevu"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Zohriať"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Zohrievanie..."); - PROGMEM Language_Str MSG_REHEATDONE = _UxGT("Zohrievanie dokonč."); + LSTR MSG_REHEAT = _UxGT("Zohriať"); + LSTR MSG_REHEATING = _UxGT("Zohrievanie..."); + LSTR MSG_REHEATDONE = _UxGT("Zohrievanie dokonč."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Sprievodca sondy Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Referencia Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Presúvam na pozíciu"); + LSTR MSG_PROBE_WIZARD = _UxGT("Sprievodca sondy Z"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Referencia Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Presúvam na pozíciu"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Zvuk"); + LSTR MSG_SOUND = _UxGT("Zvuk"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Ľavý horný"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Ľavý dolný"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Pravý horný"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Pravý dolný"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrácia dokončená"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); + LSTR MSG_TOP_LEFT = _UxGT("Ľavý horný"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Ľavý dolný"); + LSTR MSG_TOP_RIGHT = _UxGT("Pravý horný"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Pravý dolný"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrácia dokončená"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD karta"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB disk"); + LSTR MSG_SD_CARD = _UxGT("SD karta"); + LSTR MSG_USB_DISK = _UxGT("USB disk"); } diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index af80c41a82..9194dc4861 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -33,667 +33,667 @@ namespace Language_sv { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Swedish"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Swedish"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Redo."); - PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); - PROGMEM Language_Str MSG_YES = _UxGT("JA"); - PROGMEM Language_Str MSG_NO = _UxGT("NEJ"); - PROGMEM Language_Str MSG_BACK = _UxGT("Bakåt"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Avbryter..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media Instatt"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media Borttaget"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Väntar på media"); - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD init misslyckades"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Huvud"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Advancerade inställningar"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Konfiguration"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Autostarta Filer"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Inaktivera Stegare"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug Meny"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Framstegsindikator Test"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Hem"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Hem X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Hem Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Hem Z"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Justering"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Noggrannhet Minskar!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Noggrannhet uppnådd"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Hemning XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klicka för att börja"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nästa Punkt"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivellering Färdig!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Falna Höjd"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sätt Origo"); - PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Välj Origo"); - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Senaste värde "); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Redo."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("JA"); + LSTR MSG_NO = _UxGT("NEJ"); + LSTR MSG_BACK = _UxGT("Bakåt"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Avbryter..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Media Instatt"); + LSTR MSG_MEDIA_REMOVED = _UxGT("Media Borttaget"); + LSTR MSG_MEDIA_WAITING = _UxGT("Väntar på media"); + LSTR MSG_SD_INIT_FAIL = _UxGT("SD init misslyckades"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp"); + LSTR MSG_MAIN = _UxGT("Huvud"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advancerade inställningar"); + LSTR MSG_CONFIGURATION = _UxGT("Konfiguration"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostarta Filer"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Inaktivera Stegare"); + LSTR MSG_DEBUG_MENU = _UxGT("Debug Meny"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Framstegsindikator Test"); + LSTR MSG_AUTO_HOME = _UxGT("Auto Hem"); + LSTR MSG_AUTO_HOME_X = _UxGT("Hem X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Hem Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Hem Z"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Justering"); + LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Noggrannhet Minskar!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Noggrannhet uppnådd"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Hemning XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klicka för att börja"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nästa Punkt"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivellering Färdig!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Falna Höjd"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad"); + LSTR MSG_SET_ORIGIN = _UxGT("Sätt Origo"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Välj Origo"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Senaste värde "); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Förvärmning ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Förvärmning ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Alla"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Bädd"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Konf"); + LSTR MSG_PREHEAT_1 = _UxGT("Förvärmning ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Förvärmning ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Stoppa ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Alla"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Bädd"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Förvärmning ") PREHEAT_1_LABEL _UxGT(" Konf"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Förvärmning $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Förvärmning $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Förvärmning $ Stoppa"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Förvärmning $ Stoppa ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Förvärmning $ Alla"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Förvärmning $ Bädd"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Förvärmning $ Donf"); + LSTR MSG_PREHEAT_M = _UxGT("Förvärmning $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Förvärmning $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Förvärmning $ Stoppa"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Förvärmning $ Stoppa ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Förvärmning $ Alla"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Förvärmning $ Bädd"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Förvärmning $ Donf"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Förvärmning Anpassad"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Nedkylning"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvens"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser kontroll"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindel Kontroll"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Laser Styrka"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindel Styrka"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Växla Laser"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Puls ms"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Avfyra Puls"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Växla Spindel"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindel Framåt"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindel Bakåt"); - PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Av"); - PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser På"); - PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindel Av"); - PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindel På"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Sätt på ström"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Stäng av ström"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudera"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Dra tillbaka"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Flytta Axel"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bädd Nivellering"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivellera Bädd"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Bädd Justering"); - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd"); - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra Punkter: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Senaste Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nästa Hörn"); - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Nät Redigerare"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Redigera Nät"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Nätredigering Stoppad"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Sonderingspunkt"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Värde"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Anpassade Kommandon"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Sond Test"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punkt"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Sond utan för gränser"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Avvikelse"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Läge"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Verktygsoffset"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkera"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicering"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad Kopia"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Kontroll"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-Avstånd"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2:a Munstycke X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2:a Munstycke Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2:a Munstycke Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Utför G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Verktyg"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Enad Bädd Nivellering (UBL)"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Lutningspunkt"); - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuellt skapa nät"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Placera Shim & Mät"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mät"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Ta bort & Mät bädd"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Flyttar till nästa"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivera UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Avaktivera UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Bädd Temp"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bädd Temp"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hetände Temp"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hetände Temp"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Nät Redigera"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Redigera Anpassat Nät"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finjustera Nät"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Färdig Redigera Nät"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Bygg Anpassat Nät"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Bygg Nät"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Bygg Nät ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Bygg Kallt Nät"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Justera Nät Höjd"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höjd Antal"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validera Nät"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Validera Nät ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validera Anpassat Nät"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Värma Bädd"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Värma Munstycke"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Manuel grundning..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Fastlängd Grundning"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Färdig Grundning"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Avbruten"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Nivellera G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Fortsätt Bädd Nät"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nät Nivellering"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkts Nivellering"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rutnät Nivellering"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivellera Nät"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Sidopunkter"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Kart Typ"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Utmatning Nät Map"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Utmatning för Värd"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Utmatning för CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Utanför skrivare Backup"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Utmatning UBL Info"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Ifyllnad Mängd"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manuell Ifyllnad"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Smart Ifyllnad"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Ifyllnad Nät"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Ogiltigförklara Alla"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Ogiltigförklara Närmast"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Finjustera Alla"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Finjustera Närmast"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Nät Lagra"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Minnesöppning"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Ladda Bädd Nät"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Spara Bädd Nät"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Nät %i Ladda"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Nät %i Sparad"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Ingen Lagring"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Fel: UBL Sparad"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Fel: UBL Återställd"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stoppad"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Steg-för-Steg UBL"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Bygg Kallt Nät"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Ifyllnad"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validera Nät"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Finjustera Alla"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validera Nät"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Finjustera Alla"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Spara Bädd Nät"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Förvärmning Anpassad"); + LSTR MSG_COOLDOWN = _UxGT("Nedkylning"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frekvens"); + LSTR MSG_LASER_MENU = _UxGT("Laser kontroll"); + LSTR MSG_SPINDLE_MENU = _UxGT("Spindel Kontroll"); + LSTR MSG_LASER_POWER = _UxGT("Laser Styrka"); + LSTR MSG_SPINDLE_POWER = _UxGT("Spindel Styrka"); + LSTR MSG_LASER_TOGGLE = _UxGT("Växla Laser"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Test Puls ms"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Avfyra Puls"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Växla Spindel"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindel Framåt"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindel Bakåt"); + LSTR MSG_LASER_OFF = _UxGT("Laser Av"); + LSTR MSG_LASER_ON = _UxGT("Laser På"); + LSTR MSG_SPINDLE_OFF = _UxGT("Spindel Av"); + LSTR MSG_SPINDLE_ON = _UxGT("Spindel På"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Sätt på ström"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Stäng av ström"); + LSTR MSG_EXTRUDE = _UxGT("Extrudera"); + LSTR MSG_RETRACT = _UxGT("Dra tillbaka"); + LSTR MSG_MOVE_AXIS = _UxGT("Flytta Axel"); + LSTR MSG_BED_LEVELING = _UxGT("Bädd Nivellering"); + LSTR MSG_LEVEL_BED = _UxGT("Nivellera Bädd"); + LSTR MSG_BED_TRAMMING = _UxGT("Bädd Justering"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd"); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra Punkter: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Senaste Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Nästa Hörn"); + LSTR MSG_MESH_EDITOR = _UxGT("Nät Redigerare"); + LSTR MSG_EDIT_MESH = _UxGT("Redigera Nät"); + LSTR MSG_EDITING_STOPPED = _UxGT("Nätredigering Stoppad"); + LSTR MSG_PROBING_POINT = _UxGT("Sonderingspunkt"); + LSTR MSG_MESH_X = _UxGT("Index X"); + LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z Värde"); + LSTR MSG_USER_MENU = _UxGT("Anpassade Kommandon"); + LSTR MSG_M48_TEST = _UxGT("M48 Sond Test"); + LSTR MSG_M48_POINT = _UxGT("M48 Punkt"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sond utan för gränser"); + LSTR MSG_M48_DEVIATION = _UxGT("Avvikelse"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX Läge"); + LSTR MSG_OFFSETS_MENU = _UxGT("Verktygsoffset"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkera"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicering"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad Kopia"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Kontroll"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-Avstånd"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2:a Munstycke X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2:a Munstycke Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2:a Munstycke Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Utför G29"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL Verktyg"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Enad Bädd Nivellering (UBL)"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Lutningspunkt"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manuellt skapa nät"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Placera Shim & Mät"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Mät"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Ta bort & Mät bädd"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Flyttar till nästa"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Aktivera UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Avaktivera UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Bädd Temp"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bädd Temp"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hetände Temp"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hetände Temp"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Nät Redigera"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Redigera Anpassat Nät"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Finjustera Nät"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Färdig Redigera Nät"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Bygg Anpassat Nät"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Bygg Nät"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Bygg Nät ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Bygg Kallt Nät"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Justera Nät Höjd"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höjd Antal"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validera Nät"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validera Nät ($)"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validera Anpassat Nät"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Värma Bädd"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Värma Munstycke"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manuel grundning..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fastlängd Grundning"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Färdig Grundning"); + LSTR MSG_G26_CANCELED = _UxGT("G26 Avbruten"); + LSTR MSG_G26_LEAVING = _UxGT("Nivellera G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Fortsätt Bädd Nät"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Nät Nivellering"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkts Nivellering"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rutnät Nivellering"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Nivellera Nät"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Sidopunkter"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Kart Typ"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Utmatning Nät Map"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Utmatning för Värd"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Utmatning för CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Utanför skrivare Backup"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Utmatning UBL Info"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Ifyllnad Mängd"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuell Ifyllnad"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart Ifyllnad"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Ifyllnad Nät"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Ogiltigförklara Alla"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Ogiltigförklara Närmast"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Finjustera Alla"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Finjustera Närmast"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Nät Lagra"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Minnesöppning"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Ladda Bädd Nät"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Spara Bädd Nät"); + LSTR MSG_MESH_LOADED = _UxGT("Nät %i Ladda"); + LSTR MSG_MESH_SAVED = _UxGT("Nät %i Sparad"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Ingen Lagring"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Fel: UBL Sparad"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Fel: UBL Återställd"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stoppad"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Steg-för-Steg UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Bygg Kallt Nät"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Ifyllnad"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validera Nät"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Finjustera Alla"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validera Nät"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Finjustera Alla"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Spara Bädd Nät"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Kontroll"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Ljus"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Ljus Förinställd"); - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Röd"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Orange"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Gul"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Grön"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Blå"); - 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("Vitt"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanal ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Ljus #2"); - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Ljus #2 Förinställd"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Ljusstyrka"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Anpassat Ljus"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Rör Intensitet"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Grön Intensitet"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Blå Intensitet"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Vit Intensitet"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brightness"); + LSTR MSG_LED_CONTROL = _UxGT("LED Kontroll"); + LSTR MSG_LEDS = _UxGT("Ljus"); + LSTR MSG_LED_PRESETS = _UxGT("Ljus Förinställd"); + LSTR MSG_SET_LEDS_RED = _UxGT("Röd"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Gul"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Grön"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Blå"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Vitt"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + LSTR MSG_LEDS2 = _UxGT("Ljus #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Ljus #2 Förinställd"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Ljusstyrka"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Anpassat Ljus"); + LSTR MSG_INTENSITY_R = _UxGT("Rör Intensitet"); + LSTR MSG_INTENSITY_G = _UxGT("Grön Intensitet"); + LSTR MSG_INTENSITY_B = _UxGT("Blå Intensitet"); + LSTR MSG_INTENSITY_W = _UxGT("Vit Intensitet"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Brightness"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Flyttar..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Fri XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Flytta X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Flytta Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Flytta Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Flytta %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flytta 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flytta 10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flytta 100mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Flytta 0.001tum"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Flytta 0.01tum"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Flytta 0.1tum"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighet"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Bädd Z"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Munstycke"); - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Munstycke ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Munstycke Parkerad"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Munstycke Standby"); - PROGMEM Language_Str MSG_BED = _UxGT("Bädd"); - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Inkapsling"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fläkt Hastighet"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fläkt Hastighet ~"); - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Lagrad Fläkt ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fläkt Hastighet"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fläkt Hastighet ~"); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Kontroller Fläkt"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Overksam Hastighet"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto läga"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktive Hastighet"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Overksam Period"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Flöde"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flöde ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontroll"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Autotemp"); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("På"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Av"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autojustera"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autojustera *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autojustera misslyckad. Dålig extruder."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad. Temperatur för hög."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autojustera misslyckad! Tidsgräns."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Välj"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Välj *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Accel"); - PROGMEM Language_Str MSG_JERK = _UxGT("Ryck"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Ryck"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Ryck"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Hastighet"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("VTrav Min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Acceleration"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-Färdas"); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvens max"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Flöde min"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steg/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steg/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E Steg/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steg/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatur"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Rörelse"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Tråd"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Gräns i mm³"); - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Gräns *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Tråd Dia."); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Tråd Dia. *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Lossa mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Ladda mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advancera K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advancera K *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD Kontrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Spara Inställningar"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Ladda Inställningar"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Återställ Standard"); - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initiera EEPROM"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fel"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fel"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fel"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Inställningar Lagrad"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Media Uppdatera"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Återställ Skrivare"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Uppdatera"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info Skärm"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Förbered"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Justera"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Ström övervakning"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Ström"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Spänning"); - PROGMEM Language_Str MSG_POWER = _UxGT("Ström"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start Utskrift"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Nästa"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Initiera"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stoppa"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Skriv"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Återställa"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorera"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Avbryt"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Färdig"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Bakåt"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Fortsätt"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Hoppa över"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Paus.."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausera Utskrift"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Återuppta Utskrift"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Värd Start"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stoppa Utskrift"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("Slut Upprepningsloop"); - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Skriver Objekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Avbryt Objekt"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Ström Avbrott"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Skriv fråm Media"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Inget Media"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Sov..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Klick för att återuppta..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Utskrift Pausad"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Skriver..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Utskrift Avbruten"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Utskrift Färdig"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Ingen Flytt."); - PROGMEM Language_Str MSG_KILLED = _UxGT("DÖDAD. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPAD. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Dra tillbaka mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Byt Dra.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Dra tillbaka V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hoppa mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Åter dra tillbaka. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Byt åter dra t. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Återdrat. V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Byt åter dra. V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Dra-tillbka"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Byt Längd"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Byt Extra"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Rensa Längd"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Byt verktyg"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Höj"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Grund Hastighet"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Återgå Hastighet"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkera Huvud"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Återgår Hastighet"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fläkt Hastighet"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fläkt Tid"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto PÅ"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AV"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Verktyg Migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Senast Extruder"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrera till *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Byt Tråd"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Byt Tråd *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Ladda Tråd"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Ladda *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Lossa Tråd"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Lossa *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Lossa All"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Bifoga Media"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Byt Media"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Släpp Media"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Sond Utanför Bädd"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Skev Faktor"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Själv-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Återställ"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stuva undan"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Fällut"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Läge"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Läge"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Läge"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Läge-Lägring"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Sätt BLTouch to 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Sätt BLTouch to OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Reportera Dränering"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("FARA: Dålig inställningar kan orsaka skada! Fortsätt ändå?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Initiera TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Spara"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Fällut TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Fällut Z-Sond"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stuva undan Z-Sond"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Hem %s%s%s Först"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Sond Offsets"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Sond X Offset"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Sond Y Offset"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Sond Z Offset"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Flytta Munstycke till Bädd"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Småsteg X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Småsteg Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Småsteg Z"); - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Slutstopp Avbrott"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Värma Misslyckad"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Fel: REDUNDANT TEMP"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TERMISK ÖVERDRIFT"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BÄDD TERMISK ÖVERDRIFT"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMMARE T. ÖVERDRIFT"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Fel: MAXTEMP"); - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Fel: MINTEMP"); - PROGMEM Language_Str MSG_HALTED = _UxGT("Utskrift stoppad"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Snälla Återställ"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("t"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Värmer..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Kyler..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Bädd Värmer..."); - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Bädd Kyler..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Sond Värmer..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Sond Kyler..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Kammare Värmer..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Kammare Kyler..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrera X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrera Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrera Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera Center"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Inställningar"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibrering"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Sätt Delta Höjd"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sond Z-offset"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Höjd"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radius"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Om Skrivaren"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Skrivare Info"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Punkt Nivellering"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Linjär Nivellering"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilinjär Nivellering"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Enhetlig Bädd Nivellering (UBL)"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nät Nivellering"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Skrivar Stats"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistor"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderare"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Överdrift Övervakning: AV"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Överdrift Övervakning: PÅ"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hetände Overksam Tidsgräns"); + LSTR MSG_MOVING = _UxGT("Flyttar..."); + LSTR MSG_FREE_XY = _UxGT("Fri XY"); + LSTR MSG_MOVE_X = _UxGT("Flytta X"); + LSTR MSG_MOVE_Y = _UxGT("Flytta Y"); + LSTR MSG_MOVE_Z = _UxGT("Flytta Z"); + LSTR MSG_MOVE_E = _UxGT("Extruder"); + LSTR MSG_MOVE_EN = _UxGT("Extruder *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall"); + LSTR MSG_MOVE_N_MM = _UxGT("Flytta %smm"); + LSTR MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("Flytta 1mm"); + LSTR MSG_MOVE_10MM = _UxGT("Flytta 10mm"); + LSTR MSG_MOVE_100MM = _UxGT("Flytta 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Flytta 0.001tum"); + LSTR MSG_MOVE_001IN = _UxGT("Flytta 0.01tum"); + LSTR MSG_MOVE_01IN = _UxGT("Flytta 0.1tum"); + LSTR MSG_SPEED = _UxGT("Hastighet"); + LSTR MSG_BED_Z = _UxGT("Bädd Z"); + LSTR MSG_NOZZLE = _UxGT("Munstycke"); + LSTR MSG_NOZZLE_N = _UxGT("Munstycke ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Munstycke Parkerad"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Munstycke Standby"); + LSTR MSG_BED = _UxGT("Bädd"); + LSTR MSG_CHAMBER = _UxGT("Inkapsling"); + LSTR MSG_FAN_SPEED = _UxGT("Fläkt Hastighet"); + LSTR MSG_FAN_SPEED_N = _UxGT("Fläkt Hastighet ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Lagrad Fläkt ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fläkt Hastighet"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fläkt Hastighet ~"); + LSTR MSG_CONTROLLER_FAN = _UxGT("Kontroller Fläkt"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Overksam Hastighet"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto läga"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktive Hastighet"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Overksam Period"); + LSTR MSG_FLOW = _UxGT("Flöde"); + LSTR MSG_FLOW_N = _UxGT("Flöde ~"); + LSTR MSG_CONTROL = _UxGT("Kontroll"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt"); + LSTR MSG_AUTOTEMP = _UxGT("Autotemp"); + LSTR MSG_LCD_ON = _UxGT("På"); + LSTR MSG_LCD_OFF = _UxGT("Av"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autojustera"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autojustera *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autojustera misslyckad. Dålig extruder."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad. Temperatur för hög."); + LSTR MSG_PID_TIMEOUT = _UxGT("Autojustera misslyckad! Tidsgräns."); + LSTR MSG_SELECT = _UxGT("Välj"); + LSTR MSG_SELECT_E = _UxGT("Välj *"); + LSTR MSG_ACC = _UxGT("Accel"); + LSTR MSG_JERK = _UxGT("Ryck"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Ryck"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Ryck"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Ryck"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Ryck"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Ryck"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Ryck"); + LSTR MSG_VE_JERK = _UxGT("Ve-Ryck"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); + LSTR MSG_VELOCITY = _UxGT("Hastighet"); + LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vmax *"); + LSTR MSG_VMIN = _UxGT("Vmin"); + LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); + LSTR MSG_ACCELERATION = _UxGT("Acceleration"); + LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Amax *"); + LSTR MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); + LSTR MSG_A_TRAVEL = _UxGT("A-Färdas"); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvens max"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Flöde min"); + LSTR MSG_STEPS_PER_MM = _UxGT("Steg/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steg/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steg/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steg/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steg/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steg/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steg/mm"); + LSTR MSG_E_STEPS = _UxGT("E Steg/mm"); + LSTR MSG_EN_STEPS = _UxGT("* Steg/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); + LSTR MSG_MOTION = _UxGT("Rörelse"); + LSTR MSG_FILAMENT = _UxGT("Tråd"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm³"); + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Gräns i mm³"); + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Gräns *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Tråd Dia."); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Tråd Dia. *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Lossa mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Ladda mm"); + LSTR MSG_ADVANCE_K = _UxGT("Advancera K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Advancera K *"); + LSTR MSG_CONTRAST = _UxGT("LCD Kontrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Spara Inställningar"); + LSTR MSG_LOAD_EEPROM = _UxGT("Ladda Inställningar"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Återställ Standard"); + LSTR MSG_INIT_EEPROM = _UxGT("Initiera EEPROM"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fel"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fel"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fel"); + LSTR MSG_SETTINGS_STORED = _UxGT("Inställningar Lagrad"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Media Uppdatera"); + LSTR MSG_RESET_PRINTER = _UxGT("Återställ Skrivare"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Uppdatera"); + LSTR MSG_INFO_SCREEN = _UxGT("Info Skärm"); + LSTR MSG_PREPARE = _UxGT("Förbered"); + LSTR MSG_TUNE = _UxGT("Justera"); + LSTR MSG_POWER_MONITOR = _UxGT("Ström övervakning"); + LSTR MSG_CURRENT = _UxGT("Ström"); + LSTR MSG_VOLTAGE = _UxGT("Spänning"); + LSTR MSG_POWER = _UxGT("Ström"); + LSTR MSG_START_PRINT = _UxGT("Start Utskrift"); + LSTR MSG_BUTTON_NEXT = _UxGT("Nästa"); + LSTR MSG_BUTTON_INIT = _UxGT("Initiera"); + LSTR MSG_BUTTON_STOP = _UxGT("Stoppa"); + LSTR MSG_BUTTON_PRINT = _UxGT("Skriv"); + LSTR MSG_BUTTON_RESET = _UxGT("Återställa"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorera"); + LSTR MSG_BUTTON_CANCEL = _UxGT("Avbryt"); + LSTR MSG_BUTTON_DONE = _UxGT("Färdig"); + LSTR MSG_BUTTON_BACK = _UxGT("Bakåt"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Fortsätt"); + LSTR MSG_BUTTON_SKIP = _UxGT("Hoppa över"); + LSTR MSG_PAUSING = _UxGT("Paus.."); + LSTR MSG_PAUSE_PRINT = _UxGT("Pausera Utskrift"); + LSTR MSG_RESUME_PRINT = _UxGT("Återuppta Utskrift"); + LSTR MSG_HOST_START_PRINT = _UxGT("Värd Start"); + LSTR MSG_STOP_PRINT = _UxGT("Stoppa Utskrift"); + LSTR MSG_END_LOOPS = _UxGT("Slut Upprepningsloop"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Skriver Objekt"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Avbryt Objekt"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Ström Avbrott"); + LSTR MSG_MEDIA_MENU = _UxGT("Skriv fråm Media"); + LSTR MSG_NO_MEDIA = _UxGT("Inget Media"); + LSTR MSG_DWELL = _UxGT("Sov..."); + LSTR MSG_USERWAIT = _UxGT("Klick för att återuppta..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Utskrift Pausad"); + LSTR MSG_PRINTING = _UxGT("Skriver..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Utskrift Avbruten"); + LSTR MSG_PRINT_DONE = _UxGT("Utskrift Färdig"); + LSTR MSG_NO_MOVE = _UxGT("Ingen Flytt."); + LSTR MSG_KILLED = _UxGT("DÖDAD. "); + LSTR MSG_STOPPED = _UxGT("STOPPAD. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Dra tillbaka mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Byt Dra.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Dra tillbaka V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hoppa mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Åter dra tillbaka. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Byt åter dra t. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Återdrat. V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Byt åter dra. V"); + LSTR MSG_AUTORETRACT = _UxGT("Auto-Dra-tillbka"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Byt Längd"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Byt Extra"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Rensa Längd"); + LSTR MSG_TOOL_CHANGE = _UxGT("Byt verktyg"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Höj"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Grund Hastighet"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Återgå Hastighet"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkera Huvud"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Återgår Hastighet"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fläkt Hastighet"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fläkt Tid"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto PÅ"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AV"); + LSTR MSG_TOOL_MIGRATION = _UxGT("Verktyg Migration"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Senast Extruder"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrera till *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Byt Tråd"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Byt Tråd *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Ladda Tråd"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Ladda *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Lossa Tråd"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Lossa *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Lossa All"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Bifoga Media"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Byt Media"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Släpp Media"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z Sond Utanför Bädd"); + LSTR MSG_SKEW_FACTOR = _UxGT("Skev Faktor"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Själv-Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Återställ"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Stuva undan"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Fällut"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Läge"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Läge"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Läge"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Läge-Lägring"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Sätt BLTouch to 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Sätt BLTouch to OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Reportera Dränering"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("FARA: Dålig inställningar kan orsaka skada! Fortsätt ändå?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Initiera TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Spara"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Fällut TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Fällut Z-Sond"); + LSTR MSG_MANUAL_STOW = _UxGT("Stuva undan Z-Sond"); + LSTR MSG_HOME_FIRST = _UxGT("Hem %s%s%s Först"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Sond Offsets"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Sond X Offset"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Sond Y Offset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Sond Z Offset"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Flytta Munstycke till Bädd"); + LSTR MSG_BABYSTEP_X = _UxGT("Småsteg X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Småsteg Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Småsteg Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Slutstopp Avbrott"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Värma Misslyckad"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Fel: REDUNDANT TEMP"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TERMISK ÖVERDRIFT"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BÄDD TERMISK ÖVERDRIFT"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMMARE T. ÖVERDRIFT"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Fel: MAXTEMP"); + LSTR MSG_ERR_MINTEMP = _UxGT("Fel: MINTEMP"); + LSTR MSG_HALTED = _UxGT("Utskrift stoppad"); + LSTR MSG_PLEASE_RESET = _UxGT("Snälla Återställ"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("t"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_HEATING = _UxGT("Värmer..."); + LSTR MSG_COOLING = _UxGT("Kyler..."); + LSTR MSG_BED_HEATING = _UxGT("Bädd Värmer..."); + LSTR MSG_BED_COOLING = _UxGT("Bädd Kyler..."); + LSTR MSG_PROBE_HEATING = _UxGT("Sond Värmer..."); + LSTR MSG_PROBE_COOLING = _UxGT("Sond Kyler..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Kammare Värmer..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Kammare Kyler..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrera X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrera Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrera Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera Center"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Inställningar"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibrering"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Sätt Delta Höjd"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sond Z-offset"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Höjd"); + LSTR MSG_DELTA_RADIUS = _UxGT("Radius"); + LSTR MSG_INFO_MENU = _UxGT("Om Skrivaren"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Skrivare Info"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-Punkt Nivellering"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Linjär Nivellering"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilinjär Nivellering"); + LSTR MSG_UBL_LEVELING = _UxGT("Enhetlig Bädd Nivellering (UBL)"); + LSTR MSG_MESH_LEVELING = _UxGT("Nät Nivellering"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Skrivar Stats"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistor"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Extruderare"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Överdrift Övervakning: AV"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Överdrift Övervakning: PÅ"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hetände Overksam Tidsgräns"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Lådljus"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljus ljusstyrka"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("INKORREKT SKRIVARE"); + LSTR MSG_CASE_LIGHT = _UxGT("Lådljus"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljus ljusstyrka"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INKORREKT SKRIVARE"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Utskriftsantal"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdiga"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total Utskriftstid"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längsta Jobbtid"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderade Totalt"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Utskriftsantal"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdiga"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total Utskriftstid"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längsta Jobbtid"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderade Totalt"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Utskrift"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdig"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Längsta"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderad"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Utskrift"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdig"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längsta"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderad"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("PSU"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("TRÅDBYTE"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("UTSKRIFTSPAUSERAD"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LADDA TRÅD"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("LOSSA TRÅD"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ÅTERGÅ VAÖ:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Rensa mer"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Fortsätt"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Munstycke: "); - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Utskjut Sensor"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Utskjut Dist mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Hemning Misslyckad"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondering Misslyckad"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + LSTR MSG_INFO_PSU = _UxGT("PSU"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("TRÅDBYTE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("UTSKRIFTSPAUSERAD"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LADDA TRÅD"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("LOSSA TRÅD"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ÅTERGÅ VAÖ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Rensa mer"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Fortsätt"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Munstycke: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Utskjut Sensor"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Utskjut Dist mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Hemning Misslyckad"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondering Misslyckad"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VÄLJ TRÅD"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uppdatera MMU Firmware!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Behöver uppmärksamhet."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Återuppta"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Återupptas..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Ladda"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Ladda Alla"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Ladda till Munstycke"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Mata ut"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Mata ut ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Lossa"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Ladda Tråd %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Mata ut Tråd ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Lossa Tråd..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Alla"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Tråd ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Återställ MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Återställer..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, Klicka"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VÄLJ TRÅD"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Uppdatera MMU Firmware!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Behöver uppmärksamhet."); + LSTR MSG_MMU2_RESUME = _UxGT("MMU Återuppta"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU Återupptas..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Ladda"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Ladda Alla"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Ladda till Munstycke"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Mata ut"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Mata ut ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Lossa"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Ladda Tråd %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Mata ut Tråd ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Lossa Tråd..."); + LSTR MSG_MMU2_ALL = _UxGT("Alla"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Tråd ~"); + LSTR MSG_MMU2_RESET = _UxGT("Återställ MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU Återställer..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, Klicka"); - PROGMEM Language_Str MSG_MIX = _UxGT("Mixa"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); - 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("Växla Mix"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Totera Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Omvänd Gradient"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktive V-verktyg"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-verktyg"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Slut V-verktyg"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-verktyg"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Återställ V-verktyg"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Kommitta V-verktyg Mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-verktyg blev Återställda"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Slut Z:"); + LSTR MSG_MIX = _UxGT("Mixa"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); + LSTR MSG_MIXER = _UxGT("Mixer"); + LSTR MSG_GRADIENT = _UxGT("Gradient"); + LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); + LSTR MSG_TOGGLE_MIX = _UxGT("Växla Mix"); + LSTR MSG_CYCLE_MIX = _UxGT("Totera Mix"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Omvänd Gradient"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktive V-verktyg"); + LSTR MSG_START_VTOOL = _UxGT("Start V-verktyg"); + LSTR MSG_END_VTOOL = _UxGT(" Slut V-verktyg"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-verktyg"); + LSTR MSG_RESET_VTOOLS = _UxGT("Återställ V-verktyg"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Kommitta V-verktyg Mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-verktyg blev Återställda"); + LSTR MSG_START_Z = _UxGT("Start Z:"); + LSTR MSG_END_Z = _UxGT(" Slut Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Spel"); - 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("Labyrint"); + LSTR MSG_GAMES = _UxGT("Spel"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Labyrint"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Dålig sida index"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Dålig sida hastighet"); + LSTR MSG_BAD_PAGE = _UxGT("Dålig sida index"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Dålig sida hastighet"); - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Redigera Lösenord"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login Krävs"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Lösenordsinställningar"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Ange Siffra"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Sätt/Redigera Lösenord"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Ta bort Lösenord"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Lösenord är "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Börja om"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Kom ihåg att Spara!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Lösenord Bort taget"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Redigera Lösenord"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Login Krävs"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Lösenordsinställningar"); + LSTR MSG_ENTER_DIGIT = _UxGT("Ange Siffra"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Sätt/Redigera Lösenord"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Ta bort Lösenord"); + LSTR MSG_PASSWORD_SET = _UxGT("Lösenord är "); + LSTR MSG_START_OVER = _UxGT("Börja om"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Kom ihåg att Spara!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Lösenord Bort taget"); // // 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("Tryck på knappen", "för att fortsätta utskrift")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vänta på", "trådbyte", "att börja")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Sätt in tråd", "och tryck på knappen", "för att fortsätta")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Tryck på knappen", "för att värma munstycke")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Munstycke värms", "Var snäll och vänta...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Väntar på", "trådlossning")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Väntar på", "trådladdning")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Väntar på", "tråd utrensning")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klicka för att slutföra", "tråd utrensning")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Väntar på utskrift", "att återstarta...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Tryck på knappen", "för att fortsätta utskrift")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Vänta på", "trådbyte", "att börja")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Sätt in tråd", "och tryck på knappen", "för att fortsätta")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Tryck på knappen", "för att värma munstycke")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Munstycke värms", "Var snäll och vänta...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Väntar på", "trådlossning")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Väntar på", "trådladdning")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Väntar på", "tråd utrensning")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Klicka för att slutföra", "tråd utrensning")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Väntar på utskrift", "att återstarta...")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick för att fortsätta")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Vänta...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Sätt in och klicka")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klicka för att värma")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Värmer...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Lossar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Laddar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Rensar...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klicka för att slutföra")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Återgår...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Klick för att fortsätta")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkera...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Vänta...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Sätt in och klicka")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Klicka för att värma")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Värmer...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Lossar...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Laddar...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Rensar...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klicka för att slutföra")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Återgår...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver Ström"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Tröskelvärde"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorlös Hemning"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stegningsläge"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Smyghack Aktiverad"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Återställ"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korrigering"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glättning"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); + LSTR MSG_TMC_CURRENT = _UxGT("Driver Ström"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Tröskelvärde"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorlös Hemning"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stegningsläge"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Smyghack Aktiverad"); + LSTR MSG_SERVICE_RESET = _UxGT("Återställ"); + LSTR MSG_SERVICE_IN = _UxGT(" in:"); + LSTR MSG_BACKLASH = _UxGT("Backlash"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrigering"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glättning"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivå X Axel"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Kalibrera"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivå X Axel"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Kalibrera"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Overksam tidsgräns, temperatur minskning. Tryck ok för att återvärma och igen för att fortsätta."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Overksam tidsgräns, temperatur minskning. Tryck ok för att återvärma och igen för att fortsätta."); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Värmare Tidsgräns"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Värmare Tidsgräns"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Återvärm"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Återvärmning..."); + LSTR MSG_REHEAT = _UxGT("Återvärm"); + LSTR MSG_REHEATING = _UxGT("Återvärmning..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Sond Wizard"); - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Sondering Z Referens"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Flyttar till Sonderings Pos"); + LSTR MSG_PROBE_WIZARD = _UxGT("Z Sond Wizard"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Sondering Z Referens"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Flyttar till Sonderings Pos"); - PROGMEM Language_Str MSG_SOUND = _UxGT("Ljud"); + LSTR MSG_SOUND = _UxGT("Ljud"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Uppe Vänster"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Nere Vänster"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Uppe Höger"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Nere Höger"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrering Färdig"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrering Misslyckad"); + LSTR MSG_TOP_LEFT = _UxGT("Uppe Vänster"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Nere Vänster"); + LSTR MSG_TOP_RIGHT = _UxGT("Uppe Höger"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Nere Höger"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrering Färdig"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrering Misslyckad"); } diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index 16cafbebbe..20b5a7e686 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -116,121 +116,121 @@ namespace Language_test { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; + constexpr uint8_t CHARSIZE = 1; #if ENABLED(DISPLAYTEST) - PROGMEM Language_Str WELCOME_MSG = _UxGT("Language TEST"); + LSTR WELCOME_MSG = _UxGT("Language TEST"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Display test"); - PROGMEM Language_Str MSG_PREPARE = STRG_OKTAL_b; - PROGMEM Language_Str MSG_CONTROL = STRG_OKTAL_c; + LSTR MSG_INFO_SCREEN = _UxGT("Display test"); + LSTR MSG_PREPARE = STRG_OKTAL_b; + LSTR MSG_CONTROL = STRG_OKTAL_c; #endif #if ENABLED(WEST) - PROGMEM Language_Str WELCOME_MSG = _UxGT("Language TEST"); + LSTR WELCOME_MSG = _UxGT("Language TEST"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("UTF8"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("ASCII"); + LSTR MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); + LSTR MSG_PREPARE = _UxGT("UTF8"); + LSTR MSG_CONTROL = _UxGT("ASCII"); - PROGMEM Language_Str MSG_MAIN = _UxGT(".."); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = STRG_C2_8; - PROGMEM Language_Str MSG_AUTO_HOME = STRG_C2_9; - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = STRG_C2_a; - PROGMEM Language_Str MSG_PREHEAT_1 = STRG_C2_b; - PROGMEM Language_Str MSG_PREHEAT_2 = STRG_C3_8; - PROGMEM Language_Str MSG_COOLDOWN = STRG_C3_9; - PROGMEM Language_Str MSG_SWITCH_PS_OFF = STRG_C3_a; - PROGMEM Language_Str MSG_MOVE_AXIS = STRG_C3_b; + LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_DISABLE_STEPPERS = STRG_C2_8; + LSTR MSG_AUTO_HOME = STRG_C2_9; + LSTR MSG_SET_HOME_OFFSETS = STRG_C2_a; + LSTR MSG_PREHEAT_1 = STRG_C2_b; + LSTR MSG_PREHEAT_2 = STRG_C3_8; + LSTR MSG_COOLDOWN = STRG_C3_9; + LSTR MSG_SWITCH_PS_OFF = STRG_C3_a; + LSTR MSG_MOVE_AXIS = STRG_C3_b; - PROGMEM Language_Str MSG_MAIN = STRG_OKTAL_2; - PROGMEM Language_Str MSG_TEMPERATURE = STRG_OKTAL_3; - PROGMEM Language_Str MSG_MOTION = STRG_OKTAL_4; - PROGMEM Language_Str MSG_FILAMENT = STRG_OKTAL_5; - PROGMEM Language_Str MSG_CONTRAST = STRG_OKTAL_6; - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; + LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_TEMPERATURE = STRG_OKTAL_3; + LSTR MSG_MOTION = STRG_OKTAL_4; + LSTR MSG_FILAMENT = STRG_OKTAL_5; + LSTR MSG_CONTRAST = STRG_OKTAL_6; + LSTR MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; - PROGMEM Language_Str MSG_NOZZLE = STRG_OKTAL_8; - PROGMEM Language_Str MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; - PROGMEM Language_Str MSG_FAN_SPEED = STRG_OKTAL_9; - PROGMEM Language_Str MSG_FAN_SPEED_N = STRG_OKTAL_9; - PROGMEM Language_Str MSG_AUTOTEMP = STRG_OKTAL_a; - PROGMEM Language_Str MSG_MIN = STRG_OKTAL_b; - PROGMEM Language_Str MSG_MAX = STRG_OKTAL_c; - PROGMEM Language_Str MSG_FACTOR = STRG_OKTAL_d; - PROGMEM Language_Str MSG_PID_P = STRG_OKTAL_e; - PROGMEM Language_Str MSG_PID_I = STRG_OKTAL_f; + LSTR MSG_NOZZLE = STRG_OKTAL_8; + LSTR MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; + LSTR MSG_FAN_SPEED = STRG_OKTAL_9; + LSTR MSG_FAN_SPEED_N = STRG_OKTAL_9; + LSTR MSG_AUTOTEMP = STRG_OKTAL_a; + LSTR MSG_MIN = STRG_OKTAL_b; + LSTR MSG_MAX = STRG_OKTAL_c; + LSTR MSG_FACTOR = STRG_OKTAL_d; + LSTR MSG_PID_P = STRG_OKTAL_e; + LSTR MSG_PID_I = STRG_OKTAL_f; #endif #if ENABLED(CYRIL) - PROGMEM Language_Str WELCOME_MSG = _UxGT("Language TEST"); + LSTR WELCOME_MSG = _UxGT("Language TEST"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("UTF8"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("ASCII"); + LSTR MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); + LSTR MSG_PREPARE = _UxGT("UTF8"); + LSTR MSG_CONTROL = _UxGT("ASCII"); - PROGMEM Language_Str MSG_MAIN = _UxGT(".."); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = STRG_D0_8; - PROGMEM Language_Str MSG_AUTO_HOME = STRG_D0_9; - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = STRG_D0_a; - PROGMEM Language_Str MSG_PREHEAT_1 = STRG_D0_b; - PROGMEM Language_Str MSG_PREHEAT_2 = STRG_D1_8; - PROGMEM Language_Str MSG_COOLDOWN = STRG_D1_9; - PROGMEM Language_Str MSG_SWITCH_PS_OFF = STRG_D1_a; - PROGMEM Language_Str MSG_MOVE_AXIS = STRG_D1_b; + LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_DISABLE_STEPPERS = STRG_D0_8; + LSTR MSG_AUTO_HOME = STRG_D0_9; + LSTR MSG_SET_HOME_OFFSETS = STRG_D0_a; + LSTR MSG_PREHEAT_1 = STRG_D0_b; + LSTR MSG_PREHEAT_2 = STRG_D1_8; + LSTR MSG_COOLDOWN = STRG_D1_9; + LSTR MSG_SWITCH_PS_OFF = STRG_D1_a; + LSTR MSG_MOVE_AXIS = STRG_D1_b; - PROGMEM Language_Str MSG_MAIN = STRG_OKTAL_2; - PROGMEM Language_Str MSG_TEMPERATURE = STRG_OKTAL_3; - PROGMEM Language_Str MSG_MOTION = STRG_OKTAL_4; - PROGMEM Language_Str MSG_FILAMENT = STRG_OKTAL_5; - PROGMEM Language_Str MSG_CONTRAST = STRG_OKTAL_6; - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; + LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_TEMPERATURE = STRG_OKTAL_3; + LSTR MSG_MOTION = STRG_OKTAL_4; + LSTR MSG_FILAMENT = STRG_OKTAL_5; + LSTR MSG_CONTRAST = STRG_OKTAL_6; + LSTR MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; - PROGMEM Language_Str MSG_NOZZLE = STRG_OKTAL_8; - PROGMEM Language_Str MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; - PROGMEM Language_Str MSG_FAN_SPEED_N = STRG_OKTAL_9; - PROGMEM Language_Str MSG_AUTOTEMP = STRG_OKTAL_a; - PROGMEM Language_Str MSG_MIN = STRG_OKTAL_b; - PROGMEM Language_Str MSG_MAX = STRG_OKTAL_c; - PROGMEM Language_Str MSG_FACTOR = STRG_OKTAL_d; - PROGMEM Language_Str MSG_PID_P = STRG_OKTAL_e; - PROGMEM Language_Str MSG_PID_I = STRG_OKTAL_f; + LSTR MSG_NOZZLE = STRG_OKTAL_8; + LSTR MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; + LSTR MSG_FAN_SPEED_N = STRG_OKTAL_9; + LSTR MSG_AUTOTEMP = STRG_OKTAL_a; + LSTR MSG_MIN = STRG_OKTAL_b; + LSTR MSG_MAX = STRG_OKTAL_c; + LSTR MSG_FACTOR = STRG_OKTAL_d; + LSTR MSG_PID_P = STRG_OKTAL_e; + LSTR MSG_PID_I = STRG_OKTAL_f; #endif #if ENABLED(KANA) - PROGMEM Language_Str WELCOME_MSG = _UxGT("Language TEST"); + LSTR WELCOME_MSG = _UxGT("Language TEST"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("UTF8"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("ASCII"); + LSTR MSG_INFO_SCREEN = _UxGT("\001\002\003\004\005\006\007\010\011"); + LSTR MSG_PREPARE = _UxGT("UTF8"); + LSTR MSG_CONTROL = _UxGT("ASCII"); - PROGMEM Language_Str MSG_MAIN = _UxGT(".."); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = STRG_E382_8; - PROGMEM Language_Str MSG_AUTO_HOME = STRG_E382_9; - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = STRG_E382_a; - PROGMEM Language_Str MSG_PREHEAT_1 = STRG_E382_b; - PROGMEM Language_Str MSG_PREHEAT_2 = STRG_E383_8; - PROGMEM Language_Str MSG_COOLDOWN = STRG_E383_9; - PROGMEM Language_Str MSG_SWITCH_PS_OFF = STRG_E383_a; - PROGMEM Language_Str MSG_MOVE_AXIS = STRG_E383_b; + LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_DISABLE_STEPPERS = STRG_E382_8; + LSTR MSG_AUTO_HOME = STRG_E382_9; + LSTR MSG_SET_HOME_OFFSETS = STRG_E382_a; + LSTR MSG_PREHEAT_1 = STRG_E382_b; + LSTR MSG_PREHEAT_2 = STRG_E383_8; + LSTR MSG_COOLDOWN = STRG_E383_9; + LSTR MSG_SWITCH_PS_OFF = STRG_E383_a; + LSTR MSG_MOVE_AXIS = STRG_E383_b; - PROGMEM Language_Str MSG_MAIN = STRG_OKTAL_2; - PROGMEM Language_Str MSG_TEMPERATURE = STRG_OKTAL_3; - PROGMEM Language_Str MSG_MOTION = STRG_OKTAL_4; - PROGMEM Language_Str MSG_FILAMENT = STRG_OKTAL_5; - PROGMEM Language_Str MSG_CONTRAST = STRG_OKTAL_6; - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; + LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_TEMPERATURE = STRG_OKTAL_3; + LSTR MSG_MOTION = STRG_OKTAL_4; + LSTR MSG_FILAMENT = STRG_OKTAL_5; + LSTR MSG_CONTRAST = STRG_OKTAL_6; + LSTR MSG_RESTORE_DEFAULTS = STRG_OKTAL_7; - PROGMEM Language_Str MSG_NOZZLE = STRG_OKTAL_8; - PROGMEM Language_Str MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; - PROGMEM Language_Str MSG_FAN_SPEED_N = STRG_OKTAL_9; - PROGMEM Language_Str MSG_AUTOTEMP = STRG_OKTAL_a; - PROGMEM Language_Str MSG_MIN = STRG_OKTAL_b; - PROGMEM Language_Str MSG_MAX = STRG_OKTAL_c; - PROGMEM Language_Str MSG_FACTOR = STRG_OKTAL_d; - PROGMEM Language_Str MSG_PID_P = STRG_OKTAL_e; - PROGMEM Language_Str MSG_PID_I = STRG_OKTAL_f; + LSTR MSG_NOZZLE = STRG_OKTAL_8; + LSTR MSG_NOZZLE_N = STRG_OKTAL_8 " ~"; + LSTR MSG_FAN_SPEED_N = STRG_OKTAL_9; + LSTR MSG_AUTOTEMP = STRG_OKTAL_a; + LSTR MSG_MIN = STRG_OKTAL_b; + LSTR MSG_MAX = STRG_OKTAL_c; + LSTR MSG_FACTOR = STRG_OKTAL_d; + LSTR MSG_PID_P = STRG_OKTAL_e; + LSTR MSG_PID_I = STRG_OKTAL_f; #endif } diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index f31eb5b13f..e56071405c 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -37,512 +37,512 @@ namespace Language_tr { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Turkish"); + constexpr uint8_t CHARSIZE = 2; + LSTR 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_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"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Gelişmiş Ayarlar"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Yapılandırma"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Oto. Başlat"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motorları Durdur"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Hata Ayıklama"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Durum Çubuğu Testi"); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Eksenleri Sıfırla"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("X Sıfırla"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Y Sıfırla"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Z Sıfırla"); - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Oto. Z-Hizalama"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ Sıfırlanıyor"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Başlatmak için tıkla"); - 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("Ofset Ayarla"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofset Tamam"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sıfır Belirle"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" hazır."); + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("EVET"); + LSTR MSG_NO = _UxGT("HAYIR"); + LSTR MSG_BACK = _UxGT("Geri"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Durduruluyor..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD K. Yerleştirildi."); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD Kart Çıkarıldı."); + LSTR MSG_MEDIA_WAITING = _UxGT("SD Kart Bekleniyor"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Kart Okuma Hatası"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Çıkarıldı"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Başlat. Hatası"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Enstops"); // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Yazılımsal Endstops"); + LSTR MSG_MAIN = _UxGT("Ana"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Gelişmiş Ayarlar"); + LSTR MSG_CONFIGURATION = _UxGT("Yapılandırma"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Oto. Başlat"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Motorları Durdur"); + LSTR MSG_DEBUG_MENU = _UxGT("Hata Ayıklama"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Durum Çubuğu Testi"); + LSTR MSG_AUTO_HOME = _UxGT("Eksenleri Sıfırla"); + LSTR MSG_AUTO_HOME_X = _UxGT("X Sıfırla"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Y Sıfırla"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Z Sıfırla"); + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Oto. Z-Hizalama"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("XYZ Sıfırlanıyor"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Başlatmak için tıkla"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Sonraki Nokta"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Hizalama Tamam!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Kaçınma Yüksekliği"); + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ofset Ayarla"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofset Tamam"); + LSTR MSG_SET_ORIGIN = _UxGT("Sıfır Belirle"); #if PREHEAT_COUNT - 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 " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Nozul"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Nozul ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Tüm"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Tabla"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Ayarlar"); + LSTR MSG_PREHEAT_1 = _UxGT("Ön Isınma ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Ön Isınma ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Nozul"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Nozul ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Tüm"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Tabla"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Ön Isınma ") PREHEAT_1_LABEL _UxGT(" Ayarlar"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Ön Isınma $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Ön Isınma $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Ön Isınma $ Nozul"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Ön Isınma $ Nozul ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Ön Isınma $ Tüm"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Ön Isınma $ Tabla"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Ön Isınma $ Ayarlar"); + LSTR MSG_PREHEAT_M = _UxGT("Ön Isınma $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Ön Isınma $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Ön Isınma $ Nozul"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Ön Isınma $ Nozul ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Ön Isınma $ Tüm"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Ön Isınma $ Tabla"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Ön Isınma $ Ayarlar"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Özel Ön Isınma"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Soğut/(Durdur)"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lazer Kontrolü"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lazer Gücü"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindle Kontrolü"); - 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"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Geri Çek"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Eksen Hareketleri"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Tabla Hizalama"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Tabla Hizası"); - PROGMEM Language_Str MSG_BED_TRAMMING = _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_POINT = _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_CUSTOM_COMMANDS = _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"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Tam Kontrol"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2. nozul X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2. nozul Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2. nozul Z"); - 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çü"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Yataktan Ölçü Kaldır"); - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Sonrakine Git"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL'yi Etkinleştir"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL'yi Etkisizleştir"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Yatak Sıcaklığı"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Yatak Sıcaklığı"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Nozul Sıcaklığı"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Nozul Sıcaklığı"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Mesh Düzenleme"); - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Özel Mesh Düzenleme"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("İnce Ayar Mesh"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Mesh Düzenleme Tamam"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Özel Mesh Oluştur"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Mesh Oluştur"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Özel Ön Isınma"); + LSTR MSG_COOLDOWN = _UxGT("Soğut/(Durdur)"); + LSTR MSG_LASER_MENU = _UxGT("Lazer Kontrolü"); + LSTR MSG_LASER_POWER = _UxGT("Lazer Gücü"); + LSTR MSG_SPINDLE_MENU = _UxGT("Spindle Kontrolü"); + LSTR MSG_SPINDLE_POWER = _UxGT("Spindle Gücü"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindle Ters Yön"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Gücü Aç"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Gücü Kapat"); + LSTR MSG_EXTRUDE = _UxGT("Ekstrüzyon"); + LSTR MSG_RETRACT = _UxGT("Geri Çek"); + LSTR MSG_MOVE_AXIS = _UxGT("Eksen Hareketleri"); + LSTR MSG_BED_LEVELING = _UxGT("Tabla Hizalama"); + LSTR MSG_LEVEL_BED = _UxGT("Tabla Hizası"); + LSTR MSG_BED_TRAMMING = _UxGT("Hizalama Köşeleri"); + LSTR MSG_NEXT_CORNER = _UxGT("Sonraki Köşe"); + LSTR MSG_MESH_EDITOR = _UxGT("Mesh Editörü"); + LSTR MSG_EDIT_MESH = _UxGT("Mesh Düzenle"); + LSTR MSG_EDITING_STOPPED = _UxGT("Mesh Düzenleme Durdu"); + LSTR MSG_PROBING_POINT = _UxGT("Prop Noktası"); + LSTR MSG_MESH_X = _UxGT("İndeks X"); + LSTR MSG_MESH_Y = _UxGT("İndeks Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z Değeri"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Özel Komutlar"); + LSTR MSG_M48_TEST = _UxGT("M48 Prob Testi"); + LSTR MSG_M48_POINT = _UxGT("M48 Nokta"); + LSTR MSG_M48_DEVIATION = _UxGT("Sapma"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX Modu"); + LSTR MSG_OFFSETS_MENU = _UxGT("Takım Ofsetleri"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Oto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Kopyala"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Yansıtılmış kopya"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Tam Kontrol"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. nozul X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. nozul Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. nozul Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("G29 Çalışıyor"); + LSTR MSG_UBL_TOOLS = _UxGT("UBL Araçları"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("UBL Yatak Hizalama"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Eğim Noktası"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Elle Mesh Oluştur"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Altlık & Ölçü Ver"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Ölçü"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Yataktan Ölçü Kaldır"); + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Sonrakine Git"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("UBL'yi Etkinleştir"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL'yi Etkisizleştir"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Yatak Sıcaklığı"); + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Yatak Sıcaklığı"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Nozul Sıcaklığı"); + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Nozul Sıcaklığı"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Mesh Düzenleme"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Özel Mesh Düzenleme"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("İnce Ayar Mesh"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Mesh Düzenleme Tamam"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Özel Mesh Oluştur"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Mesh Oluştur"); #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Mesh Oluştur ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Doğrulama Mesh ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Mesh Oluştur ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Doğrulama Mesh ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Soğuk Mesh Oluştur"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Mesh Yükseklik Ayarı"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Yükseklik miktarı"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Doğrulama Mesh"); - 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"); - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Kafes Mesh Hizalama"); - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Mesh Seviyesi"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Yan Noktalar"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Haritalama Türü"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Mesh Çıkış Haritası"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host için Çıktı"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV için Çıktı"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Yazıcıda Yedek Kpalı"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("UBL Çıkış Bilgisi"); - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Dolgu Miktarı"); - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Manuel Dolgu"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Akıllı Dogu"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Mesh Dolgu"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Tümünü Geçersiz Kıl"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Yakını Geçersiz Kıl"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Tümünü İnce Ayarla"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Yakını İnce Ayarla"); - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Depolama"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Bellek Yuvası"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Yatak Mesh Yükle"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Yatak Mesh Kayıt Et"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Mesh %i yüklendi"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Mesh %i kayıtlandı"); - 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"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Akıllı Dogu"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Doğrulama Mesh"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Tümünü İnce Ayarla"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Doğrulama Mesh"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Tümünü İnce Ayarla"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Yatak Mesh Kayıt Et"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Soğuk Mesh Oluştur"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Mesh Yükseklik Ayarı"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Yükseklik miktarı"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Doğrulama Mesh"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Özel Mesh Doğrulama"); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 Isıtma Tablası"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Isıtma Memesi"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manuel çalışma..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Birincil Sabit Uzunluk"); + LSTR MSG_G26_PRIME_DONE = _UxGT("Çalışma Tamamlandı"); + LSTR MSG_G26_CANCELED = _UxGT("G26 İptal edildi"); + LSTR MSG_G26_LEAVING = _UxGT("Çıkış G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Tabla Mesh Devam et"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Mesh Hizalama"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Nokta Hizalama"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Kafes Mesh Hizalama"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Mesh Seviyesi"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Yan Noktalar"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Haritalama Türü"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Mesh Çıkış Haritası"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Host için Çıktı"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("CSV için Çıktı"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Yazıcıda Yedek Kpalı"); + LSTR MSG_UBL_INFO_UBL = _UxGT("UBL Çıkış Bilgisi"); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Dolgu Miktarı"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuel Dolgu"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Akıllı Dogu"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Mesh Dolgu"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Tümünü Geçersiz Kıl"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Yakını Geçersiz Kıl"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Tümünü İnce Ayarla"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Yakını İnce Ayarla"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Mesh Depolama"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Bellek Yuvası"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Yatak Mesh Yükle"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Yatak Mesh Kayıt Et"); + LSTR MSG_MESH_LOADED = _UxGT("Mesh %i yüklendi"); + LSTR MSG_MESH_SAVED = _UxGT("Mesh %i kayıtlandı"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Depolama Yok"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Hata: UBL Kayıt"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Hata: UBL Yenileme"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Ofset: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Ofset Durduruldu"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Adım Adım UBL"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Soğuk Mesh Oluştur"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Akıllı Dogu"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Doğrulama Mesh"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Tümünü İnce Ayarla"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Doğrulama Mesh"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Tümünü İnce Ayarla"); + LSTR 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("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ı"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Yeşil"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Mavi"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Lacivert"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Menekşe"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Beyaz"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Varsayılan"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Özel Işıklar"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Kırmızı Şiddeti"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Yeşil Şiddeti"); - 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"); + LSTR MSG_LED_CONTROL = _UxGT("LED Kontrolü"); + LSTR MSG_LEDS = _UxGT("LEDler"); + LSTR MSG_LED_PRESETS = _UxGT("LED Hazır Ayarları"); + LSTR MSG_SET_LEDS_RED = _UxGT("Kırmızı"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Turuncu"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Sarı"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Yeşil"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Mavi"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Lacivert"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Menekşe"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Beyaz"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Varsayılan"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Özel Işıklar"); + LSTR MSG_INTENSITY_R = _UxGT("Kırmızı Şiddeti"); + LSTR MSG_INTENSITY_G = _UxGT("Yeşil Şiddeti"); + LSTR MSG_INTENSITY_B = _UxGT("Mavi Şiddeti"); + LSTR MSG_INTENSITY_W = _UxGT("Beyaz Şiddeti"); + LSTR 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"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Y Hareketi"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Z Hareketi"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruder"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruder *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Nozul Çok Soğuk"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("%smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10mm"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Hız"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Mesafesi"); - 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ış"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Akış ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Kontrol"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Çarpan"); - 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_SELECT = _UxGT("Seç"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seç *"); - PROGMEM Language_Str MSG_ACC = _UxGT("İvme"); + LSTR MSG_MOVING = _UxGT("Hareket Ediyor.."); + LSTR MSG_FREE_XY = _UxGT("Durdur XY"); + LSTR MSG_MOVE_X = _UxGT("X Hareketi"); + LSTR MSG_MOVE_Y = _UxGT("Y Hareketi"); + LSTR MSG_MOVE_Z = _UxGT("Z Hareketi"); + LSTR MSG_MOVE_E = _UxGT("Ekstruder"); + LSTR MSG_MOVE_EN = _UxGT("Ekstruder *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Nozul Çok Soğuk"); + LSTR MSG_MOVE_N_MM = _UxGT("%smm"); + LSTR MSG_MOVE_01MM = _UxGT("0.1mm"); + LSTR MSG_MOVE_1MM = _UxGT("1mm"); + LSTR MSG_MOVE_10MM = _UxGT("10mm"); + LSTR MSG_MOVE_100MM = _UxGT("100mm"); + LSTR MSG_SPEED = _UxGT("Hız"); + LSTR MSG_BED_Z = _UxGT("Z Mesafesi"); + LSTR MSG_NOZZLE = _UxGT("Nozul"); + LSTR MSG_NOZZLE_N = _UxGT("Nozul ~"); + LSTR MSG_BED = _UxGT("Tabla"); + LSTR MSG_CHAMBER = _UxGT("Çevirme"); + LSTR MSG_FAN_SPEED = _UxGT("Fan Hızı"); + LSTR MSG_FAN_SPEED_N = _UxGT("Fan Hızı ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Depolanan Fan ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Ekstra Fan Hızı"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Ekstra Fan Hızı ~"); + LSTR MSG_FLOW = _UxGT("Akış"); + LSTR MSG_FLOW_N = _UxGT("Akış ~"); + LSTR MSG_CONTROL = _UxGT("Kontrol"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Çarpan"); + LSTR MSG_AUTOTEMP = _UxGT("Oto. Sıcaklık"); + LSTR MSG_LCD_ON = _UxGT("Açık"); + LSTR MSG_LCD_OFF = _UxGT("Kapalı"); + LSTR MSG_PID_AUTOTUNE = _UxGT("PID Kalibrasyon"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Kalibrasyon *"); + LSTR MSG_SELECT = _UxGT("Seç"); + LSTR MSG_SELECT_E = _UxGT("Seç *"); + LSTR 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"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Sarsım"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Sarsım"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Sarsım"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Sarsım"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Sarsım"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Jonksiyon Sapması"); - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Hız Vektörü"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("HızVektör.max ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("HızVektör.max ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("HızVektör.max ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("HızVektör.max ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("HızVektör.max ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("HızVektör.max ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("HızVektör.max ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("HızVektör.max *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("HızVektör.min"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("HV.gezinme min"); - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Ivme"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max. ivme ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max. ivme ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max. ivme ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Max. ivme ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Max. ivme ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Max. ivme ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max. ivme ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max. ivme *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ivme-geri çekme"); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Ivme-gezinme"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Adım/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" adım/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E adım/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* adım/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Sıcaklık"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Hareket"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filaman"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("Ekstrüzyon/mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Filaman Çapı"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Filaman Çapı *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Çıkart mm"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Yükle mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K İlerlet"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K İlerlet *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD Kontrast"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Hafızaya Al"); - 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!"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Uyku..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Operatör bekleniyor."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Baskı Duraklatıldı"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Baskı Yapılıyor..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Baskı Durduruldu!"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("İşlem yok."); - PROGMEM Language_Str MSG_KILLED = _UxGT("Kilitlendi. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("Durdu. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Geri Çek mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Geri Çekme V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Atlama mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); - 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_SPEED = _UxGT("Birincil Hız"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _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"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Filaman Yükle *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Filaman Çıkart"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Filaman Çıkart *"); - 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 K. Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Kapat"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Aç"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modu"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modu"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Modu"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("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_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_HALTED = _UxGT("YAZICI DURDURULDU"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Lütfen Resetleyin"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("G"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("S"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("D"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Isınıyor..."); - 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"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Ayarla Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Ayarla Merkez"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Delta Ayarları"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Oto Kalibrasyon"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Yük. Ayarla"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z Prob Ofseti"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Çapral Mil"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Yükseklik"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Yarıçap"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Yazıcı Hakkında"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Yazıcı Bilgisi"); - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-Nokta Hizalama"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Doğrusal Hizalama"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("İki Yönlü Doğ. Hiza."); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Birleşik Tabla Hiza."); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mesh Hizalama"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("İstatistikler"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Kontrolcü Bilgisi"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistörler"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Ekstruderler"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("İletişim Hızı"); - 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_KILL_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); + LSTR MSG_JERK = _UxGT("Sarsım"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Sarsım"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Sarsım"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Sarsım"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Sarsım"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Sarsım"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Sarsım"); + LSTR MSG_VE_JERK = _UxGT("Ve-Sarsım"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Jonksiyon Sapması"); + LSTR MSG_VELOCITY = _UxGT("Hız Vektörü"); + LSTR MSG_VMAX_A = _UxGT("HızVektör.max ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("HızVektör.max ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("HızVektör.max ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("HızVektör.max ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("HızVektör.max ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("HızVektör.max ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("HızVektör.max ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("HızVektör.max *"); + LSTR MSG_VMIN = _UxGT("HızVektör.min"); + LSTR MSG_VTRAV_MIN = _UxGT("HV.gezinme min"); + LSTR MSG_ACCELERATION = _UxGT("Ivme"); + LSTR MSG_AMAX_A = _UxGT("Max. ivme ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Max. ivme ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Max. ivme ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Max. ivme ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Max. ivme ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Max. ivme ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Max. ivme ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Max. ivme *"); + LSTR MSG_A_RETRACT = _UxGT("Ivme-geri çekme"); + LSTR MSG_A_TRAVEL = _UxGT("Ivme-gezinme"); + LSTR MSG_STEPS_PER_MM = _UxGT("Adım/mm"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" adım/mm"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" adım/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" adım/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" adım/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" adım/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" adım/mm"); + LSTR MSG_E_STEPS = _UxGT("E adım/mm"); + LSTR MSG_EN_STEPS = _UxGT("* adım/mm"); + LSTR MSG_TEMPERATURE = _UxGT("Sıcaklık"); + LSTR MSG_MOTION = _UxGT("Hareket"); + LSTR MSG_FILAMENT = _UxGT("Filaman"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("Ekstrüzyon/mm") SUPERSCRIPT_THREE; + LSTR MSG_FILAMENT_DIAM = _UxGT("Filaman Çapı"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Filaman Çapı *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Çıkart mm"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Yükle mm"); + LSTR MSG_ADVANCE_K = _UxGT("K İlerlet"); + LSTR MSG_ADVANCE_K_E = _UxGT("K İlerlet *"); + LSTR MSG_CONTRAST = _UxGT("LCD Kontrast"); + LSTR MSG_STORE_EEPROM = _UxGT("Hafızaya Al"); + LSTR MSG_LOAD_EEPROM = _UxGT("Hafızadan Yükle"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Fabrika Ayarları"); + LSTR MSG_INIT_EEPROM = _UxGT("EEPROM'u başlat"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Hata: EEPROM CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Hata: EEPROM Indeks"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Hata: EEPROM Versiyonu"); + LSTR MSG_MEDIA_UPDATE = _UxGT("SD Güncellemesi"); + LSTR MSG_RESET_PRINTER = _UxGT("Yazıcıyı Resetle"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Yenile"); + LSTR MSG_INFO_SCREEN = _UxGT("Bilgi Ekranı"); + LSTR MSG_PREPARE = _UxGT("Hazırlık"); + LSTR MSG_TUNE = _UxGT("Ayar"); + LSTR MSG_START_PRINT = _UxGT("Yaz. Başlat"); + LSTR MSG_BUTTON_NEXT = _UxGT("İleri"); + LSTR MSG_BUTTON_INIT = _UxGT("İçinde"); + LSTR MSG_BUTTON_STOP = _UxGT("Durdur"); + LSTR MSG_BUTTON_PRINT = _UxGT("Yazdır"); + LSTR MSG_BUTTON_RESET = _UxGT("Resetle"); + LSTR MSG_BUTTON_CANCEL = _UxGT("İptal"); + LSTR MSG_BUTTON_DONE = _UxGT("Tamamlandı"); + LSTR MSG_BUTTON_BACK = _UxGT("Geri"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Devam ediyor"); + LSTR MSG_PAUSE_PRINT = _UxGT("Duraklat"); + LSTR MSG_RESUME_PRINT = _UxGT("Sürdür"); + LSTR MSG_STOP_PRINT = _UxGT("Durdur"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Yazdırma Nesnesi"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Kesinti Kurtarma"); + LSTR MSG_MEDIA_MENU = _UxGT("SD Karttan Yazdır"); + LSTR MSG_NO_MEDIA = _UxGT("SD Kart Yok!"); + LSTR MSG_DWELL = _UxGT("Uyku..."); + LSTR MSG_USERWAIT = _UxGT("Operatör bekleniyor."); + LSTR MSG_PRINT_PAUSED = _UxGT("Baskı Duraklatıldı"); + LSTR MSG_PRINTING = _UxGT("Baskı Yapılıyor..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Baskı Durduruldu!"); + LSTR MSG_NO_MOVE = _UxGT("İşlem yok."); + LSTR MSG_KILLED = _UxGT("Kilitlendi. "); + LSTR MSG_STOPPED = _UxGT("Durdu. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Geri Çek mm"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Swap Re.mm"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Geri Çekme V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Atlama mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("S Unretr. mm"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + LSTR MSG_AUTORETRACT = _UxGT("Oto. Geri Çekme"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("G.Çekme Boyu"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tasfiye uzunluğu"); + LSTR MSG_TOOL_CHANGE = _UxGT("Takım Değişimi"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Yükselt"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Birincil Hız"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Geri Çekme Hızı"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Nozul Beklemede"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Filaman Değiştir"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Filaman Değiştir *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Filaman Yükle"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Filaman Yükle *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Filaman Çıkart"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Filaman Çıkart *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Tümünü Çıkart"); + LSTR MSG_ATTACH_MEDIA = _UxGT("SD Kart Başlatılıyor"); + LSTR MSG_CHANGE_MEDIA = _UxGT("SD Kart Değiştir"); + LSTR MSG_RELEASE_MEDIA = _UxGT("SD Kart Çıkart"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z Prob Açık. Tabla"); + LSTR MSG_SKEW_FACTOR = _UxGT("Çarpıklık Faktörü"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch K. Test"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Reset"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Kapat"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Aç"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modu"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modu"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Modu"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V Ayarla"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD Ayarla"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Drenaj Raporu"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("TEHLIKE: Kötü ayarlar hasara neden olabilir! Yine de devam edilsin mi?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Ofset Testi"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Kaydet"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI Aç"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Z-Probe Aç"); + LSTR MSG_MANUAL_STOW = _UxGT("Z-Probe Kapat"); + LSTR MSG_HOME_FIRST = _UxGT("Önce %s%s%s Sıfırla"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Prob Ofsetleri"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("X Prob Ofset"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Y Prob Ofset"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z Prob Ofset"); + LSTR MSG_BABYSTEP_X = _UxGT("Miniadım X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Miniadım Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Miniadım Z"); + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Toplam"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop iptal"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Isınma başarısız"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Hata: Sıcaklık Aşımı"); + LSTR MSG_THERMAL_RUNAWAY = _UxGT("TERMAL PROBLEM"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("TABLA TERMAL PROBLEM"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ODA TERMAL PROBLEM"); + LSTR MSG_ERR_MAXTEMP = _UxGT("Hata: MAX.SICAKLIK"); + LSTR MSG_ERR_MINTEMP = _UxGT("Hata: MIN.SICAKLIK"); + LSTR MSG_HALTED = _UxGT("YAZICI DURDURULDU"); + LSTR MSG_PLEASE_RESET = _UxGT("Lütfen Resetleyin"); + LSTR MSG_SHORT_DAY = _UxGT("G"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("S"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("D"); // One character only + LSTR MSG_HEATING = _UxGT("Isınıyor..."); + LSTR MSG_COOLING = _UxGT("Soğuyor..."); + LSTR MSG_BED_HEATING = _UxGT("Tabla Isınıyor..."); + LSTR MSG_BED_COOLING = _UxGT("Tabla Soğuyor..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Oda Isınıyor..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Oda Soğuyor..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrasyonu"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Ayarla X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Ayarla Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Ayarla Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Ayarla Merkez"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Ayarları"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Oto Kalibrasyon"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Yük. Ayarla"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z Prob Ofseti"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Çapral Mil"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Yükseklik"); + LSTR MSG_DELTA_RADIUS = _UxGT("Yarıçap"); + LSTR MSG_INFO_MENU = _UxGT("Yazıcı Hakkında"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Yazıcı Bilgisi"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-Nokta Hizalama"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Doğrusal Hizalama"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("İki Yönlü Doğ. Hiza."); + LSTR MSG_UBL_LEVELING = _UxGT("Birleşik Tabla Hiza."); + LSTR MSG_MESH_LEVELING = _UxGT("Mesh Hizalama"); + LSTR MSG_INFO_STATS_MENU = _UxGT("İstatistikler"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Kontrolcü Bilgisi"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistörler"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Ekstruderler"); + LSTR MSG_INFO_BAUDRATE = _UxGT("İletişim Hızı"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Protokol"); + LSTR MSG_CASE_LIGHT = _UxGT("Aydınlatmayı Aç"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Aydınlatma Parlaklğı"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Baskı Sayısı"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Tamamlanan"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Toplam Baskı Süresi"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("En Uzun Baskı Süresi"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Toplam Filaman"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Baskı Sayısı"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Tamamlanan"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Toplam Baskı Süresi"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("En Uzun Baskı Süresi"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Toplam Filaman"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Baskı"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Tamamlanan"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Süre"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("En Uzun"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Filaman"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Baskı"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Tamamlanan"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Süre"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("En Uzun"); + LSTR 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ğı"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Sürücü Gücü"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Sürücü %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Sürücü %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Sürücü %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Sürücü %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Sürücü %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 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"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Seçenekler:"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Daha Fazla Tasviye"); - 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_KILL_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Başarısız"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Sıc."); + LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Sıc."); + LSTR MSG_INFO_PSU = _UxGT("Güç Kaynağı"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Sürücü Gücü"); + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E Sürücü %"); + LSTR MSG_ERROR_TMC = _UxGT("TMC BAĞLANTI HATASI"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Yaz"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMAN DEGISTIR"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("BASKI DURAKLATILDI"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("FILAMAN YüKLE"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("FILAMAN ÇIKART"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Seçenekler:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Daha Fazla Tasviye"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Baskıyı sürdür"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozul: "); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout Sensörü"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Aşınma Farkı mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Başarısız"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMAN SEÇ"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_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"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMAN SEÇ"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("MMU Yaz. Güncelle!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Dikkat Gerektirir."); + LSTR MSG_MMU2_RESUME = _UxGT("Yaz. Devam Et"); + LSTR MSG_MMU2_RESUMING = _UxGT("Sürdürülüyor..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Filaman Yükle"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("Tümünü Yükle"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Nozula Yükle"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Filaman Çıkart"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Filaman Çıkart ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Filamenti Boşalt"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Fil. Yükleniyor %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Fil Çıkartılıyor. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Fil. Boşaltılıyor...."); + LSTR MSG_MMU2_ALL = _UxGT("Tümü"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filaman ~"); + LSTR MSG_MMU2_RESET = _UxGT("MMU Resetle"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU Resetleniyot..."); + LSTR 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:"); + LSTR MSG_MIX = _UxGT("Karışım"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Bileşen ="); + LSTR MSG_MIXER = _UxGT("Karıştırıcı"); + LSTR MSG_GRADIENT = _UxGT("Gradyan"); + LSTR MSG_FULL_GRADIENT = _UxGT("Tam Gradyan"); + LSTR MSG_TOGGLE_MIX = _UxGT("Karışım Geçişi"); + LSTR MSG_CYCLE_MIX = _UxGT("Döngü Karışımı"); + LSTR MSG_GRADIENT_MIX = _UxGT("Gradyan Karışımı"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Ters Gradyan"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktif V-tool"); + LSTR MSG_START_VTOOL = _UxGT("Başlat V-tool"); + LSTR MSG_END_VTOOL = _UxGT(" Bitir V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("V-tool Karışıö Yap"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools Resetlendi"); + LSTR MSG_START_Z = _UxGT("Başlat Z:"); + LSTR 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"); + LSTR MSG_GAMES = _UxGT("Oyunlar"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); // // Filament Değişim ekranları 4 satırlı ekranda 3 satıra kadar gösterilir @@ -550,47 +550,47 @@ namespace Language_tr { // #if LCD_HEIGHT >= 4 - 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_PARKING = _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.")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozul Isınıyor", "Lütfen Bekleyin...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Filamanın çıkması", "bekleniyor")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Filamanın yüklenmesi", "bekleniyor..")); - 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")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Baskıya devam etmek", "için Butona bas")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Park Ediliyor...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Filaman değişimi", "için başlama", "bekleniyor")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filamanı yükle", "ve devam için", "tuşa bas...")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nozulü Isıtmak için", "Butona Bas.")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Nozul Isınıyor", "Lütfen Bekleyin...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Filamanın çıkması", "bekleniyor")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Filamanın yüklenmesi", "bekleniyor..")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Filaman Temizlemesi", "için bekle")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Filaman Temizlemesi", "bitirmek için tıkla")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Baskının devam ", "etmesi için bekle")); #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Sürdürmek İçin Tıkla")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _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")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Isınıyor...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Çıkartılıyor...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Yüklüyor...")); - 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...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Sürdürmek İçin Tıkla")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Park Ediliyor...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Lütfen bekleyiniz...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Yükle ve bas")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Isıtmak için Tıkla")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Isınıyor...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Çıkartılıyor...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Yüklüyor...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Temizleniyor...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Bitirmek için Tıkla")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Sürdürülüyor...")); #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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Düzeltme"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Yumuşatma"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC Sürücüleri"); + LSTR MSG_TMC_CURRENT = _UxGT("Sürücü Akımı"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hibrit Eşiği"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensörsüz Sıfırlama"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Adım Modu"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Aktif"); + LSTR MSG_SERVICE_RESET = _UxGT("Resetle"); + LSTR MSG_SERVICE_IN = _UxGT(" içinde:"); + LSTR MSG_BACKLASH = _UxGT("Ters Tepki"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Düzeltme"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Yumuşatma"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 1e6b49da76..4cfe969307 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -33,883 +33,883 @@ namespace Language_uk { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Ukrainian"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Ukrainian"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Готовий."); - PROGMEM Language_Str MSG_YES = _UxGT("ТАК"); - PROGMEM Language_Str MSG_NO = _UxGT("НІ"); - PROGMEM Language_Str MSG_BACK = _UxGT("Назад"); - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Переривання..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена"); - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Готовий."); + LSTR MSG_YES = _UxGT("ТАК"); + LSTR MSG_NO = _UxGT("НІ"); + LSTR MSG_BACK = _UxGT("Назад"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Переривання..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); + LSTR MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Збій ініціалізації SD"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Збій ініціалізації SD"); #else - PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); + LSTR MSG_SD_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); #endif - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповнення виклику"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Програмні кінцевики"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповнення виклику"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Програмні кінцевики"); #else - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповн. виклику"); - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр.кінцевики"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповн. виклику"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр.кінцевики"); #endif - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Кінцевик"); // Max length 8 characters - PROGMEM Language_Str MSG_MAIN = _UxGT("Основне меню"); - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Інші налаштування"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Конфігурація"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Вимкнути двигуни"); - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Меню Debug"); - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Тест лінії прогр."); - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Авто паркування"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Паркування X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); - PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; - PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; - PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); - PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ітерація: %i"); - PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); - PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Точність досягнута"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Паркування XYZ"); - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Почати"); - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Наступна точка"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Завершено!"); - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Кінцевик"); // Max length 8 characters + LSTR MSG_MAIN = _UxGT("Основне меню"); + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Інші налаштування"); + LSTR MSG_CONFIGURATION = _UxGT("Конфігурація"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); + LSTR MSG_DISABLE_STEPPERS = _UxGT("Вимкнути двигуни"); + LSTR MSG_DEBUG_MENU = _UxGT("Меню Debug"); + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Тест лінії прогр."); + LSTR MSG_AUTO_HOME = _UxGT("Авто паркування"); + LSTR MSG_AUTO_HOME_X = _UxGT("Паркування X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); + LSTR MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; + LSTR MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; + LSTR MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); + LSTR MSG_ITERATION = _UxGT("G34 Ітерація: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Точність досягнута"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Паркування XYZ"); + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Почати"); + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Наступна точка"); + LSTR MSG_LEVEL_BED_DONE = _UxGT("Завершено!"); + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; #else - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); - PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); - PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); - PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); - PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; - PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; - PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; #endif - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Встановити нуль"); - PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); + LSTR MSG_SET_ORIGIN = _UxGT("Встановити нуль"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); + LSTR MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); #else - PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); + LSTR MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); #endif #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Нагрів ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрів ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" сопло"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" сопло ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" все"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" стіл"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" налашт"); + LSTR MSG_PREHEAT_1 = _UxGT("Нагрів ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("Нагрів ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" сопло"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" сопло ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" все"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" стіл"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Нагрів ") PREHEAT_1_LABEL _UxGT(" налашт"); - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Нагрів $"); - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Нагрів $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Нагрів $ сопло"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Нагрів $ сопло ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Нагрів $ все"); - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Нагрів $ стіл"); - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Нагрів $ налашт"); + LSTR MSG_PREHEAT_M = _UxGT("Нагрів $"); + LSTR MSG_PREHEAT_M_H = _UxGT("Нагрів $ ~"); + LSTR MSG_PREHEAT_M_END = _UxGT("Нагрів $ сопло"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Нагрів $ сопло ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Нагрів $ все"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Нагрів $ стіл"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Нагрів $ налашт"); #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрів свого"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Вимкнути нагрів"); + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Нагрів свого"); + LSTR MSG_COOLDOWN = _UxGT("Вимкнути нагрів"); - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Керування лазером"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Частота"); + LSTR MSG_LASER_MENU = _UxGT("Керування лазером"); + LSTR MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужність лазера"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкн. шпіндель"); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінделя"); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); + LSTR MSG_LASER_POWER = _UxGT("Потужність лазера"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Перемкн. шпіндель"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); + LSTR MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); + LSTR MSG_SPINDLE_POWER = _UxGT("Потужн. шпінделя"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); #else - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужн. лазера"); - PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемк. шпінд."); - PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемк. вакуум"); - PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкн. лазер"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потужн. шпінд."); - PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп., мс"); - PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкн. обдув"); + LSTR MSG_LASER_POWER = _UxGT("Потужн. лазера"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Перемк. шпінд."); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемк. вакуум"); + LSTR MSG_LASER_TOGGLE = _UxGT("Перемкн. лазер"); + LSTR MSG_SPINDLE_POWER = _UxGT("Потужн. шпінд."); + LSTR MSG_LASER_PULSE_MS = _UxGT("Тест. імп., мс"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкн. обдув"); #endif - PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); - PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); - PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Увімкнути живлення"); - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Вимкнути живлення"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Екструзія"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Втягування"); - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Рух по осям"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Вирівнювання столу"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Вирівняти кути"); + LSTR MSG_SWITCH_PS_ON = _UxGT("Увімкнути живлення"); + LSTR MSG_SWITCH_PS_OFF = _UxGT("Вимкнути живлення"); + LSTR MSG_EXTRUDE = _UxGT("Екструзія"); + LSTR MSG_RETRACT = _UxGT("Втягування"); + LSTR MSG_MOVE_AXIS = _UxGT("Рух по осям"); + LSTR MSG_BED_LEVELING = _UxGT("Вирівнювання столу"); + LSTR MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); + LSTR MSG_BED_TRAMMING = _UxGT("Вирівняти кути"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрацюв. зонду"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрацюв. зонду"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); #else - PROGMEM Language_Str MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрац.зонду"); - PROGMEM Language_Str MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирівн"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрац.зонду"); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирівн"); #endif - PROGMEM Language_Str MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хороші точки: "); - PROGMEM Language_Str MSG_BED_TRAMMING_LAST_Z = _UxGT("Остання Z: "); - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Наступний кут"); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хороші точки: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Остання Z: "); + LSTR MSG_NEXT_CORNER = _UxGT("Наступний кут"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); + LSTR MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); #else - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення Z"); + LSTR MSG_MESH_EDITOR = _UxGT("Зміщення Z"); #endif - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Редагувати сітку"); - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Редагув. зупинено"); - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("Точка сітки"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("Індекс X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Індекс Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Значення Z"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Власні команди"); + LSTR MSG_EDIT_MESH = _UxGT("Редагувати сітку"); + LSTR MSG_EDITING_STOPPED = _UxGT("Редагув. зупинено"); + LSTR MSG_PROBING_POINT = _UxGT("Точка сітки"); + LSTR MSG_MESH_X = _UxGT("Індекс X"); + LSTR MSG_MESH_Y = _UxGT("Індекс Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Значення Z"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Власні команди"); - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 тест зонду"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 точка"); - PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за межами"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Відхилення"); + LSTR MSG_M48_TEST = _UxGT("M48 тест зонду"); + LSTR MSG_M48_POINT = _UxGT("M48 точка"); + LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Зонд за межами"); + LSTR MSG_M48_DEVIATION = _UxGT("Відхилення"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Режим IDEX"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Зміщення сопел"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто паркування"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Дуплікація"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Дзеркальна копія"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Повний контроль"); - PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Дублюв. X-проміжок"); + LSTR MSG_IDEX_MENU = _UxGT("Режим IDEX"); + LSTR MSG_OFFSETS_MENU = _UxGT("Зміщення сопел"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Авто паркування"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Дуплікація"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Дзеркальна копія"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Повний контроль"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("Дублюв. X-проміжок"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("Друге сопло X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("Друге сопло Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("Друге сопло Z"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("Друге сопло X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("Друге сопло Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("Друге сопло Z"); - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Виконується G29"); - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Інструменти UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Налаштування UBL"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка нахилу"); + LSTR MSG_UBL_DOING_G29 = _UxGT("Виконується G29"); + LSTR MSG_UBL_TOOLS = _UxGT("Інструменти UBL"); + LSTR MSG_UBL_LEVEL_BED = _UxGT("Налаштування UBL"); + LSTR MSG_LCD_TILTING_MESH = _UxGT("Точка нахилу"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введення сітки"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розмістити шайбу і вимір."); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ручне введення сітки"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Розмістити шайбу і вимір."); #else - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введ. сітки"); - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розм. шайбу і вимір."); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ручне введ. сітки"); + LSTR MSG_UBL_BC_INSERT = _UxGT("Розм. шайбу і вимір."); #endif - PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); #else - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); + LSTR MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); #endif - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Рух до наступної"); - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активувати UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивувати UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Рух до наступної"); + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Активувати UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивувати UBL"); + LSTR MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); #else - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редаг. сітки"); - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою"); + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою"); + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редаг. сітки"); + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою"); #endif - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редагування сітки"); - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Сітка побудована"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Будувати сітку"); - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Буд. холодну сітку"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Встан.висоту сітки"); - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Висота"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Підтвердити сітку"); - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Підтвердити свою"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Редагування сітки"); + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Сітка побудована"); + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Будувати сітку"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Буд. холодну сітку"); + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Встан.висоту сітки"); + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Висота"); + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Підтвердити сітку"); + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Підтвердити свою"); - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрів столу"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрів сопла"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ручне грунтування"); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Грунтув. виконане"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 скасовано"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Вийти з G26"); - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Продовжити сітку"); - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Вирівнювання сітки"); - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точкове вирівн."); + LSTR MSG_G26_HEATING_BED = _UxGT("G26 нагрів столу"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрів сопла"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("Ручне грунтування"); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); + LSTR MSG_G26_PRIME_DONE = _UxGT("Грунтув. виконане"); + LSTR MSG_G26_CANCELED = _UxGT("G26 скасовано"); + LSTR MSG_G26_LEAVING = _UxGT("Вийти з G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Продовжити сітку"); + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Вирівнювання сітки"); + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точкове вирівн."); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнювання растру"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнювання растру"); #else - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнюв. растру"); + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнюв. растру"); #endif - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Вирівняти сітку"); - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Крайні точки"); - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Тип мапи сітки"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Вивести мапу сітки"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Вивести на хост"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вивести в CSV"); - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Вирівняти сітку"); + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Крайні точки"); + LSTR MSG_UBL_MAP_TYPE = _UxGT("Тип мапи сітки"); + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Вивести мапу сітки"); + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Вивести на хост"); + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вивести в CSV"); + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); + LSTR MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); #else - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); #endif - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ручне заповнення"); - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Розумне заповнення"); - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заповнити сітку"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Анулювати все"); - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Ручне заповнення"); + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Розумне заповнення"); + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Заповнити сітку"); + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Анулювати все"); + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); #else - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно найближчу"); + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно найближчу"); #endif - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Збереження сітки"); - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Слот пам'яті"); - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Завантажити сітку"); - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Зберегти сітку"); - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("Сітка %i завантажена"); - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("Сітка %i збережена"); - PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Немає носія"); - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Збій: збереж. UBL"); - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Збій: відновл. UBL"); - PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Зміщення Z: "); - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Зміщення Z зупинено"); - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL покроково"); - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Збудувати холодну"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Розумне заповн-я"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Затвердити сітку"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Точно налашт.все"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Затвердити сітку"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Точно налашт.все"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Зберегти сітку"); + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Збереження сітки"); + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Слот пам'яті"); + LSTR MSG_UBL_LOAD_MESH = _UxGT("Завантажити сітку"); + LSTR MSG_UBL_SAVE_MESH = _UxGT("Зберегти сітку"); + LSTR MSG_MESH_LOADED = _UxGT("Сітка %i завантажена"); + LSTR MSG_MESH_SAVED = _UxGT("Сітка %i збережена"); + LSTR MSG_UBL_NO_STORAGE = _UxGT("Немає носія"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Збій: збереж. UBL"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Збій: відновл. UBL"); + LSTR MSG_UBL_Z_OFFSET = _UxGT("Зміщення Z: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Зміщення Z зупинено"); + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL покроково"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Збудувати холодну"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Розумне заповн-я"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Затвердити сітку"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Точно налашт.все"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Затвердити сітку"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Точно налашт.все"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Зберегти сітку"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Керування світлом"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Підсвітка"); + LSTR MSG_LED_CONTROL = _UxGT("Керування світлом"); + LSTR MSG_LEDS = _UxGT("Підсвітка"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Передустановки світла"); + LSTR MSG_LED_PRESETS = _UxGT("Передустановки світла"); #else - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Передустан. світла"); + LSTR MSG_LED_PRESETS = _UxGT("Передустан. світла"); #endif - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Червоний"); - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Помаранчевий"); - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Жовтий"); - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Зелений"); - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Синій"); - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Індіго"); - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Фіолетовий"); - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Білий"); - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("За умовчанням"); - PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Канал ="); - PROGMEM Language_Str MSG_LEDS2 = _UxGT("Світло #2"); + LSTR MSG_SET_LEDS_RED = _UxGT("Червоний"); + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Помаранчевий"); + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Жовтий"); + LSTR MSG_SET_LEDS_GREEN = _UxGT("Зелений"); + LSTR MSG_SET_LEDS_BLUE = _UxGT("Синій"); + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Індіго"); + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Фіолетовий"); + LSTR MSG_SET_LEDS_WHITE = _UxGT("Білий"); + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("За умовчанням"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); + LSTR MSG_LEDS2 = _UxGT("Світло #2"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); #else - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); #endif - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яскравість"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Своє світло"); - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Рівень червоного"); - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Рівень зеленого"); - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Рівень синього"); - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Рівень білого"); - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Яскравість"); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Яскравість"); + LSTR MSG_CUSTOM_LEDS = _UxGT("Своє світло"); + LSTR MSG_INTENSITY_R = _UxGT("Рівень червоного"); + LSTR MSG_INTENSITY_G = _UxGT("Рівень зеленого"); + LSTR MSG_INTENSITY_B = _UxGT("Рівень синього"); + LSTR MSG_INTENSITY_W = _UxGT("Рівень білого"); + LSTR MSG_LED_BRIGHTNESS = _UxGT("Яскравість"); - PROGMEM Language_Str MSG_MOVING = _UxGT("Рух..."); - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Звільнити XY"); - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Рух по X"); - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Рух по Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Рух по Z"); - PROGMEM Language_Str MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; - PROGMEM Language_Str MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; - PROGMEM Language_Str MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Рух %sмм"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Рух 0.1мм"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Рух 1мм"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Рух 10мм"); - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Рух 100mm"); - PROGMEM Language_Str MSG_SPEED = _UxGT("Швидкість"); - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Столу"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Сопло ~"); - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Сопло запарковане"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); - PROGMEM Language_Str MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + LSTR MSG_MOVING = _UxGT("Рух..."); + LSTR MSG_FREE_XY = _UxGT("Звільнити XY"); + LSTR MSG_MOVE_X = _UxGT("Рух по X"); + LSTR MSG_MOVE_Y = _UxGT("Рух по Y"); + LSTR MSG_MOVE_Z = _UxGT("Рух по Z"); + LSTR MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; + LSTR MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; + LSTR MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; + LSTR MSG_MOVE_E = _UxGT("Екструдер"); + LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); + LSTR MSG_MOVE_N_MM = _UxGT("Рух %sмм"); + LSTR MSG_MOVE_01MM = _UxGT("Рух 0.1мм"); + LSTR MSG_MOVE_1MM = _UxGT("Рух 1мм"); + LSTR MSG_MOVE_10MM = _UxGT("Рух 10мм"); + LSTR MSG_MOVE_100MM = _UxGT("Рух 100mm"); + LSTR MSG_SPEED = _UxGT("Швидкість"); + LSTR MSG_BED_Z = _UxGT("Z Столу"); + LSTR MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; + LSTR MSG_NOZZLE_N = _UxGT("Сопло ~"); + LSTR MSG_NOZZLE_PARKED = _UxGT("Сопло запарковане"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); + LSTR MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; + LSTR MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк. охолодж."); + LSTR MSG_COOLER = _UxGT("Охолодження лазеру"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Перемк. охолодж."); #else - PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодж. лазеру"); - PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемк.охолод"); + LSTR MSG_COOLER = _UxGT("Охолодж. лазеру"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Перемк.охолод"); #endif - PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); - PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Швидк. вент."); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); + LSTR MSG_LASER = _UxGT("Лазер"); + LSTR MSG_FAN_SPEED = _UxGT("Швидк. вент."); + LSTR MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж.швидк.вент. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Дод. швидк. вент. ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Збереж.швидк.вент. ~"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Дод. швидк. вент. ~"); #else - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.вент. ~"); + LSTR MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.вент. ~"); #endif - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Дод. швидк. вент."); - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холості оберти"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Авто-режим"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Період простою"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Потік"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Потік ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Налаштування"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С мін"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Автотемпер."); - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Увім"); - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Вимк"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Дод. швидк. вент."); + LSTR MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холості оберти"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Авто-режим"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Період простою"); + LSTR MSG_FLOW = _UxGT("Потік"); + LSTR MSG_FLOW_N = _UxGT("Потік ~"); + LSTR MSG_CONTROL = _UxGT("Налаштування"); + LSTR MSG_MIN = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С мін"); + LSTR MSG_MAX = " " LCD_STR_THERMOMETER ", " LCD_STR_DEGREE _UxGT("С макс"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Фактор"); + LSTR MSG_AUTOTEMP = _UxGT("Автотемпер."); + LSTR MSG_LCD_ON = _UxGT("Увім"); + LSTR MSG_LCD_OFF = _UxGT("Вимк"); - PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Автопідбір PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Автопідбір PID *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Підбір PID виконано"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Збій автопідбору. Поганий екструдер."); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Збій автопідбору. Температура завищена."); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Збій автопідбору! Вичерпан час."); + LSTR MSG_PID_AUTOTUNE = _UxGT("Автопідбір PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Автопідбір PID *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Підбір PID виконано"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Збій автопідбору. Поганий екструдер."); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Збій автопідбору. Температура завищена."); + LSTR MSG_PID_TIMEOUT = _UxGT("Збій автопідбору! Вичерпан час."); - PROGMEM Language_Str MSG_SELECT = _UxGT("Вибрати"); - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Вибрати *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Прискорорення"); - PROGMEM Language_Str MSG_JERK = _UxGT("Ривок"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); - PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); - PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-ривок"); + LSTR MSG_SELECT = _UxGT("Вибрати"); + LSTR MSG_SELECT_E = _UxGT("Вибрати *"); + LSTR MSG_ACC = _UxGT("Прискорорення"); + LSTR MSG_JERK = _UxGT("Ривок"); + LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); + LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); + LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); + LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); + LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); + LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); + LSTR MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); #else - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Відхил.вузла"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхил.вузла"); #endif - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Швидкість, мм/с"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Швидк.макс *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк. мін"); + LSTR MSG_VELOCITY = _UxGT("Швидкість, мм/с"); + LSTR MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; + LSTR MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Швидк.макс *"); + LSTR MSG_VMIN = _UxGT("Швидк. мін"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщення мін"); + LSTR MSG_VTRAV_MIN = _UxGT("Переміщення мін"); #else - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); + LSTR MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); #endif - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Прискорення, мм/с2"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Приск.макс *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Приск.втягув."); - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Приск.переміщ."); - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мін."); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Кроків на мм"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E кроків/мм"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* кроків/мм"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); - PROGMEM Language_Str MSG_MOTION = _UxGT("Рух"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Пруток"); - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E, мм") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E обмеж.,мм") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E обмеж. *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Діам. прутка"); - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Діам. прутка *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Вивантаж., мм"); - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Завантаж., мм"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Kоеф. просув."); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Kоеф. просув. *"); - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Контраст екрану"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Зберегти в EEPROM"); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Зчитати з EEPROM"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базові параметри"); + LSTR MSG_ACCELERATION = _UxGT("Прискорення, мм/с2"); + LSTR MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; + LSTR MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Приск.макс *"); + LSTR MSG_A_RETRACT = _UxGT("Приск.втягув."); + LSTR MSG_A_TRAVEL = _UxGT("Приск.переміщ."); + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мін."); + LSTR MSG_STEPS_PER_MM = _UxGT("Кроків на мм"); + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); + LSTR MSG_E_STEPS = _UxGT("E кроків/мм"); + LSTR MSG_EN_STEPS = _UxGT("* кроків/мм"); + LSTR MSG_TEMPERATURE = _UxGT("Температура"); + LSTR MSG_MOTION = _UxGT("Рух"); + LSTR MSG_FILAMENT = _UxGT("Пруток"); + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E, мм") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E обмеж.,мм") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E обмеж. *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("Діам. прутка"); + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Діам. прутка *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Вивантаж., мм"); + LSTR MSG_FILAMENT_LOAD = _UxGT("Завантаж., мм"); + LSTR MSG_ADVANCE_K = _UxGT("Kоеф. просув."); + LSTR MSG_ADVANCE_K_E = _UxGT("Kоеф. просув. *"); + LSTR MSG_CONTRAST = _UxGT("Контраст екрану"); + LSTR MSG_STORE_EEPROM = _UxGT("Зберегти в EEPROM"); + LSTR MSG_LOAD_EEPROM = _UxGT("Зчитати з EEPROM"); + LSTR MSG_RESTORE_DEFAULTS = _UxGT("На базові параметри"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Ініціалізація EEPROM"); + LSTR MSG_INIT_EEPROM = _UxGT("Ініціалізація EEPROM"); #else - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Ініціаліз. EEPROM"); + LSTR MSG_INIT_EEPROM = _UxGT("Ініціаліз. EEPROM"); #endif - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Збій EEPROM: CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Збій EEPROM: індекс"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Збій EEPROM: версія"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметри збережені"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Оновити SD-картку"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Зкинути принтер"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Головний екран"); - PROGMEM Language_Str MSG_PREPARE = _UxGT("Підготувати"); - PROGMEM Language_Str MSG_TUNE = _UxGT("Підлаштування"); - PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Монітор живлення"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("Струм"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Напруга"); - PROGMEM Language_Str MSG_POWER = _UxGT("Потужність"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("Почати друк"); + LSTR MSG_ERR_EEPROM_CRC = _UxGT("Збій EEPROM: CRC"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Збій EEPROM: індекс"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Збій EEPROM: версія"); + LSTR MSG_SETTINGS_STORED = _UxGT("Параметри збережені"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Оновити SD-картку"); + LSTR MSG_RESET_PRINTER = _UxGT("Зкинути принтер"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); + LSTR MSG_INFO_SCREEN = _UxGT("Головний екран"); + LSTR MSG_PREPARE = _UxGT("Підготувати"); + LSTR MSG_TUNE = _UxGT("Підлаштування"); + LSTR MSG_POWER_MONITOR = _UxGT("Монітор живлення"); + LSTR MSG_CURRENT = _UxGT("Струм"); + LSTR MSG_VOLTAGE = _UxGT("Напруга"); + LSTR MSG_POWER = _UxGT("Потужність"); + LSTR MSG_START_PRINT = _UxGT("Почати друк"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Далі"); //short text for buttons - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Ініц-я"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Зупинка"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Друк"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Зкинути"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ігнорув."); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Відміна"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Готово"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Назад"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Продовжити"); - PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Пропустити"); + LSTR MSG_BUTTON_NEXT = _UxGT("Далі"); //short text for buttons + LSTR MSG_BUTTON_INIT = _UxGT("Ініц-я"); + LSTR MSG_BUTTON_STOP = _UxGT("Зупинка"); + LSTR MSG_BUTTON_PRINT = _UxGT("Друк"); + LSTR MSG_BUTTON_RESET = _UxGT("Зкинути"); + LSTR MSG_BUTTON_IGNORE = _UxGT("Ігнорув."); + LSTR MSG_BUTTON_CANCEL = _UxGT("Відміна"); + LSTR MSG_BUTTON_DONE = _UxGT("Готово"); + LSTR MSG_BUTTON_BACK = _UxGT("Назад"); + LSTR MSG_BUTTON_PROCEED = _UxGT("Продовжити"); + LSTR MSG_BUTTON_SKIP = _UxGT("Пропустити"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("Призупинення..."); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Призупинити друк"); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Відновити друк"); - PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Старт з хосту"); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Скасувати друк"); - PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); // needs translation - PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Друк об'єкта"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Завершити об'єкт"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Завершити об'єкт ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Віднов. після збою"); - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Друкувати з SD"); - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD-картки немає"); - PROGMEM Language_Str MSG_DWELL = _UxGT("Сон..."); - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Продовжити..."); - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Друк призупинено"); - PROGMEM Language_Str MSG_PRINTING = _UxGT("Друк..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Друк скасовано"); - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Друк завершено"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Немає руху."); - PROGMEM Language_Str MSG_KILLED = _UxGT("ПЕРЕРВАНО. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ЗУПИНЕНО. "); + LSTR MSG_PAUSING = _UxGT("Призупинення..."); + LSTR MSG_PAUSE_PRINT = _UxGT("Призупинити друк"); + LSTR MSG_RESUME_PRINT = _UxGT("Відновити друк"); + LSTR MSG_HOST_START_PRINT = _UxGT("Старт з хосту"); + LSTR MSG_STOP_PRINT = _UxGT("Скасувати друк"); + LSTR MSG_END_LOOPS = _UxGT("End Repeat Loops"); // needs translation + LSTR MSG_PRINTING_OBJECT = _UxGT("Друк об'єкта"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Завершити об'єкт"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершити об'єкт ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Віднов. після збою"); + LSTR MSG_MEDIA_MENU = _UxGT("Друкувати з SD"); + LSTR MSG_NO_MEDIA = _UxGT("SD-картки немає"); + LSTR MSG_DWELL = _UxGT("Сон..."); + LSTR MSG_USERWAIT = _UxGT("Продовжити..."); + LSTR MSG_PRINT_PAUSED = _UxGT("Друк призупинено"); + LSTR MSG_PRINTING = _UxGT("Друк..."); + LSTR MSG_PRINT_ABORTED = _UxGT("Друк скасовано"); + LSTR MSG_PRINT_DONE = _UxGT("Друк завершено"); + LSTR MSG_NO_MOVE = _UxGT("Немає руху."); + LSTR MSG_KILLED = _UxGT("ПЕРЕРВАНО. "); + LSTR MSG_STOPPED = _UxGT("ЗУПИНЕНО. "); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягування, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втягув.,мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Повернення, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Поверн.зміни, мм"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягування"); + LSTR MSG_CONTROL_RETRACT = _UxGT("Втягування, мм"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втягув.,мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Повернення, мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Поверн.зміни, мм"); + LSTR MSG_AUTORETRACT = _UxGT("Автовтягування"); #else - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягув., мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втяг.мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Поверн., мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Повер.зміни,мм"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягув."); + LSTR MSG_CONTROL_RETRACT = _UxGT("Втягув., мм"); + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втяг.мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Поверн., мм"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Повер.зміни,мм"); + LSTR MSG_AUTORETRACT = _UxGT("Автовтягув."); #endif - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Втягування V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Підскок, мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Повернення V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Поверн.зміни V"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Змінити довжини"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Змінити додатково"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистити довжину"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Зміна сопла"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Підняти по Z"); + LSTR MSG_CONTROL_RETRACTF = _UxGT("Втягування V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Підскок, мм"); + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Повернення V"); + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Поверн.зміни V"); + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Змінити довжини"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Змінити додатково"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистити довжину"); + LSTR MSG_TOOL_CHANGE = _UxGT("Зміна сопла"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Підняти по Z"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Початк.швидкість"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Швидкість втягув."); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Початк.швидкість"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Швидкість втягув."); #else - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Початк.швидк."); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Швидк.втягув."); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Початк.швидк."); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Швидк.втягув."); #endif - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Паркувати голову"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Відновити швидкість"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Паркувати голову"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Відновити швидкість"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вентилятора"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вентилятора"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вентилятора"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вентилятора"); #else - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вент."); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вент."); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вент."); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вент."); #endif - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Авто Увімк."); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Авто Вимкн."); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Заміна інструменту"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Авто заміна"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Останній екструдер"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Заміна на *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Заміна прутка"); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Заміна прутка *"); - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Подати пруток"); - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Подати пруток *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Видалити пруток"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Видалити пруток *"); - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Видалити все"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Вставити SD-картку"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Заміна SD-картки"); - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Видаліть SD-картку"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z-Зонд поза столом"); - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Фактор нахилу"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Само-тест"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Зкинути зонд"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Підняти зонд"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Опустити зонд"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Режим SW"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Режим 5V"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Режим OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Режим збереження"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Встановити BLT на 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Встановити BLT на OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Звітувати злив"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("НЕБЕЗПЕКА: Неправильні параметри приводять до пошкоджень! Продовжити?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("Z-Зонд TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Ініц. TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Тест Z-зміщення"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Зберегти"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Установити TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Установити Z-зонд"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Завантажити Z-зонд"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Спочатку дім %s%s%s"); - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Зміщення зонду"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Зміщення по X"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Зміщення по Y"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Зміщення по Z"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Рухати сопло до столу"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); - PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; - PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; - PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; - PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("ЗАВИЩЕНА Т") LCD_STR_DEGREE; - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Авто Увімк."); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Авто Вимкн."); + LSTR MSG_TOOL_MIGRATION = _UxGT("Заміна інструменту"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Авто заміна"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("Останній екструдер"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Заміна на *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("Заміна прутка"); + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Заміна прутка *"); + LSTR MSG_FILAMENTLOAD = _UxGT("Подати пруток"); + LSTR MSG_FILAMENTLOAD_E = _UxGT("Подати пруток *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Видалити пруток"); + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Видалити пруток *"); + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Видалити все"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Вставити SD-картку"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Заміна SD-картки"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Видаліть SD-картку"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z-Зонд поза столом"); + LSTR MSG_SKEW_FACTOR = _UxGT("Фактор нахилу"); + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Само-тест"); + LSTR MSG_BLTOUCH_RESET = _UxGT("Зкинути зонд"); + LSTR MSG_BLTOUCH_STOW = _UxGT("Підняти зонд"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Опустити зонд"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Режим SW"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Режим 5V"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Режим OD"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Режим збереження"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Встановити BLT на 5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Встановити BLT на OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Звітувати злив"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("НЕБЕЗПЕКА: Неправильні параметри приводять до пошкоджень! Продовжити?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("Z-Зонд TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("Ініц. TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Тест Z-зміщення"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("Зберегти"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Установити TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("Установити Z-зонд"); + LSTR MSG_MANUAL_STOW = _UxGT("Завантажити Z-зонд"); + LSTR MSG_HOME_FIRST = _UxGT("Спочатку дім %s%s%s"); + LSTR MSG_ZPROBE_OFFSETS = _UxGT("Зміщення зонду"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("Зміщення по X"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("Зміщення по Y"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Зміщення по Z"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Рухати сопло до столу"); + LSTR MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); + LSTR MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; + LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("ЗАВИЩЕНА Т") LCD_STR_DEGREE; + LSTR MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); + LSTR MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); #else - PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); + LSTR MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); #endif - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т") LCD_STR_DEGREE; - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; - PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("г"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("х"); // One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрівання..."); - PROGMEM Language_Str MSG_COOLING = _UxGT("Охолодження..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрів столу..."); - PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); + LSTR MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т") LCD_STR_DEGREE; + LSTR MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; + LSTR MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); + LSTR MSG_PLEASE_RESET = _UxGT("Перезавантажте"); + LSTR MSG_SHORT_DAY = _UxGT("д"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("г"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("х"); // One character only + LSTR MSG_HEATING = _UxGT("Нагрівання..."); + LSTR MSG_COOLING = _UxGT("Охолодження..."); + LSTR MSG_BED_HEATING = _UxGT("Нагрів столу..."); + LSTR MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодження столу..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодження лазеру..."); + LSTR MSG_BED_COOLING = _UxGT("Охолодження столу..."); + LSTR MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); + LSTR MSG_LASER_COOLING = _UxGT("Охолодження лазеру..."); #else - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодж. столу..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодж. зонду..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодж. камери..."); - PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодж. лазеру..."); + LSTR MSG_BED_COOLING = _UxGT("Охолодж. столу..."); + LSTR MSG_PROBE_COOLING = _UxGT("Охолодж. зонду..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("Охолодж. камери..."); + LSTR MSG_LASER_COOLING = _UxGT("Охолодж. лазеру..."); #endif - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калібрувати X"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калібрувати Y"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калібрувати Z"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калібр. центр"); - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Параметри Delta"); - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Автокалібрування"); - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Встан. Висоту Delta"); - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z-зміщення зонду"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Діагональ стрижня"); - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Висота"); - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радіус"); + LSTR MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Калібрувати X"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Калібрувати Y"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Калібрувати Z"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Калібр. центр"); + LSTR MSG_DELTA_SETTINGS = _UxGT("Параметри Delta"); + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Автокалібрування"); + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Встан. Висоту Delta"); + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z-зміщення зонду"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Діагональ стрижня"); + LSTR MSG_DELTA_HEIGHT = _UxGT("Висота"); + LSTR MSG_DELTA_RADIUS = _UxGT("Радіус"); - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Про принтер"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Дані принтера"); + LSTR MSG_INFO_MENU = _UxGT("Про принтер"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Дані принтера"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точкове вирівнювання"); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівнювання"); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівнювання"); + LSTR MSG_3POINT_LEVELING = _UxGT("3-точкове вирівнювання"); + LSTR MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівнювання"); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівнювання"); #else - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("3-точкове вирівн."); - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівн."); - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівн."); + LSTR MSG_3POINT_LEVELING = _UxGT("3-точкове вирівн."); + LSTR MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівн."); + LSTR MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівн."); #endif - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL"); - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); + LSTR MSG_UBL_LEVELING = _UxGT("UBL"); + LSTR MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); + LSTR MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); #else - PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування виконано"); + LSTR MSG_MESH_DONE = _UxGT("Зондування виконано"); #endif - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Про плату"); - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Термістори"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Екструдери"); - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Бод"); - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Протокол"); + LSTR MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); + LSTR MSG_INFO_BOARD_MENU = _UxGT("Про плату"); + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Термістори"); + LSTR MSG_INFO_EXTRUDERS = _UxGT("Екструдери"); + LSTR MSG_INFO_BAUDRATE = _UxGT("Бод"); + LSTR MSG_INFO_PROTOCOL = _UxGT("Протокол"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Увімк"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Час простою хотенду"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Увімк"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Час простою хотенду"); #else - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Контр.витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Контр.витіку ") LCD_STR_THERMOMETER _UxGT(" Увімк"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Час прост. хот-у"); + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контр.витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контр.витіку ") LCD_STR_THERMOMETER _UxGT(" Увімк"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Час прост. хот-у"); #endif - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Підсвітка"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яскравість світла"); - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("НЕ ТОЙ ПРИНТЕР"); + LSTR MSG_CASE_LIGHT = _UxGT("Підсвітка"); + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яскравість світла"); + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("НЕ ТОЙ ПРИНТЕР"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Екструдовано"); + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Екструдовано"); #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Кількість друків"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Весь час друку"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Найдовший час"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Кількість друків"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Весь час друку"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Найдовший час"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Друків"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Загалом"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Найдовше"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Друків"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Загалом"); + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Найдовше"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Мін. ") LCD_STR_THERMOMETER; - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Блок жив-ня"); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Сила мотору"); - PROGMEM Language_Str MSG_DAC_PERCENT_A = _UxGT("Драйвер ") LCD_STR_A _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_B = _UxGT("Драйвер ") LCD_STR_B _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = _UxGT("Драйвер ") LCD_STR_C _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") LCD_STR_I _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") LCD_STR_J _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") LCD_STR_K _UxGT(", %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМІНА ПРУТКА"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("ЗУПИНКА ДРУКУ"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ЗАВАНТАЖИТИ ПРУТОК"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("ВИВАНТАЖИТИ ПРУТОК"); + LSTR MSG_INFO_MIN_TEMP = _UxGT("Мін. ") LCD_STR_THERMOMETER; + LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; + LSTR MSG_INFO_PSU = _UxGT("Блок жив-ня"); + LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила мотору"); + LSTR MSG_DAC_PERCENT_A = _UxGT("Драйвер ") LCD_STR_A _UxGT(", %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Драйвер ") LCD_STR_B _UxGT(", %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Драйвер ") LCD_STR_C _UxGT(", %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Драйвер ") LCD_STR_I _UxGT(", %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Драйвер ") LCD_STR_J _UxGT(", %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Драйвер ") LCD_STR_K _UxGT(", %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); + LSTR MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("ЗАМІНА ПРУТКА"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("ЗУПИНКА ДРУКУ"); + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ЗАВАНТАЖИТИ ПРУТОК"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("ВИВАНТАЖИТИ ПРУТОК"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМЕТРИ ПРОДОВЖЕННЯ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМЕТРИ ПРОДОВЖЕННЯ:"); #else - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМ.ПРОДОВЖЕННЯ:"); + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМ.ПРОДОВЖЕННЯ:"); #endif - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Видавити ще"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Відновити друк"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопло: "); + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Видавити ще"); + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Відновити друк"); + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопло: "); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Датчик закінчення прутка"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Відстань закінч.,мм"); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик закінчення прутка"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Відстань закінч.,мм"); #else - PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Датчик закінч.прутка"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("До закінч.,мм"); + LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик закінч.прутка"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("До закінч.,мм"); #endif - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Помилка паркування"); - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Помилка зондування"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Помилка паркування"); + LSTR MSG_LCD_PROBING_FAILED = _UxGT("Помилка зондування"); - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ОБЕРІТЬ ПРУТОК"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Онови прошивку MMU!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU потребує уваги"); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU Продовжити"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU Продовження..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Завантажити"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU Завантажити все"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ОБЕРІТЬ ПРУТОК"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Онови прошивку MMU!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU потребує уваги"); + LSTR MSG_MMU2_RESUME = _UxGT("MMU Продовжити"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU Продовження..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Завантажити"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Завантажити все"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); #else - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); #endif - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Звільнити"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Звільнити ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Вивантажити"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаж. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Викидання прутка..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Все"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Пруток ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Звільнити"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Звільнити ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Вивантажити"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаж. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Викидання прутка..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження..."); + LSTR MSG_MMU2_ALL = _UxGT("Все"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("Пруток ~"); + LSTR MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_MIX = _UxGT("Змішування"); + LSTR MSG_MIX = _UxGT("Змішування"); #else - PROGMEM Language_Str MSG_MIX = _UxGT("Змішув."); + LSTR MSG_MIX = _UxGT("Змішув."); #endif - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("Змішувач"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градієнт"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); + LSTR MSG_MIXER = _UxGT("Змішувач"); + LSTR MSG_GRADIENT = _UxGT("Градієнт"); + LSTR MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); + LSTR MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); #else - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); + LSTR MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); #endif - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Циклічне змішування"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); + LSTR MSG_CYCLE_MIX = _UxGT("Циклічне змішування"); + LSTR MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Активація В-інструменту"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструменту"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Активація В-інструменту"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструменту"); + LSTR MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); #else - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив. В-інструм."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм."); + LSTR MSG_ACTIVE_VTOOL = _UxGT("Актив. В-інструм."); + LSTR MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм"); + LSTR MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм."); #endif - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Початок В-інструменту"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Початок Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" Кінець Z:"); + LSTR MSG_START_VTOOL = _UxGT("Початок В-інструменту"); + LSTR MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); + LSTR MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); + LSTR MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); + LSTR MSG_START_Z = _UxGT("Початок Z:"); + LSTR MSG_END_Z = _UxGT(" Кінець Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("Ігри"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Цеглини"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("Вторгнення"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("Zм!йк@"); - PROGMEM Language_Str MSG_MAZE = _UxGT("Лабіринт"); + LSTR MSG_GAMES = _UxGT("Ігри"); + LSTR MSG_BRICKOUT = _UxGT("Цеглини"); + LSTR MSG_INVADERS = _UxGT("Вторгнення"); + LSTR MSG_SNAKE = _UxGT("Zм!йк@"); + LSTR MSG_MAZE = _UxGT("Лабіринт"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Погана сторінка"); + LSTR MSG_BAD_PAGE = _UxGT("Погана сторінка"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидкість стор."); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Погана швидкість стор."); #else - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Погана швидк. стор."); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("Погана швидк. стор."); #endif - PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Редагувати пароль"); - PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Потрібен логін"); - PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Параметри паролю"); - PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Введіть цифру"); - PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Змінити пароль"); - PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Видалити пароль"); - PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Пароль: "); - PROGMEM Language_Str MSG_START_OVER = _UxGT("Старт через"); - PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); - PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Редагувати пароль"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("Потрібен логін"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Параметри паролю"); + LSTR MSG_ENTER_DIGIT = _UxGT("Введіть цифру"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Змінити пароль"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Видалити пароль"); + LSTR MSG_PASSWORD_SET = _UxGT("Пароль: "); + LSTR MSG_START_OVER = _UxGT("Старт через"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Натисніть кнопку", "для продовження", "друку")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Зачекайте", "на початок", "заміни прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставте пруток", "та натисніть", "для продовження")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Натисніть кнопку", "для нагріву сопла")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Сопло нагрівається", "зачекайте...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Зачекайте", "на вивід прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Зачекайте", "на ввід прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Дочекайтесь", "очищення прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Натисніть кнопку", "для завершення", "очищення прутка")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Зачекайте", "на відновлення", "друку")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Натисніть кнопку", "для продовження", "друку")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Зачекайте", "на початок", "заміни прутка")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Вставте пруток", "та натисніть", "для продовження")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Натисніть кнопку", "для нагріву сопла")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Сопло нагрівається", "зачекайте...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Зачекайте", "на вивід прутка")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Зачекайте", "на ввід прутка")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Дочекайтесь", "очищення прутка")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("Натисніть кнопку", "для завершення", "очищення прутка")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Зачекайте", "на відновлення", "друку")); #else // Up to 2 lines allowed - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Продовжити друк")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Зачекайте...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Вставте і натисніть")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Нагріти сопло")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Нагрів сопла...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Вивід прутка...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Ввід прутка...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Очищення прутка...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Завершити очищення")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Поновлення друку...")); + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Продовжити друк")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Зачекайте...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Вставте і натисніть")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Нагріти сопло")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Нагрів сопла...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Вивід прутка...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Ввід прутка...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Очищення прутка...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Завершити очищення")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Поновлення друку...")); #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Драйвери TMC"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Струм драйвера"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Гібридний поріг"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Дім без кінцевиків"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Режим мікрокроку"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим увімк."); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Зкидання"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" в:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("Люфт"); - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Виправлення"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Зглажування"); + LSTR MSG_TMC_DRIVERS = _UxGT("Драйвери TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Струм драйвера"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Гібридний поріг"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Дім без кінцевиків"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Режим мікрокроку"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим увімк."); + LSTR MSG_SERVICE_RESET = _UxGT("Зкидання"); + LSTR MSG_SERVICE_IN = _UxGT(" в:"); + LSTR MSG_BACKLASH = _UxGT("Люфт"); + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Виправлення"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Зглажування"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Рівень вісі X"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Авто калібрування"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Рівень вісі X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Авто калібрування"); #if ENABLED(TOUCH_UI_FTDI_EVE) - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Час простою збіг, температура впала. Натисніть ОК, щоби знову нагріти та продовжити"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Час простою збіг, температура впала. Натисніть ОК, щоби знову нагріти та продовжити"); #else - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Час нагрівача збіг"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Час нагрівача збіг"); #endif - PROGMEM Language_Str MSG_REHEAT = _UxGT("Поновити нагрів"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("Нагрівання..."); + LSTR MSG_REHEAT = _UxGT("Поновити нагрів"); + LSTR MSG_REHEATING = _UxGT("Нагрівання..."); - PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Майстер Z-зонда"); + LSTR MSG_PROBE_WIZARD = _UxGT("Майстер Z-зонда"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув. контрольної точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондування"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув. контрольної точки Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондування"); #else - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув.контр.точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондув."); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув.контр.точки Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондув."); #endif - PROGMEM Language_Str MSG_SOUND = _UxGT("Звук"); + LSTR MSG_SOUND = _UxGT("Звук"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Верхній лівий"); - PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Нижній лівий"); - PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Верхній правий"); - PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижній правий"); - PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калібрування успішне"); - PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Збій калібрування"); + LSTR MSG_TOP_LEFT = _UxGT("Верхній лівий"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Нижній лівий"); + LSTR MSG_TOP_RIGHT = _UxGT("Верхній правий"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Нижній правий"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Калібрування успішне"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Збій калібрування"); - PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); - PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Картка"); - PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); + LSTR MSG_SD_CARD = _UxGT("SD Картка"); + LSTR MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 9ee93a56bb..9a4ef464b5 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -30,427 +30,427 @@ namespace Language_vi { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Vietnamese"); + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Vietnamese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" Sẵn sàng."); // Ready - PROGMEM Language_Str MSG_BACK = _UxGT("Trở lại"); // Back - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Đang hủy bỏ..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Phương tiện được cắm vào"); // Media inserted - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Phương tiện được rút ra"); - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Chờ đợi phương tiện"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Lỗi đọc phương tiện"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB được rút ra"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB khởi thất bại"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Công tắc"); // Endstops - công tắc hành trình - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Công tắc mềm"); // soft Endstops - PROGMEM Language_Str MSG_MAIN = _UxGT("Chính"); // Main - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Thiết lập cấp cao"); // Advanced Settings - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Cấu hình"); // Configuration - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("Khởi chạy tự động"); // Autostart - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Tắt động cơ bước"); // Disable steppers - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu gỡ lỗi"); // Debug Menu - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Kiểm tra tiến độ"); // Progress bar test - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Về nhà tự động"); // Auto home - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Về nhà X"); // home X - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Về nhà Y"); // home Y - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Về nhà Z"); // home Z - PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Chỉnh canh Z tự động"); - PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Đang về nhà XYZ"); // Homing XYZ - PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Nhấn để bắt đầu"); // Click to Begin - PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Điểm tiếp theo"); // Next Point - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("San lấp được hoàn thành"); // Leveling Done! - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Chiều cao mờ dần"); // Fade Height - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Đặt bù đắp nhà"); // Set home offsets - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Bù đắp được áp dụng"); // Offsets applied - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Đặt nguồn gốc"); // Set origin + LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Sẵn sàng."); // Ready + LSTR MSG_BACK = _UxGT("Trở lại"); // Back + LSTR MSG_MEDIA_ABORTING = _UxGT("Đang hủy bỏ..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("Phương tiện được cắm vào"); // Media inserted + LSTR MSG_MEDIA_REMOVED = _UxGT("Phương tiện được rút ra"); + LSTR MSG_MEDIA_WAITING = _UxGT("Chờ đợi phương tiện"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Lỗi đọc phương tiện"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB được rút ra"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB khởi thất bại"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Công tắc"); // Endstops - công tắc hành trình + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Công tắc mềm"); // soft Endstops + LSTR MSG_MAIN = _UxGT("Chính"); // Main + LSTR MSG_ADVANCED_SETTINGS = _UxGT("Thiết lập cấp cao"); // Advanced Settings + LSTR MSG_CONFIGURATION = _UxGT("Cấu hình"); // Configuration + LSTR MSG_RUN_AUTO_FILES = _UxGT("Khởi chạy tự động"); // Autostart + LSTR MSG_DISABLE_STEPPERS = _UxGT("Tắt động cơ bước"); // Disable steppers + LSTR MSG_DEBUG_MENU = _UxGT("Menu gỡ lỗi"); // Debug Menu + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Kiểm tra tiến độ"); // Progress bar test + LSTR MSG_AUTO_HOME = _UxGT("Về nhà tự động"); // Auto home + LSTR MSG_AUTO_HOME_X = _UxGT("Về nhà X"); // home X + LSTR MSG_AUTO_HOME_Y = _UxGT("Về nhà Y"); // home Y + LSTR MSG_AUTO_HOME_Z = _UxGT("Về nhà Z"); // home Z + LSTR MSG_AUTO_Z_ALIGN = _UxGT("Chỉnh canh Z tự động"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("Đang về nhà XYZ"); // Homing XYZ + LSTR MSG_LEVEL_BED_WAITING = _UxGT("Nhấn để bắt đầu"); // Click to Begin + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Điểm tiếp theo"); // Next Point + LSTR MSG_LEVEL_BED_DONE = _UxGT("San lấp được hoàn thành"); // Leveling Done! + LSTR MSG_Z_FADE_HEIGHT = _UxGT("Chiều cao mờ dần"); // Fade Height + LSTR MSG_SET_HOME_OFFSETS = _UxGT("Đặt bù đắp nhà"); // Set home offsets + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Bù đắp được áp dụng"); // Offsets applied + LSTR MSG_SET_ORIGIN = _UxGT("Đặt nguồn gốc"); // Set origin #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước"); // Preheat - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước ~"); // Preheat - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Đầu"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Đầu ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Tất cả"); // all - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Bàn"); // bed -- using vietnamese term for 'table' instead - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Cấu hình"); // conf + LSTR MSG_PREHEAT_1 = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước"); // Preheat + LSTR MSG_PREHEAT_1_H = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" trước ~"); // Preheat + LSTR MSG_PREHEAT_1_END = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Đầu"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Đầu ~"); + LSTR MSG_PREHEAT_1_ALL = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Tất cả"); // all + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Bàn"); // bed -- using vietnamese term for 'table' instead + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Làm nóng ") PREHEAT_1_LABEL _UxGT(" Cấu hình"); // conf - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Làm nóng $ trước"); // Preheat - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Làm nóng $ trước ~"); // Preheat - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Làm nóng $ Đầu"); - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Làm nóng $ Đầu ~"); - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Làm nóng $ Tất cả"); // all - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Làm nóng $ Bàn"); // bed -- using vietnamese term for 'table' instead - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("Làm nóng $ Cấu hình"); // conf + LSTR MSG_PREHEAT_M = _UxGT("Làm nóng $ trước"); // Preheat + LSTR MSG_PREHEAT_M_H = _UxGT("Làm nóng $ trước ~"); // Preheat + LSTR MSG_PREHEAT_M_END = _UxGT("Làm nóng $ Đầu"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Làm nóng $ Đầu ~"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Làm nóng $ Tất cả"); // all + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Làm nóng $ Bàn"); // bed -- using vietnamese term for 'table' instead + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Làm nóng $ Cấu hình"); // conf #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Sự nóng trước tự chọn"); // Preheat Custom - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Nguội xuống"); // Cooldown - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bật nguồn"); // Switch power on - PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Tắt nguồn"); // Switch power off - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Ép đùn"); // Extrude - PROGMEM Language_Str MSG_RETRACT = _UxGT("Rút lại"); // Retract - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Di chuyển trục"); // Move axis - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("San Lấp Bàn"); // Bed Leveling - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Làm bằng mặt bàn"); // Level bed - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("Làm bằng góc bàn"); // Level corners - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Góc tiếp theo"); // Next corner - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Chỉnh lưới đã dừng"); // Mesh Editing Stopped - PROGMEM Language_Str MSG_MESH_X = _UxGT("Mục lục X"); // Index X - PROGMEM Language_Str MSG_MESH_Y = _UxGT("Mục lục Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Giá trị Z"); // Z Value - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Các lệnh tự chọn"); // Custom Commands - PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Đang chạy G29"); // Doing G29 - PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Công cụ UBL"); // UBL tools - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("San Lấp Bàn Thống Nhất (UBL)"); // Unified Bed Leveling - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("chế độ IDEX"); // IDEX Mode - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Đậu tự động"); // Auto-Park - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Sự gấp đôi"); // Duplication - PROGMEM Language_Str MSG_IDEX_MODE_SCALED_COPY = _UxGT("Bản sao thu nhỏ"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Toàn quyền điều khiển"); // Full control - PROGMEM Language_Str MSG_IDEX_X_OFFSET = _UxGT("Đầu phun X nhì"); // 2nd nozzle X - PROGMEM Language_Str MSG_IDEX_Y_OFFSET = _UxGT("Đầu phun Y nhì"); - PROGMEM Language_Str MSG_IDEX_Z_OFFSET = _UxGT("Đầu phun Z nhì"); - PROGMEM Language_Str MSG_IDEX_SAVE_OFFSETS = _UxGT("Lưu bù đắp"); // Save offsets - PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Tự xây dựng lưới"); // Manually Build Mesh - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Đặt chêm và đo"); // Place shim & measure - PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Đo"); // Measure - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Tháo và đo bàn"); // Remove & measure bed - PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Chuyển sang tiếp theo"); // moving to next - PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Bật UBL"); - PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Tắt UBL"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Nhiệt độ bàn"); // Bed Temp - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Nhiệt độ đầu phun"); // Hotend Temp - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); - PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Chỉnh sửa lưới"); // Mesh Edit - PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Chỉnh sửa lưới tự chọn"); // Edit Custom Mesh - PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Chỉnh lưới chính xác"); // Fine tuning mesh - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Chỉnh sửa xong lưới"); // Done Editing Mesh - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Xây dựng lưới tự chọn"); // Build Custom Mesh - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Xây dựng lưới"); // Build Mesh + LSTR MSG_PREHEAT_CUSTOM = _UxGT("Sự nóng trước tự chọn"); // Preheat Custom + LSTR MSG_COOLDOWN = _UxGT("Nguội xuống"); // Cooldown + LSTR MSG_SWITCH_PS_ON = _UxGT("Bật nguồn"); // Switch power on + LSTR MSG_SWITCH_PS_OFF = _UxGT("Tắt nguồn"); // Switch power off + LSTR MSG_EXTRUDE = _UxGT("Ép đùn"); // Extrude + LSTR MSG_RETRACT = _UxGT("Rút lại"); // Retract + LSTR MSG_MOVE_AXIS = _UxGT("Di chuyển trục"); // Move axis + LSTR MSG_BED_LEVELING = _UxGT("San Lấp Bàn"); // Bed Leveling + LSTR MSG_LEVEL_BED = _UxGT("Làm bằng mặt bàn"); // Level bed + LSTR MSG_BED_TRAMMING = _UxGT("Làm bằng góc bàn"); // Level corners + LSTR MSG_NEXT_CORNER = _UxGT("Góc tiếp theo"); // Next corner + LSTR MSG_EDITING_STOPPED = _UxGT("Chỉnh lưới đã dừng"); // Mesh Editing Stopped + LSTR MSG_MESH_X = _UxGT("Mục lục X"); // Index X + LSTR MSG_MESH_Y = _UxGT("Mục lục Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Giá trị Z"); // Z Value + LSTR MSG_CUSTOM_COMMANDS = _UxGT("Các lệnh tự chọn"); // Custom Commands + LSTR MSG_UBL_DOING_G29 = _UxGT("Đang chạy G29"); // Doing G29 + LSTR MSG_UBL_TOOLS = _UxGT("Công cụ UBL"); // UBL tools + LSTR MSG_UBL_LEVEL_BED = _UxGT("San Lấp Bàn Thống Nhất (UBL)"); // Unified Bed Leveling + LSTR MSG_IDEX_MENU = _UxGT("chế độ IDEX"); // IDEX Mode + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Đậu tự động"); // Auto-Park + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Sự gấp đôi"); // Duplication + LSTR MSG_IDEX_MODE_SCALED_COPY = _UxGT("Bản sao thu nhỏ"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Toàn quyền điều khiển"); // Full control + LSTR MSG_IDEX_X_OFFSET = _UxGT("Đầu phun X nhì"); // 2nd nozzle X + LSTR MSG_IDEX_Y_OFFSET = _UxGT("Đầu phun Y nhì"); + LSTR MSG_IDEX_Z_OFFSET = _UxGT("Đầu phun Z nhì"); + LSTR MSG_IDEX_SAVE_OFFSETS = _UxGT("Lưu bù đắp"); // Save offsets + LSTR MSG_UBL_MANUAL_MESH = _UxGT("Tự xây dựng lưới"); // Manually Build Mesh + LSTR MSG_UBL_BC_INSERT = _UxGT("Đặt chêm và đo"); // Place shim & measure + LSTR MSG_UBL_BC_INSERT2 = _UxGT("Đo"); // Measure + LSTR MSG_UBL_BC_REMOVE = _UxGT("Tháo và đo bàn"); // Remove & measure bed + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Chuyển sang tiếp theo"); // moving to next + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("Bật UBL"); + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Tắt UBL"); + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Nhiệt độ bàn"); // Bed Temp + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bed Temp"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Nhiệt độ đầu phun"); // Hotend Temp + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hotend Temp"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("Chỉnh sửa lưới"); // Mesh Edit + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Chỉnh sửa lưới tự chọn"); // Edit Custom Mesh + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Chỉnh lưới chính xác"); // Fine tuning mesh + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Chỉnh sửa xong lưới"); // Done Editing Mesh + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Xây dựng lưới tự chọn"); // Build Custom Mesh + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Xây dựng lưới"); // Build Mesh #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Xây dựng lưới ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Thẩm tra lưới ($)"); + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Xây dựng lưới ($)"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Thẩm tra lưới ($)"); #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Xây dựng lưới lạnh"); // Build cold mesh - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Điều chỉnh chiều cao lưới"); // Adjust Mesh Height - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Số lượng chiều cao"); // Height Amount - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Thẩm tra lưới"); // Validate Mesh - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Thẩm tra lưới tự chọn"); // validate custom mesh - PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Tiếp tục xây lưới bàn"); // Continue Bed Mesh - PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Đang san lấp lưới"); // Mesh Leveling - PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Đang san lấp 3-điểm"); // 3-Point Leveling - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Đang san lấp lưới phẳng"); // Grid (planar) Mesh Leveling - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Làm bằng lưới"); // Level Mesh - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Điểm bên cạnh"); // Side Points - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Loại bản đồ"); // Map Type - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Đầu ra bản đồ lưới"); // Output Mesh Map - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Đầu ra cho máy chủ"); // Output for Host - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Đầu ra cho CSV"); // Output for CSV - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Hỗ trợ lưới"); // Off Printer Backup | backup mesh - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Đầu ra thông tin UBL"); // Output UBL Info - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Chỉnh sửa lưới"); // Edit mesh - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Số lượng lấp đầy"); // Fill-in Amount - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Tự lấp đầy"); // Manual Fill-in - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Lấp đầy thông minh"); // Smart Fill-in - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Lưới lấp đầy"); // Fill-in Mesh - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Bác bỏ tất cả"); // Invalidate All - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Bác bỏ gần nhất"); // Invalidate Closest - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Chỉnh chính xác tất cả"); // Fine Tune ALl - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Chỉnh chính xác gần nhất"); // Fine Tune Closest - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Lưu trữ lưới"); // Mesh Storage - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Khe nhớ"); // Memory Slot - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Tải lưới bàn"); // Load Bed Mesh - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Lưu lưới bàn"); // Save Bed Mesh - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("%i lưới được nạp"); // Mesh %i loaded - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("%i lưới đã lưu"); - PROGMEM Language_Str MSG_NO_STORAGE = _UxGT("Không lưu trữ"); // No Storage - PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Điều sai: Lưu UBL"); // Err: UBL Save - PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Điều Sai: Khôi Phục UBL"); // Err: UBL Restore - PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Đầu Dò-Z Đã Ngừng"); // Z-Offset Stopped - PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Bước-Từng-Bước UBL"); // Step-By-Step UBL - PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Xây dựng lưới lạnh"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2.Lấp đầy thông minh"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Thẩm tra lưới"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Chỉnh chính xác tất cả"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Thẩm tra lưới"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Chỉnh chính xác tất cả"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Lưu lưới bàn"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Xây dựng lưới lạnh"); // Build cold mesh + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Điều chỉnh chiều cao lưới"); // Adjust Mesh Height + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Số lượng chiều cao"); // Height Amount + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Thẩm tra lưới"); // Validate Mesh + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Thẩm tra lưới tự chọn"); // validate custom mesh + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Tiếp tục xây lưới bàn"); // Continue Bed Mesh + LSTR MSG_UBL_MESH_LEVELING = _UxGT("Đang san lấp lưới"); // Mesh Leveling + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Đang san lấp 3-điểm"); // 3-Point Leveling + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Đang san lấp lưới phẳng"); // Grid (planar) Mesh Leveling + LSTR MSG_UBL_MESH_LEVEL = _UxGT("Làm bằng lưới"); // Level Mesh + LSTR MSG_UBL_SIDE_POINTS = _UxGT("Điểm bên cạnh"); // Side Points + LSTR MSG_UBL_MAP_TYPE = _UxGT("Loại bản đồ"); // Map Type + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Đầu ra bản đồ lưới"); // Output Mesh Map + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Đầu ra cho máy chủ"); // Output for Host + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Đầu ra cho CSV"); // Output for CSV + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Hỗ trợ lưới"); // Off Printer Backup | backup mesh + LSTR MSG_UBL_INFO_UBL = _UxGT("Đầu ra thông tin UBL"); // Output UBL Info + LSTR MSG_EDIT_MESH = _UxGT("Chỉnh sửa lưới"); // Edit mesh + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Số lượng lấp đầy"); // Fill-in Amount + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Tự lấp đầy"); // Manual Fill-in + LSTR MSG_UBL_SMART_FILLIN = _UxGT("Lấp đầy thông minh"); // Smart Fill-in + LSTR MSG_UBL_FILLIN_MESH = _UxGT("Lưới lấp đầy"); // Fill-in Mesh + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Bác bỏ tất cả"); // Invalidate All + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Bác bỏ gần nhất"); // Invalidate Closest + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Chỉnh chính xác tất cả"); // Fine Tune ALl + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Chỉnh chính xác gần nhất"); // Fine Tune Closest + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Lưu trữ lưới"); // Mesh Storage + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Khe nhớ"); // Memory Slot + LSTR MSG_UBL_LOAD_MESH = _UxGT("Tải lưới bàn"); // Load Bed Mesh + LSTR MSG_UBL_SAVE_MESH = _UxGT("Lưu lưới bàn"); // Save Bed Mesh + LSTR MSG_MESH_LOADED = _UxGT("%i lưới được nạp"); // Mesh %i loaded + LSTR MSG_MESH_SAVED = _UxGT("%i lưới đã lưu"); + LSTR MSG_NO_STORAGE = _UxGT("Không lưu trữ"); // No Storage + LSTR MSG_UBL_SAVE_ERROR = _UxGT("Điều sai: Lưu UBL"); // Err: UBL Save + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Điều Sai: Khôi Phục UBL"); // Err: UBL Restore + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Đầu Dò-Z Đã Ngừng"); // Z-Offset Stopped + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Bước-Từng-Bước UBL"); // Step-By-Step UBL + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Xây dựng lưới lạnh"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Lấp đầy thông minh"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Thẩm tra lưới"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Chỉnh chính xác tất cả"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Thẩm tra lưới"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Chỉnh chính xác tất cả"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Lưu lưới bàn"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Điều khiển LED"); // LED Control - PROGMEM Language_Str MSG_LEDS = _UxGT("Đèn"); // Lights - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Đèn định sẵn"); // Light Presets - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Đỏ"); // Red - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Cam"); // Orange - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Vàng"); // Yellow - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Xanh Lá"); // Green - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Xanh"); // Blue - PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Xanh Đậm"); // Indigo - PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Tím"); // Violet - PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Trắng"); // White - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Mặc định"); // Default - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Đèn Tự Chọn"); // Custom Lights - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Cường Độ Đỏ"); // Red Intensity - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Cường Độ Xanh Lá"); // Green Intensity - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Cường Độ Xanh"); // Blue Intensity - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Cường Độ Trắng"); // White Intensity - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("độ sáng"); // Brightness + LSTR MSG_LED_CONTROL = _UxGT("Điều khiển LED"); // LED Control + LSTR MSG_LEDS = _UxGT("Đèn"); // Lights + LSTR MSG_LED_PRESETS = _UxGT("Đèn định sẵn"); // Light Presets + LSTR MSG_SET_LEDS_RED = _UxGT("Đỏ"); // Red + LSTR MSG_SET_LEDS_ORANGE = _UxGT("Cam"); // Orange + LSTR MSG_SET_LEDS_YELLOW = _UxGT("Vàng"); // Yellow + LSTR MSG_SET_LEDS_GREEN = _UxGT("Xanh Lá"); // Green + LSTR MSG_SET_LEDS_BLUE = _UxGT("Xanh"); // Blue + LSTR MSG_SET_LEDS_INDIGO = _UxGT("Xanh Đậm"); // Indigo + LSTR MSG_SET_LEDS_VIOLET = _UxGT("Tím"); // Violet + LSTR MSG_SET_LEDS_WHITE = _UxGT("Trắng"); // White + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Mặc định"); // Default + LSTR MSG_CUSTOM_LEDS = _UxGT("Đèn Tự Chọn"); // Custom Lights + LSTR MSG_INTENSITY_R = _UxGT("Cường Độ Đỏ"); // Red Intensity + LSTR MSG_INTENSITY_G = _UxGT("Cường Độ Xanh Lá"); // Green Intensity + LSTR MSG_INTENSITY_B = _UxGT("Cường Độ Xanh"); // Blue Intensity + LSTR MSG_INTENSITY_W = _UxGT("Cường Độ Trắng"); // White Intensity + LSTR MSG_LED_BRIGHTNESS = _UxGT("độ sáng"); // Brightness - PROGMEM Language_Str MSG_MOVING = _UxGT("Di chuyển..."); // Moving - PROGMEM Language_Str MSG_FREE_XY = _UxGT("Giải phóng XY"); // Free XY - PROGMEM Language_Str MSG_MOVE_X = _UxGT("Di chuyển X"); // Move X - PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Di chuyển Y"); - PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Di chuyển Z"); - PROGMEM Language_Str MSG_MOVE_E = _UxGT("Máy đùn"); // Extruder - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Máy đùn *"); - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Đầu nóng quá lạnh"); // Hotend too cold - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Di chuyển 10mm"); // Move 10mm - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Di chuyển 100mm"); // Move 100mm - PROGMEM Language_Str MSG_SPEED = _UxGT("Tốc độ"); // Speed - PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Bàn"); - PROGMEM Language_Str MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Đầu phun ~"); - PROGMEM Language_Str MSG_BED = _UxGT("Bàn"); // bed - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Tốc độ quạt"); // fan speed - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Tốc độ quạt ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Tốc độ quạt phụ"); // Extra fan speed - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Tốc độ quạt phụ ~"); - PROGMEM Language_Str MSG_FLOW = _UxGT("Lưu Lượng"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("Lưu Lượng ~"); - PROGMEM Language_Str MSG_CONTROL = _UxGT("Điều khiển"); // Control - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Đa"); // min - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Thiểu"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Hệ Số"); // factor - PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Nhiệt độ tự động"); // Autotemp - PROGMEM Language_Str MSG_LCD_ON = _UxGT("Bật"); // on - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Tắt"); // off - PROGMEM Language_Str MSG_SELECT = _UxGT("Lựa"); // Select - PROGMEM Language_Str MSG_SELECT_E = _UxGT("Lựa *"); - PROGMEM Language_Str MSG_ACC = _UxGT("Tăng Tốc"); - PROGMEM Language_Str MSG_JERK = _UxGT("Giật"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("Giật-V") LCD_STR_A; - PROGMEM Language_Str MSG_VB_JERK = _UxGT("Giật-V") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("Giật-V") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("Giật-V") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("Giật-V") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("Giật-V") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Giật-Ve"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Độ Lệch Chỗ Giao"); // Junction Dev - PROGMEM Language_Str MSG_VELOCITY = _UxGT("Vận tốc"); // velocity - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vđa") LCD_STR_A; // Vmax - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vđa") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vđa") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vđa") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vđa") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vđa") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vđa") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vđa *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vthiểu"); // Vmin - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vchuyển thiểu"); // VTrav min - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Sự tăng tốc"); // Acceleration - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Tăng tốc ca") LCD_STR_A; // Amax - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Tăng tốc ca") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Tăng tốc ca") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("Tăng tốc ca") LCD_STR_I; // Amax - PROGMEM Language_Str MSG_AMAX_J = _UxGT("Tăng tốc ca") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("Tăng tốc ca") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Tăng tốc ca") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("TT-Rút"); // A-retract - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("TT-Chuyển"); // A-travel - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Bước/mm"); // Steps - PROGMEM Language_Str MSG_A_STEPS = _UxGT("Bước") LCD_STR_A _UxGT("/mm"); // Steps/mm - PROGMEM Language_Str MSG_B_STEPS = _UxGT("Bước") LCD_STR_B _UxGT("/mm"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("Bước") LCD_STR_C _UxGT("/mm"); - PROGMEM Language_Str MSG_I_STEPS = _UxGT("Bước") LCD_STR_I _UxGT("/mm"); // Steps/mm - PROGMEM Language_Str MSG_J_STEPS = _UxGT("Bước") LCD_STR_J _UxGT("/mm"); - PROGMEM Language_Str MSG_K_STEPS = _UxGT("Bước") LCD_STR_K _UxGT("/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("BướcE/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("Bước */mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature - PROGMEM Language_Str MSG_MOTION = _UxGT("Chuyển động"); // Motion - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Vật liệu in"); // dây nhựa - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E bằng mm") SUPERSCRIPT_THREE; // E in mm - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Đường kính nhựa"); // Fil. Dai. - PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Đường kính nhựa *"); - PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Dỡ mm"); // unload mm - PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Nạp mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("K Cấp Cao"); // Advance K - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("K Cấp Cao *"); // Advance K - PROGMEM Language_Str MSG_CONTRAST = _UxGT("Độ tương phản LCD"); // LCD contrast - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Lưu các thiết lập"); // Store settings - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Tải các cài đặt"); // Load settings - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Khôi phục phòng hư"); // Restore Defaults - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Khởi Tạo EEPROM"); // Initialize EEPROM - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Cập Nhật phương tiện"); // Update media - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Bặt Lại Máy In"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Cập Nhật"); // Refresh - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Màn Hình Thông Tin"); // Info screen - PROGMEM Language_Str MSG_PREPARE = _UxGT("Chuẩn bị"); // Prepare - PROGMEM Language_Str MSG_TUNE = _UxGT("Điều Chỉnh"); // Tune - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Tạm dừng in"); // Pause print - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Tiếp tục in"); // Resume print - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Ngừng in"); // Stop print - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Phục Hồi Mất Điện"); // Outage Recovery - PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("In từ phương tiện"); // Print from media - PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Không có phương tiện"); // No media - PROGMEM Language_Str MSG_DWELL = _UxGT("Ngủ..."); // Sleep - PROGMEM Language_Str MSG_USERWAIT = _UxGT("Nhấn để tiếp tục..."); // Click to resume (same as 'continue') - PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("In tạm dừng"); // print paused - PROGMEM Language_Str MSG_PRINTING = _UxGT("Đang in..."); // printing - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("In đã hủy bỏ"); // Print aborted - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Không di chuyển."); // No move. - PROGMEM Language_Str MSG_KILLED = _UxGT("ĐÃ CHẾT. "); - PROGMEM Language_Str MSG_STOPPED = _UxGT("ĐÃ NGỪNG. "); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rút mm"); // Retract mm - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Rút Trao.mm"); // Swap Re.mm - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Rút V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Nhảy mm"); // hop - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("BỏRút mm"); // Unretr. mm - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("BỏRút T mm"); // S Unretr. mm - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("BỏRút V"); // UnRet V - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("BỏRút T V"); // S UnRet V - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("RútTựĐộng"); // Auto-Retract - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Khoảng Cách Rút"); // Retract Distance - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Thay Đổi Công Cụ"); // Tool Change - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Đưa Lên Z"); // Z Raise - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Tốc Độ Tuôn Ra"); // Prime Speed - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Tốc Độ Rút Lại"); // Retract Speed - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Thay dây nhựa"); // change filament - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Thay dây nhựa *"); // change filament - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Nạp dây nhựa"); // load filament - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Nạp dây nhựa *"); // load filament - PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Dỡ dây nhựa"); // unload filament - PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Dỡ dây nhựa *"); // unload filament - PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Dỡ tất cả"); // Unload All - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Khởi tạo phương tiện"); // Attach media - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Thay phương tiện"); // Change midea - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Phát hành phương tiện"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Đầu Dò Z qua bàn"); // Z Probe past bed - PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Hệ số nghiêng"); // Skew Factor - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTOUCH"); // BLTouch - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Tự kiểm tra BLTOUCH "); // BLTouch Self-Test - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Bặt lại BLTouch"); // Reset BLTouch - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Đem BLTouch"); // Deploy BLTouch - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Cất BLTouch"); // Stow BLTouch - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Đem Đầu Dò-Z"); // Deploy Z-Probe - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Cất Đầu Dò-Z"); // Stow Z-Probe - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Về nhà %s%s%s Trước"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Đầu Dò Bù Đắp Z"); // Probe Z Offset - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Nhít X"); // Babystep X - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Nhít Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Nhít Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Hủy bỏ công tắc"); // Endstop abort - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Sưởi đầu phun không thành công"); // Heating failed - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Điều sai: nhiệt độ dư"); // Err: REDUNDANT TEMP - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Vấn đề nhiệt"); // THERMAL RUNAWAY | problem - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("Vấn đề nhiệt bàn"); // BED THERMAL RUNAWAY - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Điều sai: nhiệt độ tối đa"); // Err: MAXTEMP - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Điều sai: nhiệt độ tối thiểu"); // Err: MINTEMP - PROGMEM Language_Str MSG_HALTED = _UxGT("MÁY IN ĐÃ DỪNG LẠI"); // PRINTER HALTED - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Xin bặt lại"); // Please reset - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // d - ngày - One character only - PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("g"); // h - giờ - One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("p"); // m - phút - One character only - PROGMEM Language_Str MSG_HEATING = _UxGT("Đang sưởi nóng..."); // heating - PROGMEM Language_Str MSG_COOLING = _UxGT("Đang làm nguội..."); // cooling - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Đang sưởi nong bàn..."); // bed heating - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Đang làm nguội bàn..."); // bed cooling - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Cân Chỉnh Delta"); // Delta calibration - PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Chỉnh X lại"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Chỉnh Y lại"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Chỉnh Z lại"); - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Chỉnh Z Center"); // Calibrate Center - PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Cài Đặt Delta"); // Delta Settings - PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Cân Chỉnh Tự Động"); // Auto Calibration - PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Đặt Chiều Cao Delta"); // Set Delta Height - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Đầu Dò Z-Bù Đắp"); // Probe Z-offset - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Gậy Chéo"); // Diag Rod - PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Chiều Cao"); // Height - PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Bán Kính"); // Radius - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Về Máy In"); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Thông Tin Máy In"); // Printer Info - PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("San lấp 3-Điểm"); // 3-Point Leveling - PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("San Lấp Tuyến Tính"); // Linear Leveling - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("San Lấp Song Tuyến"); // Bilinear Leveling - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("San Lấp Bàn Thống Nhất"); // Unified Bed Leveling - PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Lưới San Lấp"); // Mesh Leveling - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Thống Kê Máy In"); // Printer Stats - PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Thông Tin Bo Mạch"); // Board Info - PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Điện Trở Nhiệt"); // Thermistors - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Máy đùn"); // Extruders - PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baud"); // Baud - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Giao Thức"); // Protocol - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Đèn Khuông"); // Case light - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Độ Sáng"); // Light Brightness + LSTR MSG_MOVING = _UxGT("Di chuyển..."); // Moving + LSTR MSG_FREE_XY = _UxGT("Giải phóng XY"); // Free XY + LSTR MSG_MOVE_X = _UxGT("Di chuyển X"); // Move X + LSTR MSG_MOVE_Y = _UxGT("Di chuyển Y"); + LSTR MSG_MOVE_Z = _UxGT("Di chuyển Z"); + LSTR MSG_MOVE_E = _UxGT("Máy đùn"); // Extruder + LSTR MSG_MOVE_EN = _UxGT("Máy đùn *"); + LSTR MSG_HOTEND_TOO_COLD = _UxGT("Đầu nóng quá lạnh"); // Hotend too cold + LSTR MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm + LSTR MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm + LSTR MSG_MOVE_10MM = _UxGT("Di chuyển 10mm"); // Move 10mm + LSTR MSG_MOVE_100MM = _UxGT("Di chuyển 100mm"); // Move 100mm + LSTR MSG_SPEED = _UxGT("Tốc độ"); // Speed + LSTR MSG_BED_Z = _UxGT("Z Bàn"); + LSTR MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle + LSTR MSG_NOZZLE_N = _UxGT("Đầu phun ~"); + LSTR MSG_BED = _UxGT("Bàn"); // bed + LSTR MSG_FAN_SPEED = _UxGT("Tốc độ quạt"); // fan speed + LSTR MSG_FAN_SPEED_N = _UxGT("Tốc độ quạt ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Tốc độ quạt phụ"); // Extra fan speed + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Tốc độ quạt phụ ~"); + LSTR MSG_FLOW = _UxGT("Lưu Lượng"); + LSTR MSG_FLOW_N = _UxGT("Lưu Lượng ~"); + LSTR MSG_CONTROL = _UxGT("Điều khiển"); // Control + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Đa"); // min + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Thiểu"); + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Hệ Số"); // factor + LSTR MSG_AUTOTEMP = _UxGT("Nhiệt độ tự động"); // Autotemp + LSTR MSG_LCD_ON = _UxGT("Bật"); // on + LSTR MSG_LCD_OFF = _UxGT("Tắt"); // off + LSTR MSG_SELECT = _UxGT("Lựa"); // Select + LSTR MSG_SELECT_E = _UxGT("Lựa *"); + LSTR MSG_ACC = _UxGT("Tăng Tốc"); + LSTR MSG_JERK = _UxGT("Giật"); + LSTR MSG_VA_JERK = _UxGT("Giật-V") LCD_STR_A; + LSTR MSG_VB_JERK = _UxGT("Giật-V") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("Giật-V") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("Giật-V") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("Giật-V") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("Giật-V") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("Giật-Ve"); + LSTR MSG_JUNCTION_DEVIATION = _UxGT("Độ Lệch Chỗ Giao"); // Junction Dev + LSTR MSG_VELOCITY = _UxGT("Vận tốc"); // velocity + LSTR MSG_VMAX_A = _UxGT("Vđa") LCD_STR_A; // Vmax + LSTR MSG_VMAX_B = _UxGT("Vđa") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("Vđa") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("Vđa") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("Vđa") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("Vđa") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("Vđa") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("Vđa *"); + LSTR MSG_VMIN = _UxGT("Vthiểu"); // Vmin + LSTR MSG_VTRAV_MIN = _UxGT("Vchuyển thiểu"); // VTrav min + LSTR MSG_ACCELERATION = _UxGT("Sự tăng tốc"); // Acceleration + LSTR MSG_AMAX_A = _UxGT("Tăng tốc ca") LCD_STR_A; // Amax + LSTR MSG_AMAX_B = _UxGT("Tăng tốc ca") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("Tăng tốc ca") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("Tăng tốc ca") LCD_STR_I; // Amax + LSTR MSG_AMAX_J = _UxGT("Tăng tốc ca") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("Tăng tốc ca") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("Tăng tốc ca") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); + LSTR MSG_A_RETRACT = _UxGT("TT-Rút"); // A-retract + LSTR MSG_A_TRAVEL = _UxGT("TT-Chuyển"); // A-travel + LSTR MSG_STEPS_PER_MM = _UxGT("Bước/mm"); // Steps + LSTR MSG_A_STEPS = _UxGT("Bước") LCD_STR_A _UxGT("/mm"); // Steps/mm + LSTR MSG_B_STEPS = _UxGT("Bước") LCD_STR_B _UxGT("/mm"); + LSTR MSG_C_STEPS = _UxGT("Bước") LCD_STR_C _UxGT("/mm"); + LSTR MSG_I_STEPS = _UxGT("Bước") LCD_STR_I _UxGT("/mm"); // Steps/mm + LSTR MSG_J_STEPS = _UxGT("Bước") LCD_STR_J _UxGT("/mm"); + LSTR MSG_K_STEPS = _UxGT("Bước") LCD_STR_K _UxGT("/mm"); + LSTR MSG_E_STEPS = _UxGT("BướcE/mm"); + LSTR MSG_EN_STEPS = _UxGT("Bước */mm"); + LSTR MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature + LSTR MSG_MOTION = _UxGT("Chuyển động"); // Motion + LSTR MSG_FILAMENT = _UxGT("Vật liệu in"); // dây nhựa + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E bằng mm") SUPERSCRIPT_THREE; // E in mm + LSTR MSG_FILAMENT_DIAM = _UxGT("Đường kính nhựa"); // Fil. Dai. + LSTR MSG_FILAMENT_DIAM_E = _UxGT("Đường kính nhựa *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("Dỡ mm"); // unload mm + LSTR MSG_FILAMENT_LOAD = _UxGT("Nạp mm"); + LSTR MSG_ADVANCE_K = _UxGT("K Cấp Cao"); // Advance K + LSTR MSG_ADVANCE_K_E = _UxGT("K Cấp Cao *"); // Advance K + LSTR MSG_CONTRAST = _UxGT("Độ tương phản LCD"); // LCD contrast + LSTR MSG_STORE_EEPROM = _UxGT("Lưu các thiết lập"); // Store settings + LSTR MSG_LOAD_EEPROM = _UxGT("Tải các cài đặt"); // Load settings + LSTR MSG_RESTORE_DEFAULTS = _UxGT("Khôi phục phòng hư"); // Restore Defaults + LSTR MSG_INIT_EEPROM = _UxGT("Khởi Tạo EEPROM"); // Initialize EEPROM + LSTR MSG_MEDIA_UPDATE = _UxGT("Cập Nhật phương tiện"); // Update media + LSTR MSG_RESET_PRINTER = _UxGT("Bặt Lại Máy In"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Cập Nhật"); // Refresh + LSTR MSG_INFO_SCREEN = _UxGT("Màn Hình Thông Tin"); // Info screen + LSTR MSG_PREPARE = _UxGT("Chuẩn bị"); // Prepare + LSTR MSG_TUNE = _UxGT("Điều Chỉnh"); // Tune + LSTR MSG_PAUSE_PRINT = _UxGT("Tạm dừng in"); // Pause print + LSTR MSG_RESUME_PRINT = _UxGT("Tiếp tục in"); // Resume print + LSTR MSG_STOP_PRINT = _UxGT("Ngừng in"); // Stop print + LSTR MSG_OUTAGE_RECOVERY = _UxGT("Phục Hồi Mất Điện"); // Outage Recovery + LSTR MSG_MEDIA_MENU = _UxGT("In từ phương tiện"); // Print from media + LSTR MSG_NO_MEDIA = _UxGT("Không có phương tiện"); // No media + LSTR MSG_DWELL = _UxGT("Ngủ..."); // Sleep + LSTR MSG_USERWAIT = _UxGT("Nhấn để tiếp tục..."); // Click to resume (same as 'continue') + LSTR MSG_PRINT_PAUSED = _UxGT("In tạm dừng"); // print paused + LSTR MSG_PRINTING = _UxGT("Đang in..."); // printing + LSTR MSG_PRINT_ABORTED = _UxGT("In đã hủy bỏ"); // Print aborted + LSTR MSG_NO_MOVE = _UxGT("Không di chuyển."); // No move. + LSTR MSG_KILLED = _UxGT("ĐÃ CHẾT. "); + LSTR MSG_STOPPED = _UxGT("ĐÃ NGỪNG. "); + LSTR MSG_CONTROL_RETRACT = _UxGT("Rút mm"); // Retract mm + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Rút Trao.mm"); // Swap Re.mm + LSTR MSG_CONTROL_RETRACTF = _UxGT("Rút V"); + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Nhảy mm"); // hop + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("BỏRút mm"); // Unretr. mm + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("BỏRút T mm"); // S Unretr. mm + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("BỏRút V"); // UnRet V + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("BỏRút T V"); // S UnRet V + LSTR MSG_AUTORETRACT = _UxGT("RútTựĐộng"); // Auto-Retract + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Khoảng Cách Rút"); // Retract Distance + LSTR MSG_TOOL_CHANGE = _UxGT("Thay Đổi Công Cụ"); // Tool Change + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Đưa Lên Z"); // Z Raise + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Tốc Độ Tuôn Ra"); // Prime Speed + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Tốc Độ Rút Lại"); // Retract Speed + LSTR MSG_FILAMENTCHANGE = _UxGT("Thay dây nhựa"); // change filament + LSTR MSG_FILAMENTCHANGE_E = _UxGT("Thay dây nhựa *"); // change filament + LSTR MSG_FILAMENTLOAD = _UxGT("Nạp dây nhựa"); // load filament + LSTR MSG_FILAMENTLOAD_E = _UxGT("Nạp dây nhựa *"); // load filament + LSTR MSG_FILAMENTUNLOAD = _UxGT("Dỡ dây nhựa"); // unload filament + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Dỡ dây nhựa *"); // unload filament + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Dỡ tất cả"); // Unload All + LSTR MSG_ATTACH_MEDIA = _UxGT("Khởi tạo phương tiện"); // Attach media + LSTR MSG_CHANGE_MEDIA = _UxGT("Thay phương tiện"); // Change midea + LSTR MSG_RELEASE_MEDIA = _UxGT("Phát hành phương tiện"); + LSTR MSG_ZPROBE_OUT = _UxGT("Đầu Dò Z qua bàn"); // Z Probe past bed + LSTR MSG_SKEW_FACTOR = _UxGT("Hệ số nghiêng"); // Skew Factor + LSTR MSG_BLTOUCH = _UxGT("BLTOUCH"); // BLTouch + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Tự kiểm tra BLTOUCH "); // BLTouch Self-Test + LSTR MSG_BLTOUCH_RESET = _UxGT("Bặt lại BLTouch"); // Reset BLTouch + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Đem BLTouch"); // Deploy BLTouch + LSTR MSG_BLTOUCH_STOW = _UxGT("Cất BLTouch"); // Stow BLTouch + LSTR MSG_MANUAL_DEPLOY = _UxGT("Đem Đầu Dò-Z"); // Deploy Z-Probe + LSTR MSG_MANUAL_STOW = _UxGT("Cất Đầu Dò-Z"); // Stow Z-Probe + LSTR MSG_HOME_FIRST = _UxGT("Về nhà %s%s%s Trước"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Đầu Dò Bù Đắp Z"); // Probe Z Offset + LSTR MSG_BABYSTEP_X = _UxGT("Nhít X"); // Babystep X + LSTR MSG_BABYSTEP_Y = _UxGT("Nhít Y"); + LSTR MSG_BABYSTEP_Z = _UxGT("Nhít Z"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("Hủy bỏ công tắc"); // Endstop abort + LSTR MSG_HEATING_FAILED_LCD = _UxGT("Sưởi đầu phun không thành công"); // Heating failed + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Điều sai: nhiệt độ dư"); // Err: REDUNDANT TEMP + LSTR MSG_THERMAL_RUNAWAY = _UxGT("Vấn đề nhiệt"); // THERMAL RUNAWAY | problem + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("Vấn đề nhiệt bàn"); // BED THERMAL RUNAWAY + LSTR MSG_ERR_MAXTEMP = _UxGT("Điều sai: nhiệt độ tối đa"); // Err: MAXTEMP + LSTR MSG_ERR_MINTEMP = _UxGT("Điều sai: nhiệt độ tối thiểu"); // Err: MINTEMP + LSTR MSG_HALTED = _UxGT("MÁY IN ĐÃ DỪNG LẠI"); // PRINTER HALTED + LSTR MSG_PLEASE_RESET = _UxGT("Xin bặt lại"); // Please reset + LSTR MSG_SHORT_DAY = _UxGT("n"); // d - ngày - One character only + LSTR MSG_SHORT_HOUR = _UxGT("g"); // h - giờ - One character only + LSTR MSG_SHORT_MINUTE = _UxGT("p"); // m - phút - One character only + LSTR MSG_HEATING = _UxGT("Đang sưởi nóng..."); // heating + LSTR MSG_COOLING = _UxGT("Đang làm nguội..."); // cooling + LSTR MSG_BED_HEATING = _UxGT("Đang sưởi nong bàn..."); // bed heating + LSTR MSG_BED_COOLING = _UxGT("Đang làm nguội bàn..."); // bed cooling + LSTR MSG_DELTA_CALIBRATE = _UxGT("Cân Chỉnh Delta"); // Delta calibration + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Chỉnh X lại"); + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Chỉnh Y lại"); + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Chỉnh Z lại"); + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Chỉnh Z Center"); // Calibrate Center + LSTR MSG_DELTA_SETTINGS = _UxGT("Cài Đặt Delta"); // Delta Settings + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Cân Chỉnh Tự Động"); // Auto Calibration + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Đặt Chiều Cao Delta"); // Set Delta Height + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Đầu Dò Z-Bù Đắp"); // Probe Z-offset + LSTR MSG_DELTA_DIAG_ROD = _UxGT("Gậy Chéo"); // Diag Rod + LSTR MSG_DELTA_HEIGHT = _UxGT("Chiều Cao"); // Height + LSTR MSG_DELTA_RADIUS = _UxGT("Bán Kính"); // Radius + LSTR MSG_INFO_MENU = _UxGT("Về Máy In"); + LSTR MSG_INFO_PRINTER_MENU = _UxGT("Thông Tin Máy In"); // Printer Info + LSTR MSG_3POINT_LEVELING = _UxGT("San lấp 3-Điểm"); // 3-Point Leveling + LSTR MSG_LINEAR_LEVELING = _UxGT("San Lấp Tuyến Tính"); // Linear Leveling + LSTR MSG_BILINEAR_LEVELING = _UxGT("San Lấp Song Tuyến"); // Bilinear Leveling + LSTR MSG_UBL_LEVELING = _UxGT("San Lấp Bàn Thống Nhất"); // Unified Bed Leveling + LSTR MSG_MESH_LEVELING = _UxGT("Lưới San Lấp"); // Mesh Leveling + LSTR MSG_INFO_STATS_MENU = _UxGT("Thống Kê Máy In"); // Printer Stats + LSTR MSG_INFO_BOARD_MENU = _UxGT("Thông Tin Bo Mạch"); // Board Info + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Điện Trở Nhiệt"); // Thermistors + LSTR MSG_INFO_EXTRUDERS = _UxGT("Máy đùn"); // Extruders + LSTR MSG_INFO_BAUDRATE = _UxGT("Baud"); // Baud + LSTR MSG_INFO_PROTOCOL = _UxGT("Giao Thức"); // Protocol + LSTR MSG_CASE_LIGHT = _UxGT("Đèn Khuông"); // Case light + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Độ Sáng"); // Light Brightness #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Số In"); // Print Count - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Đã hoàn thành"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tổng số thời gian in"); // Total print time - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Thời gian việc lâu nhất"); // Longest job time - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Tổng số đùn"); // Extruded total + LSTR MSG_INFO_PRINT_COUNT = _UxGT("Số In"); // Print Count + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Đã hoàn thành"); + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tổng số thời gian in"); // Total print time + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Thời gian việc lâu nhất"); // Longest job time + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Tổng số đùn"); // Extruded total #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("In"); // prints - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Đã hoàn thành"); // Completed - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tổng số"); // total - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Dài nhất"); // Longest - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Đã ép đùn"); + LSTR MSG_INFO_PRINT_COUNT = _UxGT("In"); // prints + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Đã hoàn thành"); // Completed + LSTR MSG_INFO_PRINT_TIME = _UxGT("Tổng số"); // total + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Dài nhất"); // Longest + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Đã ép đùn"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Nhiệt độ tối thiểu"); // Min Temp - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Nhiệt độ tối đa"); // Max temp - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Bộ nguồn"); // PSU - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Sức mạnh ổ đĩa"); // Drive Strength - PROGMEM Language_Str MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" % trình điều khiển"); // X Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Ghi DAC EEPROM"); // DAC EEPROM Write - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("In tạm dừng"); // PRINT PAUSED - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("Nạp dây nhựa"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("Dỡ dây nhựa"); // unload filament - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Tùy chọn hồi phục:"); // RESUME OPTIONS - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Xả thêm"); // Purge more - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Tiếp tục"); // continue - PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Đầu Phun: "); // Nozzle - PROGMEM Language_Str MSG_RUNOUT_SENSOR_ENABLE = _UxGT("Cảm Biến Hết"); // Runout Sensor - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Sự nhà không thành công"); // Homing failed - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT(" không thành công"); // Probing failed + LSTR MSG_INFO_MIN_TEMP = _UxGT("Nhiệt độ tối thiểu"); // Min Temp + LSTR MSG_INFO_MAX_TEMP = _UxGT("Nhiệt độ tối đa"); // Max temp + LSTR MSG_INFO_PSU = _UxGT("Bộ nguồn"); // PSU + LSTR MSG_DRIVE_STRENGTH = _UxGT("Sức mạnh ổ đĩa"); // Drive Strength + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" % trình điều khiển"); // X Driver % + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Ghi DAC EEPROM"); // DAC EEPROM Write + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("In tạm dừng"); // PRINT PAUSED + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("Nạp dây nhựa"); + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("Dỡ dây nhựa"); // unload filament + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("Tùy chọn hồi phục:"); // RESUME OPTIONS + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Xả thêm"); // Purge more + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Tiếp tục"); // continue + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Đầu Phun: "); // Nozzle + LSTR MSG_RUNOUT_SENSOR_ENABLE = _UxGT("Cảm Biến Hết"); // Runout Sensor + LSTR MSG_KILL_HOMING_FAILED = _UxGT("Sự nhà không thành công"); // Homing failed + LSTR MSG_LCD_PROBING_FAILED = _UxGT(" không thành công"); // Probing failed // // 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("Nhấn nút", "để tiếp tục in")); // Press button to resume print - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Chờ cho sự", "thay đổi dây nhựa", "bắt đầu")); // wait for filament change to start - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Đút dây nhựa vào", "và nhấn nút", "để tiếp tục")); // insert filament and press button to continue // - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nhấn nút", "để làm nóng đầu phun")); // Press button to heat nozzle - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Đầu phun đang nóng lên", "Xin chờ...")); // Nozzle heating Please wait - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Chờ tro", "dây nhựa ra")); // Wait for filament unload - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Chờ tro", "dây nhựa vào")); // Wait for filament load - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Chờ tro", "xả dây nhựa")); // wait for filament purge - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Nhấn nút để kết thúc", "xả dây nhựa")); // Click to finish dây nhựa purge - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Chờ tro in", "tiếp tục...")); // Wait for print to resume + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Nhấn nút", "để tiếp tục in")); // Press button to resume print + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Chờ cho sự", "thay đổi dây nhựa", "bắt đầu")); // wait for filament change to start + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Đút dây nhựa vào", "và nhấn nút", "để tiếp tục")); // insert filament and press button to continue // + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nhấn nút", "để làm nóng đầu phun")); // Press button to heat nozzle + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Đầu phun đang nóng lên", "Xin chờ...")); // Nozzle heating Please wait + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("Chờ tro", "dây nhựa ra")); // Wait for filament unload + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Chờ tro", "dây nhựa vào")); // Wait for filament load + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Chờ tro", "xả dây nhựa")); // wait for filament purge + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Nhấn nút để kết thúc", "xả dây nhựa")); // Click to finish dây nhựa purge + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Chờ tro in", "tiếp tục...")); // Wait for print to resume #else // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Nhấn nút để tiếp tục")); // Click to continue - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Xin chờ...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Chèn và nhấn")); // Insert and Click - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Nhấn để sưởi")); // Click to heat - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Đang sưởi nóng")); // Heating - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Đang dỡ ra...")); // Ejecting - PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Đang nạp...")); // Loading - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Đang xả...")); // Purging - PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Nhấn nút để kết thúc")); // Click to finish - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Đang tiếp tục...")); // Resuming + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Nhấn nút để tiếp tục")); // Click to continue + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Xin chờ...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Chèn và nhấn")); // Insert and Click + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Nhấn để sưởi")); // Click to heat + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Đang sưởi nóng")); // Heating + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Đang dỡ ra...")); // Ejecting + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Đang nạp...")); // Loading + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Đang xả...")); // Purging + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Nhấn nút để kết thúc")); // Click to finish + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Đang tiếp tục...")); // Resuming #endif // LCD_HEIGHT < 4 - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Trình điều khiển TMC"); // TMC drivers - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Dòng điện trình điều khiển"); // Driver current - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Ngưỡng Hỗn Hợp"); // Hybrid threshold - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Vô cảm biến"); // Sensorless homing - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Chế độ từng bước"); // Stepping mode - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("CắtTàngHình được kích hoạt"); // StealthChop enabled + LSTR MSG_TMC_DRIVERS = _UxGT("Trình điều khiển TMC"); // TMC drivers + LSTR MSG_TMC_CURRENT = _UxGT("Dòng điện trình điều khiển"); // Driver current + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Ngưỡng Hỗn Hợp"); // Hybrid threshold + LSTR MSG_TMC_HOMING_THRS = _UxGT("Vô cảm biến"); // Sensorless homing + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Chế độ từng bước"); // Stepping mode + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("CắtTàngHình được kích hoạt"); // StealthChop enabled } diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 35642460fc..2d9dc725f9 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -30,607 +30,607 @@ namespace Language_zh_CN { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 3; - PROGMEM Language_Str LANGUAGE = _UxGT("Simplified Chinese"); + constexpr uint8_t CHARSIZE = 3; + LSTR LANGUAGE = _UxGT("Simplified Chinese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); // " ready." - PROGMEM Language_Str MSG_MARLIN = _UxGT("马林"); - PROGMEM Language_Str MSG_YES = _UxGT("是"); - PROGMEM Language_Str MSG_NO = _UxGT("否"); - PROGMEM Language_Str MSG_BACK = _UxGT("返回"); // ”Back“ - PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("放弃中..."); - PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); // "Card inserted" - PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); // "Card removed" - PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("等待存储器"); - PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("存储器读取错误"); - PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB设备已弹出"); - PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB启动错误"); - PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出"); - PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters - PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块"); - PROGMEM Language_Str MSG_MAIN = _UxGT("主菜单"); // "Main" - PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("高级设置"); - PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("配置"); - PROGMEM Language_Str MSG_RUN_AUTO_FILES = _UxGT("自动开始"); // "Autostart" - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("关闭步进电机"); // "Disable steppers" - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("调试菜单"); // "Debug Menu" - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("进度条测试"); // "Progress Bar Test" - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("自动回原点"); // "Auto home" - 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对齐"); - 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" - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成热床调平"); // "Leveling Done!" - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("设置原点偏移"); // "Set home offsets" - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已启用"); // "Offsets applied" - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("设置原点"); // "Set origin" + LSTR WELCOME_MSG = MACHINE_NAME _UxGT("已就绪."); // " ready." + LSTR MSG_MARLIN = _UxGT("马林"); + LSTR MSG_YES = _UxGT("是"); + LSTR MSG_NO = _UxGT("否"); + LSTR MSG_BACK = _UxGT("返回"); // ”Back“ + LSTR MSG_MEDIA_ABORTING = _UxGT("放弃中..."); + LSTR MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); // "Card inserted" + LSTR MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); // "Card removed" + LSTR MSG_MEDIA_WAITING = _UxGT("等待存储器"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("存储器读取错误"); + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB设备已弹出"); + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB启动错误"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块"); + LSTR MSG_MAIN = _UxGT("主菜单"); // "Main" + LSTR MSG_ADVANCED_SETTINGS = _UxGT("高级设置"); + LSTR MSG_CONFIGURATION = _UxGT("配置"); + LSTR MSG_RUN_AUTO_FILES = _UxGT("自动开始"); // "Autostart" + LSTR MSG_DISABLE_STEPPERS = _UxGT("关闭步进电机"); // "Disable steppers" + LSTR MSG_DEBUG_MENU = _UxGT("调试菜单"); // "Debug Menu" + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("进度条测试"); // "Progress Bar Test" + LSTR MSG_AUTO_HOME = _UxGT("自动回原点"); // "Auto home" + LSTR MSG_AUTO_HOME_X = _UxGT("回X原位"); // "Home X" + LSTR MSG_AUTO_HOME_Y = _UxGT("回Y原位"); // "Home Y" + LSTR MSG_AUTO_HOME_Z = _UxGT("回Z原位"); // "Home Z" + LSTR MSG_AUTO_Z_ALIGN = _UxGT("自动Z对齐"); + LSTR MSG_LEVEL_BED_HOMING = _UxGT("平台调平XYZ归原位"); // "Homing XYZ" + LSTR MSG_LEVEL_BED_WAITING = _UxGT("单击开始热床调平"); // "Click to Begin" + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("下个热床调平点"); // "Next Point" + LSTR MSG_LEVEL_BED_DONE = _UxGT("完成热床调平"); // "Leveling Done!" + LSTR MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" + LSTR MSG_SET_HOME_OFFSETS = _UxGT("设置原点偏移"); // "Set home offsets" + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已启用"); // "Offsets applied" + LSTR MSG_SET_ORIGIN = _UxGT("设置原点"); // "Set origin" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("预热 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("预热 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴 ~"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 热床"); //MSG_PREHEAT_1 " Bed" - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 设置"); //MSG_PREHEAT_1 " conf" + LSTR MSG_PREHEAT_1 = _UxGT("预热 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_2_LABEL" + LSTR MSG_PREHEAT_1_H = _UxGT("预热 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_2_LABEL" + LSTR MSG_PREHEAT_1_END = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_1_END_E = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 喷嘴 ~"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_1_ALL = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 热床"); //MSG_PREHEAT_1 " Bed" + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("预热 ") PREHEAT_1_LABEL _UxGT(" 设置"); //MSG_PREHEAT_1 " conf" - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("预热 $"); // "Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("预热 $ ~"); // "Preheat PREHEAT_2_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("预热 $ 喷嘴"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("预热 $ 喷嘴 ~"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("预热 $ 全部"); //MSG_PREHEAT_1 " All" - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("预热 $ 热床"); //MSG_PREHEAT_1 " Bed" - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("预热 $ 设置"); //MSG_PREHEAT_1 " conf" + LSTR MSG_PREHEAT_M = _UxGT("预热 $"); // "Preheat PREHEAT_2_LABEL" + LSTR MSG_PREHEAT_M_H = _UxGT("预热 $ ~"); // "Preheat PREHEAT_2_LABEL" + LSTR MSG_PREHEAT_M_END = _UxGT("预热 $ 喷嘴"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_M_END_E = _UxGT("预热 $ 喷嘴 ~"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_M_ALL = _UxGT("预热 $ 全部"); //MSG_PREHEAT_1 " All" + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("预热 $ 热床"); //MSG_PREHEAT_1 " Bed" + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("预热 $ 设置"); //MSG_PREHEAT_1 " conf" #endif - PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("预热自定义"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降温"); // "Cooldown" - PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("切割频率"); - PROGMEM Language_Str MSG_LASER_MENU = _UxGT("激光控制"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("激光电源"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主轴控制"); - PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("主轴电源"); - PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("主轴反转"); - 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" - PROGMEM Language_Str MSG_RETRACT = _UxGT("回抽"); // "Retract" - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移动轴"); // "Move axis" - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("调平热床"); // "Bed leveling" - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("调平热床"); // "Level bed" - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("调平边角"); // "Bed Tramming" - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下个边角"); // "Next corner" - PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("网格编辑器"); - PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("编辑网格"); // "Edit Mesh" - PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("网格编辑已停止"); // "Mesh Editing Stopped" - PROGMEM Language_Str MSG_PROBING_POINT = _UxGT("探测点"); - PROGMEM Language_Str MSG_MESH_X = _UxGT("索引X"); - PROGMEM Language_Str MSG_MESH_Y = _UxGT("索引Y"); - PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z 值"); - PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("定制命令"); // "Custom Commands" - PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48探测"); - PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48点"); - PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("M48偏差"); - PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX模式"); - PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("工具偏移量"); - PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("自动停靠"); - PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("复制"); - PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("镜像复制"); - PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("完全控制"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("第二喷头是X"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("第二喷头是Y"); - PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("第二喷头是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("倾斜點"); - 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" - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("移除并测量热床"); // "Remove & measure bed" - 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_BED_TEMP_CUSTOM = _UxGT("热床温度"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("热端温度"); // "Hotend Temp" - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("热端温度"); - 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" - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("完成编辑网格"); // "Done Editing Mesh" - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("创设客户网格"); // "Build Custom Mesh" - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("创设网格"); // "Build Mesh" + LSTR MSG_PREHEAT_CUSTOM = _UxGT("预热自定义"); + LSTR MSG_COOLDOWN = _UxGT("降温"); // "Cooldown" + LSTR MSG_CUTTER_FREQUENCY = _UxGT("切割频率"); + LSTR MSG_LASER_MENU = _UxGT("激光控制"); + LSTR MSG_LASER_POWER = _UxGT("激光电源"); + LSTR MSG_SPINDLE_MENU = _UxGT("主轴控制"); + LSTR MSG_SPINDLE_POWER = _UxGT("主轴电源"); + LSTR MSG_SPINDLE_REVERSE = _UxGT("主轴反转"); + LSTR MSG_SWITCH_PS_ON = _UxGT("电源打开"); // "Switch power on" + LSTR MSG_SWITCH_PS_OFF = _UxGT("电源关闭"); // "Switch power off" + LSTR MSG_EXTRUDE = _UxGT("挤出"); // "Extrude" + LSTR MSG_RETRACT = _UxGT("回抽"); // "Retract" + LSTR MSG_MOVE_AXIS = _UxGT("移动轴"); // "Move axis" + LSTR MSG_BED_LEVELING = _UxGT("调平热床"); // "Bed leveling" + LSTR MSG_LEVEL_BED = _UxGT("调平热床"); // "Level bed" + LSTR MSG_BED_TRAMMING = _UxGT("调平边角"); // "Bed Tramming" + LSTR MSG_NEXT_CORNER = _UxGT("下个边角"); // "Next corner" + LSTR MSG_MESH_EDITOR = _UxGT("网格编辑器"); + LSTR MSG_EDIT_MESH = _UxGT("编辑网格"); // "Edit Mesh" + LSTR MSG_EDITING_STOPPED = _UxGT("网格编辑已停止"); // "Mesh Editing Stopped" + LSTR MSG_PROBING_POINT = _UxGT("探测点"); + LSTR MSG_MESH_X = _UxGT("索引X"); + LSTR MSG_MESH_Y = _UxGT("索引Y"); + LSTR MSG_MESH_EDIT_Z = _UxGT("Z 值"); + LSTR MSG_CUSTOM_COMMANDS = _UxGT("定制命令"); // "Custom Commands" + LSTR MSG_M48_TEST = _UxGT("M48探测"); + LSTR MSG_M48_POINT = _UxGT("M48点"); + LSTR MSG_M48_DEVIATION = _UxGT("M48偏差"); + LSTR MSG_IDEX_MENU = _UxGT("IDEX模式"); + LSTR MSG_OFFSETS_MENU = _UxGT("工具偏移量"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("自动停靠"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("复制"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("镜像复制"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("完全控制"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("第二喷头是X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("第二喷头是Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("第二喷头是Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("执行G29"); // "Doing G29" + LSTR MSG_UBL_TOOLS = _UxGT("UBL工具"); // "UBL Tools" + LSTR MSG_UBL_LEVEL_BED = _UxGT("统一热床调平(UBL)"); // "Unified Bed Leveling" + LSTR MSG_LCD_TILTING_MESH = _UxGT("倾斜點"); + LSTR MSG_UBL_MANUAL_MESH = _UxGT("手工创设网格"); // "Manually Build Mesh" + LSTR MSG_UBL_BC_INSERT = _UxGT("放置垫片并测量"); // "Place shim & measure" + LSTR MSG_UBL_BC_INSERT2 = _UxGT("测量"); // "Measure" + LSTR MSG_UBL_BC_REMOVE = _UxGT("移除并测量热床"); // "Remove & measure bed" + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("移动到下一个"); // "Moving to next" + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("激活UBL"); // "Activate UBL" + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("关闭UBL"); // "Deactivate UBL" + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("热床温度"); // "Bed Temp" + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("热床温度"); + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("热端温度"); // "Hotend Temp" + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("热端温度"); + LSTR MSG_UBL_MESH_EDIT = _UxGT("网格编辑"); // "Mesh Edit" + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("编辑客户网格"); // "Edit Custom Mesh" + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("细调网格"); // "Fine Tuning Mesh" + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("完成编辑网格"); // "Done Editing Mesh" + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("创设客户网格"); // "Build Custom Mesh" + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("创设网格"); // "Build Mesh" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("创设 $ 网格"); // "Build PREHEAT_1_LABEL Mesh" - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("批准 $ 网格"); // "Validate PREHEAT_1_LABEL Mesh" + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("创设 $ 网格"); // "Build PREHEAT_1_LABEL Mesh" + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("批准 $ 网格"); // "Validate PREHEAT_1_LABEL Mesh" #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("创设冷网格"); // "Build Cold Mesh" - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("调整网格高度"); // "Adjust Mesh Height" - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("高度合计"); // "Height Amount" - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("批准网格"); // "Validate Mesh" - PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("批准客户网格"); // "Validate Custom Mesh" - PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26加热热床"); - PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26加热喷嘴"); - PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("手动填装中..."); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("固定距离填装"); - PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("填装完成"); - PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26已取消"); - PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("离开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" - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("格子网格调平"); // "Grid Mesh Leveling" - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("调平网格"); // "Level Mesh" - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("边点"); // "Side Points" - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("图类型"); // "Map Type" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("输出网格图"); // "Output Mesh Map" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("输出到主机"); // "Output for Host" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("输出到CSV"); // "Output for CSV" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("输出到备份"); // "Off Printer Backup" - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("输出UBL信息"); // "Output UBL Info" - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("填充合计"); // "Fill-in Amount" - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("手工填充"); // "Manual Fill-in" - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("聪明填充"); // "Smart Fill-in" - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("填充网格"); // "Fill-in Mesh" - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("作废所有的"); // "Invalidate All" - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("作废最近的"); // "Invalidate Closest" - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("细调所有的"); // "Fine Tune All" - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("细调最近的"); // "Fine Tune Closest" - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("网格存储"); // "Mesh Storage" - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("存储槽"); // "Memory Slot" - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("装载热床网格"); // "Load Bed Mesh" - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("保存热床网格"); // "Save Bed Mesh" - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("网格 %i 已装载"); // "Mesh %i loaded" - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("网格 %i 已保存"); // "Mesh %i saved" - 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偏移量: "); - 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. 创设冷网格"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. 聪明填充"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. 批准网格"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. 细调所有的"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. 批准网格"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. 细调所有的"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. 保存热床网格"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("创设冷网格"); // "Build Cold Mesh" + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("调整网格高度"); // "Adjust Mesh Height" + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("高度合计"); // "Height Amount" + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("批准网格"); // "Validate Mesh" + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("批准客户网格"); // "Validate Custom Mesh" + LSTR MSG_G26_HEATING_BED = _UxGT("G26加热热床"); + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26加热喷嘴"); + LSTR MSG_G26_MANUAL_PRIME = _UxGT("手动填装中..."); + LSTR MSG_G26_FIXED_LENGTH = _UxGT("固定距离填装"); + LSTR MSG_G26_PRIME_DONE = _UxGT("填装完成"); + LSTR MSG_G26_CANCELED = _UxGT("G26已取消"); + LSTR MSG_G26_LEAVING = _UxGT("离开G26"); + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("继续热床网格"); // "Continue Bed Mesh" + LSTR MSG_UBL_MESH_LEVELING = _UxGT("网格调平"); // "Mesh Leveling" + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("三点调平"); // "3-Point Leveling" + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("格子网格调平"); // "Grid Mesh Leveling" + LSTR MSG_UBL_MESH_LEVEL = _UxGT("调平网格"); // "Level Mesh" + LSTR MSG_UBL_SIDE_POINTS = _UxGT("边点"); // "Side Points" + LSTR MSG_UBL_MAP_TYPE = _UxGT("图类型"); // "Map Type" + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("输出网格图"); // "Output Mesh Map" + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("输出到主机"); // "Output for Host" + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("输出到CSV"); // "Output for CSV" + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("输出到备份"); // "Off Printer Backup" + LSTR MSG_UBL_INFO_UBL = _UxGT("输出UBL信息"); // "Output UBL Info" + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("填充合计"); // "Fill-in Amount" + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("手工填充"); // "Manual Fill-in" + LSTR MSG_UBL_SMART_FILLIN = _UxGT("聪明填充"); // "Smart Fill-in" + LSTR MSG_UBL_FILLIN_MESH = _UxGT("填充网格"); // "Fill-in Mesh" + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("作废所有的"); // "Invalidate All" + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("作废最近的"); // "Invalidate Closest" + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("细调所有的"); // "Fine Tune All" + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("细调最近的"); // "Fine Tune Closest" + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("网格存储"); // "Mesh Storage" + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("存储槽"); // "Memory Slot" + LSTR MSG_UBL_LOAD_MESH = _UxGT("装载热床网格"); // "Load Bed Mesh" + LSTR MSG_UBL_SAVE_MESH = _UxGT("保存热床网格"); // "Save Bed Mesh" + LSTR MSG_MESH_LOADED = _UxGT("网格 %i 已装载"); // "Mesh %i loaded" + LSTR MSG_MESH_SAVED = _UxGT("网格 %i 已保存"); // "Mesh %i saved" + LSTR MSG_UBL_NO_STORAGE = _UxGT("没有存储"); // "No storage" + LSTR MSG_UBL_SAVE_ERROR = _UxGT("错误: UBL保存"); // "Err: UBL Save" + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("错误: UBL还原"); // "Err: UBL Restore" + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z偏移量: "); + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z偏移已停止"); // "Z-Offset Stopped" + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("一步步UBL"); // "Step-By-Step UBL" + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. 创设冷网格"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. 聪明填充"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. 批准网格"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. 细调所有的"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. 批准网格"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. 细调所有的"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. 保存热床网格"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED控制"); // "LED Control") - PROGMEM Language_Str MSG_LEDS = _UxGT("灯"); // "Lights") - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("灯预置"); // "Light Presets") - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("红"); // "Red") - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("橙"); // "Orange") - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("黄"); // "Yellow") - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("绿"); // "Green") - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("蓝"); // "Blue") - 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_CUSTOM_LEDS = _UxGT("定制灯"); // "Custom Lights") - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("红饱和度"); // "Red Intensity") - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("绿饱和度"); // "Green Intensity") - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("蓝饱和度"); // "Blue Intensity") - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("白饱和度"); // "White Intensity") - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("亮度"); // "Brightness") + LSTR MSG_LED_CONTROL = _UxGT("LED控制"); // "LED Control") + LSTR MSG_LEDS = _UxGT("灯"); // "Lights") + LSTR MSG_LED_PRESETS = _UxGT("灯预置"); // "Light Presets") + LSTR MSG_SET_LEDS_RED = _UxGT("红"); // "Red") + LSTR MSG_SET_LEDS_ORANGE = _UxGT("橙"); // "Orange") + LSTR MSG_SET_LEDS_YELLOW = _UxGT("黄"); // "Yellow") + LSTR MSG_SET_LEDS_GREEN = _UxGT("绿"); // "Green") + LSTR MSG_SET_LEDS_BLUE = _UxGT("蓝"); // "Blue") + LSTR MSG_SET_LEDS_INDIGO = _UxGT("青"); // "Indigo") + LSTR MSG_SET_LEDS_VIOLET = _UxGT("紫"); // "Violet") + LSTR MSG_SET_LEDS_WHITE = _UxGT("白"); // "White") + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("缺省"); // "Default") + LSTR MSG_CUSTOM_LEDS = _UxGT("定制灯"); // "Custom Lights") + LSTR MSG_INTENSITY_R = _UxGT("红饱和度"); // "Red Intensity") + LSTR MSG_INTENSITY_G = _UxGT("绿饱和度"); // "Green Intensity") + LSTR MSG_INTENSITY_B = _UxGT("蓝饱和度"); // "Blue Intensity") + LSTR MSG_INTENSITY_W = _UxGT("白饱和度"); // "White Intensity") + LSTR MSG_LED_BRIGHTNESS = _UxGT("亮度"); // "Brightness") - PROGMEM Language_Str MSG_MOVING = _UxGT("移动..."); // "Moving...") - PROGMEM Language_Str MSG_FREE_XY = _UxGT("释放 XY"); // "Free XY") - PROGMEM Language_Str MSG_MOVE_X = _UxGT("移动X"); // "Move X" - 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("挤出机 *"); // "Extruder" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); - PROGMEM Language_Str MSG_MOVE_N_MM = _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" - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); // "Move 10mm" - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); // "Move 100mm" - PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); // "Speed" - PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); // "Bed Z" - PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); // "Nozzle" 噴嘴 - PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("喷嘴 ~"); // "Nozzle" 噴嘴 - PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("喷嘴已停靠"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("喷嘴待命中"); - PROGMEM Language_Str MSG_BED = _UxGT("热床"); // "Bed" - PROGMEM Language_Str MSG_CHAMBER = _UxGT("机箱壳"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("风扇速率"); // "Fan speed" - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("风扇速率 ~"); // "Fan speed" - PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("存储的风扇 ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("额外风扇速率"); // "Extra fan speed" - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("额外风扇速率 ~"); // "Extra fan speed" - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("控制器风扇"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("空闲速度"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("自动模式"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("工作速度"); - PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("空闲周期"); - PROGMEM Language_Str MSG_FLOW = _UxGT("挤出速率"); // "Flow" - PROGMEM Language_Str MSG_FLOW_N = _UxGT("挤出速率 ~"); // "Flow" - PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); // "Control" - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" - 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_PID_AUTOTUNE = _UxGT("自动PID"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("自动PID *"); - PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID调整完成"); - PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败. 坏的挤出机"); - PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败. 温度太高"); - PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("自动调失败! 超时"); - PROGMEM Language_Str MSG_SELECT = _UxGT("选择"); // "Select" - PROGMEM Language_Str MSG_SELECT_E = _UxGT("选择 *"); - PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); // "Accel" acceleration - PROGMEM Language_Str MSG_JERK = _UxGT("抖动速率"); // "Jerk" - PROGMEM Language_Str MSG_VA_JERK = _UxGT("轴抖动速率") LCD_STR_A; // "Va-jerk" - 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_VI_JERK = _UxGT("轴抖动速率") LCD_STR_I; // "Vi-jerk" - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("轴抖动速率") LCD_STR_J; // "Vj-jerk" - PROGMEM Language_Str MSG_VK_JERK = _UxGT("轴抖动速率") LCD_STR_K; // "Vk-jerk" - PROGMEM Language_Str MSG_VE_JERK = _UxGT("挤出机抖动速率"); // "Ve-jerk" - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("接点差"); - 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; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("最大进料速率") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("最大进料速率") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("最大进料速率") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("最大进料速率") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("最大进料速率") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大进料速率 *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("最小进料速率"); // "Vmin" min_feedrate_mm_s - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移动速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大打印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_B = _UxGT("最大打印加速度") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("最大打印加速度") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("最大打印加速度") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("最大打印加速度") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("最大打印加速度") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("最大打印加速度") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大打印加速度 *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("收进加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非打印移动加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves - PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("频率最大"); - PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("进给速度"); - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("轴步数/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" 步数/mm"); // "Asteps/mm" - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" 步数/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" 步数/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" 步数/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" 步数/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" 步数/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("E 步数/mm"); // "Esteps/mm" - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* 步数/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("温度"); // "Temperature" - PROGMEM Language_Str MSG_MOTION = _UxGT("运动"); // "Motion" - PROGMEM Language_Str MSG_FILAMENT = _UxGT("料丝"); // "Filament" menu_advanced_filament - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E 限制 在 mm") SUPERSCRIPT_THREE; - PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E 限制 *"); - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("丝料直径"); // "Fil. Dia." - 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_INIT_EEPROM = _UxGT("初始化设置"); // "Initialize EEPROM" - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC 错误"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index 错误"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version 错误"); - PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("设置已保存"); - PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("存储器更新"); - PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("复位打印机"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("刷新"); - 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_POWER_MONITOR = _UxGT("电源监控"); - PROGMEM Language_Str MSG_CURRENT = _UxGT("电流"); - PROGMEM Language_Str MSG_VOLTAGE = _UxGT("电压"); - PROGMEM Language_Str MSG_POWER = _UxGT("功率"); - PROGMEM Language_Str MSG_START_PRINT = _UxGT("开始打印"); - PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("下一个"); - PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("初始"); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("停止"); - PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("打印"); - PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("复位"); - PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("忽略"); - PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("取消"); - PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("完成"); - PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("返回"); - PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("继续"); - PROGMEM Language_Str MSG_PAUSING = _UxGT("暂停中..."); - 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("打印物体"); - PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("取消物体"); - PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("取消物体 ="); - PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("中断恢复"); - 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("打印中..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("已取消打印"); // "Print aborted" - PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("打印已完成"); - PROGMEM Language_Str MSG_NO_MOVE = _UxGT("无移动"); // "No move." - PROGMEM Language_Str MSG_KILLED = _UxGT("已杀掉"); // "KILLED. " - PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回抽长度mm"); // "Retract mm" retract_length, retract length (positive mm) - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("换手回抽长度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回抽速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回抽恢复长度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("换手回抽恢复长度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回抽恢复后进料速率mm/s"); // "Unretract 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("自动抽回"); // "Auto-Retract" autoretract_enabled, - PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("交换长度"); - PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("额外的交换"); - PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("清洗长度"); - PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("换工具"); - PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z抬起"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("进给速度"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("回抽速度"); - PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("停靠头"); - PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("恢复速度"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("风扇速度"); - PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("风扇时间"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("自动开"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("自动关"); - PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("工具迁移"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("自动迁移"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("上一个挤出机"); - PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("迁移至 *"); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("更换丝料"); // "Change filament" - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更换丝料 *"); // "Change filament" - PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("装载丝料"); // "Load filament" - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("装载丝料 *"); // "Load filament" - 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_CHANGE_MEDIA = _UxGT("更换存储卡"); // "Change SD card" - PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("释放存储卡"); - 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("自检"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("重置"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("装载"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW模式"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V模式"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD模式"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("模式保存"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("设置BLTouch为5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("设置BLTouch为OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("报告开漏"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("危险: 错误的设置将引起损坏! 是否继续?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("初始化TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z偏移量测试"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("保存"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("部署TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("部署Z探针"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("收好Z探针"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("归位 %s%s%s 先"); // "Home ... first" - PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("探针偏移量"); - PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("探针X偏移"); - PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("探针Y偏移"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("探针Z偏移"); // "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("总计"); - 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("错误:冗余温度"); // "Err: REDUNDANT TEMP" - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("温控失控"); // "THERMAL RUNAWAY" - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("热床热量失控"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("机箱热量失控"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("错误:最高温度"); // "Err: MAXTEMP" - PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("错误:最低温度"); // "Err: MINTEMP" - PROGMEM Language_Str MSG_HALTED = _UxGT("打印停机"); // "PRINTER HALTED" - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("请重置"); // "Please reset" - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only - 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("冷却中 ..."); - PROGMEM Language_Str MSG_BED_HEATING = _UxGT("加热热床中 ..."); // "Bed Heating..." - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("热床冷却中 ..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("机箱加热中 ..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("机箱冷却中 ..."); - 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" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校准Z"); // "Calibrate Z" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校准中心"); // "Calibrate Center" - 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" - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("关于打印机"); // "About Printer" - 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_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_BAUDRATE = _UxGT("波特率"); // "Baud" - PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("协议"); // "Protocol" - PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("监控温度失控:关"); - PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("监控温度失控:开"); - PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("热端空闲超时"); + LSTR MSG_MOVING = _UxGT("移动..."); // "Moving...") + LSTR MSG_FREE_XY = _UxGT("释放 XY"); // "Free XY") + LSTR MSG_MOVE_X = _UxGT("移动X"); // "Move X" + LSTR MSG_MOVE_Y = _UxGT("移动Y"); // "Move Y" + LSTR MSG_MOVE_Z = _UxGT("移动Z"); // "Move Z" + LSTR MSG_MOVE_E = _UxGT("挤出机"); // "Extruder" + LSTR MSG_MOVE_EN = _UxGT("挤出机 *"); // "Extruder" + LSTR MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); + LSTR MSG_MOVE_N_MM = _UxGT("移动 %s mm"); // "Move 0.025mm" + LSTR MSG_MOVE_01MM = _UxGT("移动 0.1 mm"); // "Move 0.1mm" + LSTR MSG_MOVE_1MM = _UxGT("移动 1 mm"); // "Move 1mm" + LSTR MSG_MOVE_10MM = _UxGT("移动 10 mm"); // "Move 10mm" + LSTR MSG_MOVE_100MM = _UxGT("移动 100 mm"); // "Move 100mm" + LSTR MSG_SPEED = _UxGT("速率"); // "Speed" + LSTR MSG_BED_Z = _UxGT("热床Z"); // "Bed Z" + LSTR MSG_NOZZLE = _UxGT("喷嘴"); // "Nozzle" 噴嘴 + LSTR MSG_NOZZLE_N = _UxGT("喷嘴 ~"); // "Nozzle" 噴嘴 + LSTR MSG_NOZZLE_PARKED = _UxGT("喷嘴已停靠"); + LSTR MSG_NOZZLE_STANDBY = _UxGT("喷嘴待命中"); + LSTR MSG_BED = _UxGT("热床"); // "Bed" + LSTR MSG_CHAMBER = _UxGT("机箱壳"); + LSTR MSG_FAN_SPEED = _UxGT("风扇速率"); // "Fan speed" + LSTR MSG_FAN_SPEED_N = _UxGT("风扇速率 ~"); // "Fan speed" + LSTR MSG_STORED_FAN_N = _UxGT("存储的风扇 ~"); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("额外风扇速率"); // "Extra fan speed" + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("额外风扇速率 ~"); // "Extra fan speed" + LSTR MSG_CONTROLLER_FAN = _UxGT("控制器风扇"); + LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("空闲速度"); + LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("自动模式"); + LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("工作速度"); + LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("空闲周期"); + LSTR MSG_FLOW = _UxGT("挤出速率"); // "Flow" + LSTR MSG_FLOW_N = _UxGT("挤出速率 ~"); // "Flow" + LSTR MSG_CONTROL = _UxGT("控制"); // "Control" + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" 最大"); // " " LCD_STR_THERMOMETER " Max" + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 因数"); // " " LCD_STR_THERMOMETER " Fact" + LSTR MSG_AUTOTEMP = _UxGT("自动控温"); // "Autotemp" + LSTR MSG_LCD_ON = _UxGT("开"); // "On" + LSTR MSG_LCD_OFF = _UxGT("关"); // "Off" + LSTR MSG_PID_AUTOTUNE = _UxGT("自动PID"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("自动PID *"); + LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID调整完成"); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("自动调失败. 坏的挤出机"); + LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("自动调失败. 温度太高"); + LSTR MSG_PID_TIMEOUT = _UxGT("自动调失败! 超时"); + LSTR MSG_SELECT = _UxGT("选择"); // "Select" + LSTR MSG_SELECT_E = _UxGT("选择 *"); + LSTR MSG_ACC = _UxGT("加速度"); // "Accel" acceleration + LSTR MSG_JERK = _UxGT("抖动速率"); // "Jerk" + LSTR MSG_VA_JERK = _UxGT("轴抖动速率") LCD_STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("轴抖动速率") LCD_STR_B; // "Vb-jerk" + LSTR MSG_VC_JERK = _UxGT("轴抖动速率") LCD_STR_C; // "Vc-jerk" + LSTR MSG_VI_JERK = _UxGT("轴抖动速率") LCD_STR_I; // "Vi-jerk" + LSTR MSG_VJ_JERK = _UxGT("轴抖动速率") LCD_STR_J; // "Vj-jerk" + LSTR MSG_VK_JERK = _UxGT("轴抖动速率") LCD_STR_K; // "Vk-jerk" + LSTR MSG_VE_JERK = _UxGT("挤出机抖动速率"); // "Ve-jerk" + LSTR MSG_JUNCTION_DEVIATION = _UxGT("接点差"); + LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" + LSTR MSG_VMAX_A = _UxGT("最大进料速率") LCD_STR_A; // "Vmax " max_feedrate_mm_s + LSTR MSG_VMAX_B = _UxGT("最大进料速率") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("最大进料速率") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("最大进料速率") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("最大进料速率") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("最大进料速率") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("最大进料速率") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("最大进料速率 *"); + LSTR MSG_VMIN = _UxGT("最小进料速率"); // "Vmin" min_feedrate_mm_s + LSTR MSG_VTRAV_MIN = _UxGT("最小移动速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move + LSTR MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" + LSTR MSG_AMAX_A = _UxGT("最大打印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + LSTR MSG_AMAX_B = _UxGT("最大打印加速度") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("最大打印加速度") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("最大打印加速度") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("最大打印加速度") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("最大打印加速度") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("最大打印加速度") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("最大打印加速度 *"); + LSTR MSG_A_RETRACT = _UxGT("收进加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts + LSTR MSG_A_TRAVEL = _UxGT("非打印移动加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves + LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("频率最大"); + LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("进给速度"); + LSTR MSG_STEPS_PER_MM = _UxGT("轴步数/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" 步数/mm"); // "Asteps/mm" + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" 步数/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" 步数/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" 步数/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" 步数/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" 步数/mm"); + LSTR MSG_E_STEPS = _UxGT("E 步数/mm"); // "Esteps/mm" + LSTR MSG_EN_STEPS = _UxGT("* 步数/mm"); + LSTR MSG_TEMPERATURE = _UxGT("温度"); // "Temperature" + LSTR MSG_MOTION = _UxGT("运动"); // "Motion" + LSTR MSG_FILAMENT = _UxGT("料丝"); // "Filament" menu_advanced_filament + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E 在 mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled + LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E 限制 在 mm") SUPERSCRIPT_THREE; + LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E 限制 *"); + LSTR MSG_FILAMENT_DIAM = _UxGT("丝料直径"); // "Fil. Dia." + LSTR MSG_FILAMENT_DIAM_E = _UxGT("丝料直径 *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("卸载 mm"); // "Unload mm" + LSTR MSG_FILAMENT_LOAD = _UxGT("装载 mm"); // "Load mm" + LSTR MSG_ADVANCE_K = _UxGT("Advance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); + LSTR MSG_CONTRAST = _UxGT("LCD对比度"); // "LCD contrast" + LSTR MSG_STORE_EEPROM = _UxGT("保存设置"); // "Store memory" + LSTR MSG_LOAD_EEPROM = _UxGT("装载设置"); // "Load memory" + LSTR MSG_RESTORE_DEFAULTS = _UxGT("恢复安全值"); // "Restore Defaults" + LSTR MSG_INIT_EEPROM = _UxGT("初始化设置"); // "Initialize EEPROM" + LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC 错误"); + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index 错误"); + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version 错误"); + LSTR MSG_SETTINGS_STORED = _UxGT("设置已保存"); + LSTR MSG_MEDIA_UPDATE = _UxGT("存储器更新"); + LSTR MSG_RESET_PRINTER = _UxGT("复位打印机"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("刷新"); + LSTR MSG_INFO_SCREEN = _UxGT("信息屏"); // "Info screen" + LSTR MSG_PREPARE = _UxGT("准备"); // "Prepare" + LSTR MSG_TUNE = _UxGT("调整"); // "Tune" + LSTR MSG_POWER_MONITOR = _UxGT("电源监控"); + LSTR MSG_CURRENT = _UxGT("电流"); + LSTR MSG_VOLTAGE = _UxGT("电压"); + LSTR MSG_POWER = _UxGT("功率"); + LSTR MSG_START_PRINT = _UxGT("开始打印"); + LSTR MSG_BUTTON_NEXT = _UxGT("下一个"); + LSTR MSG_BUTTON_INIT = _UxGT("初始"); + LSTR MSG_BUTTON_STOP = _UxGT("停止"); + LSTR MSG_BUTTON_PRINT = _UxGT("打印"); + LSTR MSG_BUTTON_RESET = _UxGT("复位"); + LSTR MSG_BUTTON_IGNORE = _UxGT("忽略"); + LSTR MSG_BUTTON_CANCEL = _UxGT("取消"); + LSTR MSG_BUTTON_DONE = _UxGT("完成"); + LSTR MSG_BUTTON_BACK = _UxGT("返回"); + LSTR MSG_BUTTON_PROCEED = _UxGT("继续"); + LSTR MSG_PAUSING = _UxGT("暂停中..."); + LSTR MSG_PAUSE_PRINT = _UxGT("暂停打印"); // "Pause print" + LSTR MSG_RESUME_PRINT = _UxGT("恢复打印"); // "Resume print" + LSTR MSG_STOP_PRINT = _UxGT("停止打印"); // "Stop print" + LSTR MSG_PRINTING_OBJECT = _UxGT("打印物体"); + LSTR MSG_CANCEL_OBJECT = _UxGT("取消物体"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("取消物体 ="); + LSTR MSG_OUTAGE_RECOVERY = _UxGT("中断恢复"); + LSTR MSG_MEDIA_MENU = _UxGT("从存储卡上打印"); // "Print from SD" + LSTR MSG_NO_MEDIA = _UxGT("无存储卡"); // "No SD card" + LSTR MSG_DWELL = _UxGT("休眠中 ..."); // "Sleep..." + LSTR MSG_USERWAIT = _UxGT("点击继续 ..."); // "Click to resume..." + LSTR MSG_PRINT_PAUSED = _UxGT("暫停打印"); // "Print paused" + LSTR MSG_PRINTING = _UxGT("打印中..."); + LSTR MSG_PRINT_ABORTED = _UxGT("已取消打印"); // "Print aborted" + LSTR MSG_PRINT_DONE = _UxGT("打印已完成"); + LSTR MSG_NO_MOVE = _UxGT("无移动"); // "No move." + LSTR MSG_KILLED = _UxGT("已杀掉"); // "KILLED. " + LSTR MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " + LSTR MSG_CONTROL_RETRACT = _UxGT("回抽长度mm"); // "Retract mm" retract_length, retract length (positive mm) + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("换手回抽长度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change + LSTR MSG_CONTROL_RETRACTF = _UxGT("回抽速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("回抽恢复长度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("换手回抽恢复长度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回抽恢复后进料速率mm/s"); // "Unretract V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); // "S UnRet V" + LSTR MSG_AUTORETRACT = _UxGT("自动抽回"); // "Auto-Retract" autoretract_enabled, + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("交换长度"); + LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("额外的交换"); + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("清洗长度"); + LSTR MSG_TOOL_CHANGE = _UxGT("换工具"); + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z抬起"); + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("进给速度"); + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("回抽速度"); + LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("停靠头"); + LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("恢复速度"); + LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("风扇速度"); + LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("风扇时间"); + LSTR MSG_TOOL_MIGRATION_ON = _UxGT("自动开"); + LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("自动关"); + LSTR MSG_TOOL_MIGRATION = _UxGT("工具迁移"); + LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("自动迁移"); + LSTR MSG_TOOL_MIGRATION_END = _UxGT("上一个挤出机"); + LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("迁移至 *"); + LSTR MSG_FILAMENTCHANGE = _UxGT("更换丝料"); // "Change filament" + LSTR MSG_FILAMENTCHANGE_E = _UxGT("更换丝料 *"); // "Change filament" + LSTR MSG_FILAMENTLOAD = _UxGT("装载丝料"); // "Load filament" + LSTR MSG_FILAMENTLOAD_E = _UxGT("装载丝料 *"); // "Load filament" + LSTR MSG_FILAMENTUNLOAD = _UxGT("卸载丝料"); // "Unload filament" + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("卸载丝料 *"); // "Unload filament" + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("卸载全部"); // "Unload All" + LSTR MSG_ATTACH_MEDIA = _UxGT("初始化存储卡"); // "Init. SD card" + LSTR MSG_CHANGE_MEDIA = _UxGT("更换存储卡"); // "Change SD card" + LSTR MSG_RELEASE_MEDIA = _UxGT("释放存储卡"); + LSTR MSG_ZPROBE_OUT = _UxGT("Z探针在热床之外"); // "Z probe out. bed" Z probe is not within the physical limits + LSTR MSG_SKEW_FACTOR = _UxGT("偏斜因数"); // "Skew Factor" + LSTR MSG_BLTOUCH = _UxGT("BLTouch"); // "BLTouch" + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("自检"); + LSTR MSG_BLTOUCH_RESET = _UxGT("重置"); + LSTR MSG_BLTOUCH_STOW = _UxGT("装载"); + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("部署"); + LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW模式"); + LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V模式"); + LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD模式"); + LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("模式保存"); + LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("设置BLTouch为5V"); + LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("设置BLTouch为OD"); + LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("报告开漏"); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("危险: 错误的设置将引起损坏! 是否继续?"); + LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + LSTR MSG_TOUCHMI_INIT = _UxGT("初始化TouchMI"); + LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z偏移量测试"); + LSTR MSG_TOUCHMI_SAVE = _UxGT("保存"); + LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("部署TouchMI"); + LSTR MSG_MANUAL_DEPLOY = _UxGT("部署Z探针"); + LSTR MSG_MANUAL_STOW = _UxGT("收好Z探针"); + LSTR MSG_HOME_FIRST = _UxGT("归位 %s%s%s 先"); // "Home ... first" + LSTR MSG_ZPROBE_OFFSETS = _UxGT("探针偏移量"); + LSTR MSG_ZPROBE_XOFFSET = _UxGT("探针X偏移"); + LSTR MSG_ZPROBE_YOFFSET = _UxGT("探针Y偏移"); + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("探针Z偏移"); // "Z Offset" + LSTR MSG_BABYSTEP_X = _UxGT("微量调整X轴"); // "Babystep X" lcd_babystep_x, Babystepping enables the user to control the axis in tiny amounts + LSTR MSG_BABYSTEP_Y = _UxGT("微量调整Y轴"); // "Babystep Y" + LSTR MSG_BABYSTEP_Z = _UxGT("微量调整Z轴"); // "Babystep Z" + LSTR MSG_BABYSTEP_TOTAL = _UxGT("总计"); + LSTR MSG_ENDSTOP_ABORT = _UxGT("挡块终止"); // "Endstop abort" + LSTR MSG_HEATING_FAILED_LCD = _UxGT("加热失败"); // "Heating failed" + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("错误:冗余温度"); // "Err: REDUNDANT TEMP" + LSTR MSG_THERMAL_RUNAWAY = _UxGT("温控失控"); // "THERMAL RUNAWAY" + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("热床热量失控"); + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("机箱热量失控"); + LSTR MSG_ERR_MAXTEMP = _UxGT("错误:最高温度"); // "Err: MAXTEMP" + LSTR MSG_ERR_MINTEMP = _UxGT("错误:最低温度"); // "Err: MINTEMP" + LSTR MSG_HALTED = _UxGT("打印停机"); // "PRINTER HALTED" + LSTR MSG_PLEASE_RESET = _UxGT("请重置"); // "Please reset" + LSTR MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only + LSTR MSG_SHORT_HOUR = _UxGT("时"); // "h" // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("分"); // "m" // One character only + LSTR MSG_HEATING = _UxGT("加热中 ..."); // "Heating..." + LSTR MSG_COOLING = _UxGT("冷却中 ..."); + LSTR MSG_BED_HEATING = _UxGT("加热热床中 ..."); // "Bed Heating..." + LSTR MSG_BED_COOLING = _UxGT("热床冷却中 ..."); + LSTR MSG_CHAMBER_HEATING = _UxGT("机箱加热中 ..."); + LSTR MSG_CHAMBER_COOLING = _UxGT("机箱冷却中 ..."); + LSTR MSG_DELTA_CALIBRATE = _UxGT("⊿校准"); // "Delta Calibration" + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("⊿校准X"); // "Calibrate X" + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("⊿校准Y"); // "Calibrate Y" + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校准Z"); // "Calibrate Z" + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校准中心"); // "Calibrate Center" + LSTR MSG_DELTA_SETTINGS = _UxGT("⊿设置"); // "Delta Settings" + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("⊿自动校准"); // "Auto Calibration" + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("设置⊿高度"); // "Set Delta Height" + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("探针Z偏移量"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("⊿斜柱"); // "Diag Rod" + LSTR MSG_DELTA_HEIGHT = _UxGT("⊿高度"); // "Height" + LSTR MSG_DELTA_RADIUS = _UxGT("⊿半径"); // "Radius" + LSTR MSG_INFO_MENU = _UxGT("关于打印机"); // "About Printer" + LSTR MSG_INFO_PRINTER_MENU = _UxGT("打印机信息"); // "Printer Info" + LSTR MSG_3POINT_LEVELING = _UxGT("三点调平"); // "3-Point Leveling" + LSTR MSG_LINEAR_LEVELING = _UxGT("线性调平"); // "Linear Leveling" + LSTR MSG_BILINEAR_LEVELING = _UxGT("双线性调平"); // "Bilinear Leveling" + LSTR MSG_UBL_LEVELING = _UxGT("统一热床调平(UBL)"); // "Unified Bed Leveling" + LSTR MSG_MESH_LEVELING = _UxGT("网格调平"); // "Mesh Leveling" + LSTR MSG_INFO_STATS_MENU = _UxGT("打印机统计"); // "Printer Stats" + LSTR MSG_INFO_BOARD_MENU = _UxGT("主板信息"); // "Board Info" + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("温度计"); // "Thermistors" + LSTR MSG_INFO_EXTRUDERS = _UxGT("挤出机"); // "Extruders" + LSTR MSG_INFO_BAUDRATE = _UxGT("波特率"); // "Baud" + LSTR MSG_INFO_PROTOCOL = _UxGT("协议"); // "Protocol" + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("监控温度失控:关"); + LSTR MSG_INFO_RUNAWAY_ON = _UxGT("监控温度失控:开"); + LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("热端空闲超时"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("外壳灯"); // "Case light" - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("灯亮度"); // "Light BRIGHTNESS" + LSTR MSG_CASE_LIGHT = _UxGT("外壳灯"); // "Case light" + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("灯亮度"); // "Light BRIGHTNESS" - PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); // "Print Count" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成了"); // "Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总打印时间"); // "Total print time" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长工作时间"); // "Longest job time" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("总计挤出"); // "Extruded total" + LSTR MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); // "Print Count" + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("完成了"); // "Completed" + LSTR MSG_INFO_PRINT_TIME = _UxGT("总打印时间"); // "Total print time" + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("最长工作时间"); // "Longest job time" + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("总计挤出"); // "Extruded total" #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("打印数"); // "Prints" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("总共"); // "Total" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最长"); // "Longest" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已挤出"); // "Extruded" + LSTR MSG_INFO_PRINT_COUNT = _UxGT("打印数"); // "Prints" + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" + LSTR MSG_INFO_PRINT_TIME = _UxGT("总共"); // "Total" + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("最长"); // "Longest" + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("已挤出"); // "Extruded" #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低温度"); // "Min Temp" - 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_A = LCD_STR_A _UxGT(" 驱动 %"); // "X Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驱动 %"); - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驱动 %"); - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驱动 %"); - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驱动 %"); - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驱动 %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E 驱动 %"); // "E Driver %" - PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC 连接错误"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("保存驱动设置"); // "DAC EEPROM Write" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("更换料"); - 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" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢复选项:"); // "RESUME OPTIONS:" - 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("断料传感器"); - PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("断料距离mm"); - PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("归原位失败"); // "Homing failed" - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探针探测失败"); // "Probing failed" + LSTR MSG_INFO_MIN_TEMP = _UxGT("最低温度"); // "Min Temp" + LSTR MSG_INFO_MAX_TEMP = _UxGT("最高温度"); // "Max Temp" + LSTR MSG_INFO_PSU = _UxGT("电源供应"); // "Power Supply" + LSTR MSG_DRIVE_STRENGTH = _UxGT("驱动力度"); // "Drive Strength" + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" 驱动 %"); // "X Driver %" + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_E = _UxGT("E 驱动 %"); // "E Driver %" + LSTR MSG_ERROR_TMC = _UxGT("TMC 连接错误"); + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驱动设置"); // "DAC EEPROM Write" + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("更换料"); + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("打印已暂停"); // "PRINT PAUSED" + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("装载丝料"); // "LOAD FILAMENT" + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("卸载丝料"); // "UNLOAD FILAMENT" + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢复选项:"); // "RESUME OPTIONS:" + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("清除更多"); // "Purge more" + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("恢复打印"); // "Resume print" + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 喷嘴: "); // " Nozzle: " + LSTR MSG_RUNOUT_SENSOR = _UxGT("断料传感器"); + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("断料距离mm"); + LSTR MSG_KILL_HOMING_FAILED = _UxGT("归原位失败"); // "Homing failed" + LSTR MSG_LCD_PROBING_FAILED = _UxGT("探针探测失败"); // "Probing failed" - PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("选择料"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); - PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("升级MMU固件!"); - PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU需要专注."); - PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("MMU恢复"); - PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("MMU恢复中..."); - PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU加载"); - PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("MMU加载全部"); - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU加载到喷嘴"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU弹出"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU弹出 ~"); - PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU卸载"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("加载填充. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("弹出填充. ..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("卸载填充...."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("全部"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("料 ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("复位MMU"); - PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU复位中..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("移出, 按下"); + LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("选择料"); + LSTR MSG_MMU2_MENU = _UxGT("MMU"); + LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("升级MMU固件!"); + LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU需要专注."); + LSTR MSG_MMU2_RESUME = _UxGT("MMU恢复"); + LSTR MSG_MMU2_RESUMING = _UxGT("MMU恢复中..."); + LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU加载"); + LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU加载全部"); + LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU加载到喷嘴"); + LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU弹出"); + LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU弹出 ~"); + LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU卸载"); + LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("加载填充. %i..."); + LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("弹出填充. ..."); + LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("卸载填充...."); + LSTR MSG_MMU2_ALL = _UxGT("全部"); + LSTR MSG_MMU2_FILAMENT_N = _UxGT("料 ~"); + LSTR MSG_MMU2_RESET = _UxGT("复位MMU"); + LSTR MSG_MMU2_RESETTING = _UxGT("MMU复位中..."); + LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("移出, 按下"); - PROGMEM Language_Str MSG_MIX = _UxGT("混合"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("器件 ="); - PROGMEM Language_Str MSG_MIXER = _UxGT("混合器"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("梯度"); - PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("全梯度"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("开关混合"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("循环混合"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("梯度混合"); - PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("反向梯度"); - PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("激活 V-tool"); - PROGMEM Language_Str MSG_START_VTOOL = _UxGT("开始 V-tool"); - PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" 结束 V-tool"); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("别名 V-tool"); - PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("复位 V-tools"); - PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("提交 V-tool Mix"); - PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools 已复位"); - PROGMEM Language_Str MSG_START_Z = _UxGT("开始 Z:"); - PROGMEM Language_Str MSG_END_Z = _UxGT(" 结束 Z:"); + LSTR MSG_MIX = _UxGT("混合"); + LSTR MSG_MIX_COMPONENT_N = _UxGT("器件 ="); + LSTR MSG_MIXER = _UxGT("混合器"); + LSTR MSG_GRADIENT = _UxGT("梯度"); + LSTR MSG_FULL_GRADIENT = _UxGT("全梯度"); + LSTR MSG_TOGGLE_MIX = _UxGT("开关混合"); + LSTR MSG_CYCLE_MIX = _UxGT("循环混合"); + LSTR MSG_GRADIENT_MIX = _UxGT("梯度混合"); + LSTR MSG_REVERSE_GRADIENT = _UxGT("反向梯度"); + LSTR MSG_ACTIVE_VTOOL = _UxGT("激活 V-tool"); + LSTR MSG_START_VTOOL = _UxGT("开始 V-tool"); + LSTR MSG_END_VTOOL = _UxGT(" 结束 V-tool"); + LSTR MSG_GRADIENT_ALIAS = _UxGT("别名 V-tool"); + LSTR MSG_RESET_VTOOLS = _UxGT("复位 V-tools"); + LSTR MSG_COMMIT_VTOOL = _UxGT("提交 V-tool Mix"); + LSTR MSG_VTOOLS_RESET = _UxGT("V-tools 已复位"); + LSTR MSG_START_Z = _UxGT("开始 Z:"); + LSTR MSG_END_Z = _UxGT(" 结束 Z:"); - PROGMEM Language_Str MSG_GAMES = _UxGT("游戏"); - PROGMEM Language_Str MSG_BRICKOUT = _UxGT("敲方块"); - PROGMEM Language_Str MSG_INVADERS = _UxGT("入侵者"); - PROGMEM Language_Str MSG_SNAKE = _UxGT("贪吃蛇"); - PROGMEM Language_Str MSG_MAZE = _UxGT("迷宫"); + LSTR MSG_GAMES = _UxGT("游戏"); + LSTR MSG_BRICKOUT = _UxGT("敲方块"); + LSTR MSG_INVADERS = _UxGT("入侵者"); + LSTR MSG_SNAKE = _UxGT("贪吃蛇"); + LSTR MSG_MAZE = _UxGT("迷宫"); - PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("错误页面索引"); - PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("错误页面速度"); + LSTR MSG_BAD_PAGE = _UxGT("错误页面索引"); + LSTR MSG_BAD_PAGE_SPEED = _UxGT("错误页面速度"); // // 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("按下按钮", "恢复打印")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停靠中...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("等待开始", "丝料", "变更")); // "Wait for start of the filament change" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("插入料", "并按下", "以继续")); - 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_UNLOAD = _UxGT(MSG_2_LINE("等待", "卸下丝料")); // "Wait for filament unload" - 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("按下已完成", "料的清洗")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("等待打印", "恢复")); // "Wait for print to resume" + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("按下按钮", "恢复打印")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停靠中...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("等待开始", "丝料", "变更")); // "Wait for start of the filament change" + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("插入料", "并按下", "以继续")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("按下按钮来", "加热喷嘴.")); // "Press button to heat nozzle." + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("加热喷嘴", "请等待 ...")); // "Heating nozzle Please wait..." + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("等待", "卸下丝料")); // "Wait for filament unload" + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("等待", "进料")); // "Wait for filament load" + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("等待", "丝料清除")); // "Wait for filament purge" + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("按下已完成", "料的清洗")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("等待打印", "恢复")); // "Wait for print to resume" #else - PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下继续")); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停靠中...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("请等待 ...")); // "Please wait..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入并单击")); // "Insert and Click" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加热")); - 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_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢复中 ...")); // "Resuming..." + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下继续")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停靠中...")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("请等待 ...")); // "Please wait..." + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入并单击")); // "Insert and Click" + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加热")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("加热中 ...")); // "Heating..." + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("退出中 ...")); // "Ejecting..." + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("装载中 ...")); // "Loading..." + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("清除中 ...")); // "Purging..." + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢复中 ...")); // "Resuming..." #endif - PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC驱动器"); - PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("驱动电流"); - PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("混合阈值"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("无感回零"); - PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("步进模式"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop已使能"); - PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("复位"); - PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" 在:"); - PROGMEM Language_Str MSG_BACKLASH = _UxGT("回差"); - 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_I = LCD_STR_I; - PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; - PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; - PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("校正"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("平滑的"); + LSTR MSG_TMC_DRIVERS = _UxGT("TMC驱动器"); + LSTR MSG_TMC_CURRENT = _UxGT("驱动电流"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("混合阈值"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("无感回零"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("步进模式"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop已使能"); + LSTR MSG_SERVICE_RESET = _UxGT("复位"); + LSTR MSG_SERVICE_IN = _UxGT(" 在:"); + LSTR MSG_BACKLASH = _UxGT("回差"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_CORRECTION = _UxGT("校正"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("平滑的"); - PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X轴调平"); - PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("自动校准"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("加热器超时"); - PROGMEM Language_Str MSG_REHEAT = _UxGT("重新加热"); - PROGMEM Language_Str MSG_REHEATING = _UxGT("重新加热中..."); + LSTR MSG_LEVEL_X_AXIS = _UxGT("X轴调平"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("自动校准"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("加热器超时"); + LSTR MSG_REHEAT = _UxGT("重新加热"); + LSTR MSG_REHEATING = _UxGT("重新加热中..."); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 467a2467f5..42bb5be080 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -30,483 +30,483 @@ namespace Language_zh_TW { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 3; - PROGMEM Language_Str LANGUAGE = _UxGT("Traditional Chinese"); + constexpr uint8_t CHARSIZE = 3; + LSTR LANGUAGE = _UxGT("Traditional Chinese"); - PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); // " ready." - 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_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_RUN_AUTO_FILES = _UxGT("自動開始"); // "Autostart" - PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); // "Disable steppers" - PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("除錯選單"); // "Debug Menu" - PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("進度條測試"); // "Progress Bar Test" - PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("自動回原點"); // "Auto home" - 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" - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("完成熱床調平"); // "Leveling Done!" - PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("設置原點偏移"); // "Set home offsets" - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已啟用"); // "Offsets applied" - PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("設置原點"); // "Set origin" + LSTR WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); // " ready." + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_YES = _UxGT("是"); // "YES" + LSTR MSG_NO = _UxGT("否"); // "NO" + LSTR MSG_BACK = _UxGT("返回"); // "Back" + LSTR MSG_MEDIA_ABORTING = _UxGT("正在中止..."); // "Aborting..." + LSTR MSG_MEDIA_INSERTED = _UxGT("記憶卡已插入"); // "Card inserted" + LSTR MSG_MEDIA_REMOVED = _UxGT("記憶卡被拔出"); // "Card removed" + LSTR MSG_MEDIA_WAITING = _UxGT("等待記憶卡"); // "Waiting for media" + LSTR MSG_MEDIA_READ_ERROR = _UxGT("記憶卡讀取錯誤"); //"Media read error" + LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB裝置已移除"); // "USB device removed" + LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed" + LSTR MSG_LCD_ENDSTOPS = _UxGT("擋塊"); // "Endstops" // Max length 8 characters + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("軟體擋塊"); // "Soft Endstops" + LSTR MSG_MAIN = _UxGT("主選單"); // "Main" + LSTR MSG_ADVANCED_SETTINGS = _UxGT("進階設置"); // "Advanced Settings" + LSTR MSG_CONFIGURATION = _UxGT("設置"); //Configuration + LSTR MSG_RUN_AUTO_FILES = _UxGT("自動開始"); // "Autostart" + LSTR MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); // "Disable steppers" + LSTR MSG_DEBUG_MENU = _UxGT("除錯選單"); // "Debug Menu" + LSTR MSG_PROGRESS_BAR_TEST = _UxGT("進度條測試"); // "Progress Bar Test" + LSTR MSG_AUTO_HOME = _UxGT("自動回原點"); // "Auto home" + LSTR MSG_AUTO_HOME_X = _UxGT("回X原點"); // "Home X" + LSTR MSG_AUTO_HOME_Y = _UxGT("回Y原點"); // "Home Y" + LSTR MSG_AUTO_HOME_Z = _UxGT("回Z原點"); // "Home Z" + LSTR MSG_AUTO_Z_ALIGN = _UxGT("自動Z對齊"); // "Auto Z-Align" + LSTR MSG_LEVEL_BED_HOMING = _UxGT("平台調平XYZ歸原點"); // "Homing XYZ" + LSTR MSG_LEVEL_BED_WAITING = _UxGT("單擊開始熱床調平"); // "Click to Begin" + LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("下個熱床調平點"); // "Next Point" + LSTR MSG_LEVEL_BED_DONE = _UxGT("完成熱床調平"); // "Leveling Done!" + LSTR MSG_Z_FADE_HEIGHT = _UxGT("淡出高度"); // "Fade Height" + LSTR MSG_SET_HOME_OFFSETS = _UxGT("設置原點偏移"); // "Set home offsets" + LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("偏移已啟用"); // "Offsets applied" + LSTR MSG_SET_ORIGIN = _UxGT("設置原點"); // "Set origin" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("預熱 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("預熱 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴 ~"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 熱床"); //MSG_PREHEAT_1 " Bed" - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 設置"); //MSG_PREHEAT_1 " conf" + LSTR MSG_PREHEAT_1 = _UxGT("預熱 ") PREHEAT_1_LABEL; // "Preheat PREHEAT_1_LABEL" + LSTR MSG_PREHEAT_1_H = _UxGT("預熱 ") PREHEAT_1_LABEL " ~"; // "Preheat PREHEAT_1_LABEL" + LSTR MSG_PREHEAT_1_END = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_1_END_E = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 噴嘴 ~"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_1_ALL = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 全部"); //MSG_PREHEAT_1 " All" + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 熱床"); //MSG_PREHEAT_1 " Bed" + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("預熱 ") PREHEAT_1_LABEL _UxGT(" 設置"); //MSG_PREHEAT_1 " conf" - PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("預熱 $"); // "Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("預熱 $ ~"); // "Preheat PREHEAT_1_LABEL" - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("預熱 $ 噴嘴"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("預熱 $ 噴嘴 ~"); //MSG_PREHEAT_1 " " - PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("預熱 $ 全部"); //MSG_PREHEAT_1 " All" - PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("預熱 $ 熱床"); //MSG_PREHEAT_1 " Bed" - PROGMEM Language_Str MSG_PREHEAT_M_SETTINGS = _UxGT("預熱 $ 設置"); //MSG_PREHEAT_1 " conf" + LSTR MSG_PREHEAT_M = _UxGT("預熱 $"); // "Preheat PREHEAT_1_LABEL" + LSTR MSG_PREHEAT_M_H = _UxGT("預熱 $ ~"); // "Preheat PREHEAT_1_LABEL" + LSTR MSG_PREHEAT_M_END = _UxGT("預熱 $ 噴嘴"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_M_END_E = _UxGT("預熱 $ 噴嘴 ~"); //MSG_PREHEAT_1 " " + LSTR MSG_PREHEAT_M_ALL = _UxGT("預熱 $ 全部"); //MSG_PREHEAT_1 " All" + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("預熱 $ 熱床"); //MSG_PREHEAT_1 " Bed" + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("預熱 $ 設置"); //MSG_PREHEAT_1 " conf" #endif - 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_POWER = _UxGT("激光電源"); // "Laser Power" - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主軸控告制"); // "Spindle Control" - 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" - PROGMEM Language_Str MSG_RETRACT = _UxGT("回縮"); // "Retract" - PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("移動軸"); // "Move axis" - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("調平熱床"); // "Bed leveling" - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("調平熱床"); // "Level bed" - PROGMEM Language_Str MSG_BED_TRAMMING = _UxGT("調平邊角"); // "Bed Tramming" - 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_PROBING_POINT = _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_CUSTOM_COMMANDS = _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" - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("移除並測量熱床"); // "Remove & measure bed" - 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_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" - PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("完成編輯網格"); // "Done Editing Mesh" - PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("創設客戶網格"); // "Build Custom Mesh" - PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("創設網格"); // "Build Mesh" + LSTR MSG_PREHEAT_CUSTOM = _UxGT("自定預熱"); // "Preheat Custom" + LSTR MSG_COOLDOWN = _UxGT("降溫"); // "Cooldown" + LSTR MSG_LASER_MENU = _UxGT("激光控制"); // "Laser Control" + LSTR MSG_LASER_POWER = _UxGT("激光電源"); // "Laser Power" + LSTR MSG_SPINDLE_MENU = _UxGT("主軸控告制"); // "Spindle Control" + LSTR MSG_SPINDLE_POWER = _UxGT("主軸電源"); // "Spindle Power" + LSTR MSG_SPINDLE_REVERSE = _UxGT("主軸反轉"); // "Spindle Reverse" + LSTR MSG_SWITCH_PS_ON = _UxGT("電源打開"); // "Switch power on" + LSTR MSG_SWITCH_PS_OFF = _UxGT("電源關閉"); // "Switch power off" + LSTR MSG_EXTRUDE = _UxGT("擠出"); // "Extrude" + LSTR MSG_RETRACT = _UxGT("回縮"); // "Retract" + LSTR MSG_MOVE_AXIS = _UxGT("移動軸"); // "Move axis" + LSTR MSG_BED_LEVELING = _UxGT("調平熱床"); // "Bed leveling" + LSTR MSG_LEVEL_BED = _UxGT("調平熱床"); // "Level bed" + LSTR MSG_BED_TRAMMING = _UxGT("調平邊角"); // "Bed Tramming" + LSTR MSG_NEXT_CORNER = _UxGT("下個邊角"); // "Next corner" + LSTR MSG_MESH_EDITOR = _UxGT("網格編輯器"); // "Mesh Editor" + LSTR MSG_EDIT_MESH = _UxGT("編輯網格"); // "Edit Mesh" + LSTR MSG_EDITING_STOPPED = _UxGT("網格編輯已停止"); // "Mesh Editing Stopped" + LSTR MSG_PROBING_POINT = _UxGT("探測點"); // "Probing Point" + LSTR MSG_MESH_X = _UxGT("索引 X"); // "Index X" + LSTR MSG_MESH_Y = _UxGT("索引 Y"); // "Index Y" + LSTR MSG_MESH_EDIT_Z = _UxGT("Z 值"); // "Z Value" + LSTR MSG_CUSTOM_COMMANDS = _UxGT("自定命令"); // "Custom Commands" + LSTR MSG_M48_TEST = _UxGT("M48 探測測試"); // "M48 Probe Test" + LSTR MSG_M48_POINT = _UxGT("M48 探測點"); // "M48 Point" + LSTR MSG_M48_DEVIATION = _UxGT("偏差"); // "Deviation" + LSTR MSG_IDEX_MENU = _UxGT("IDEX Mode"); + LSTR MSG_OFFSETS_MENU = _UxGT("Tool Offsets"); + LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); + LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); + LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); + LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); + LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); + LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_UBL_DOING_G29 = _UxGT("執行G29"); // "Doing G29" + LSTR MSG_UBL_TOOLS = _UxGT("UBL工具"); // "UBL Tools" + LSTR MSG_UBL_LEVEL_BED = _UxGT("統一熱床調平(UBL)"); // "Unified Bed Leveling" + LSTR MSG_LCD_TILTING_MESH = _UxGT("傾斜點"); // "Tilting Point" + LSTR MSG_UBL_MANUAL_MESH = _UxGT("手工建網"); // "Manually Build Mesh" + LSTR MSG_UBL_BC_INSERT = _UxGT("放置墊片並測量"); // "Place shim & measure" + LSTR MSG_UBL_BC_INSERT2 = _UxGT("測量"); // "Measure" + LSTR MSG_UBL_BC_REMOVE = _UxGT("移除並測量熱床"); // "Remove & measure bed" + LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("移動到下一個"); // "Moving to next" + LSTR MSG_UBL_ACTIVATE_MESH = _UxGT("啟動UBL"); // "Activate UBL" + LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("關閉UBL"); // "Deactivate UBL" + LSTR MSG_UBL_SET_TEMP_BED = _UxGT("置設熱床溫度"); // "Bed Temp" + LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("置設熱床溫度"); // "Bed Temp") + LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("置設噴嘴溫度"); // "Hotend Temp" + LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("熱端溫度"); // "Hotend Temp" + LSTR MSG_UBL_MESH_EDIT = _UxGT("網格編輯"); // "Mesh Edit" + LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("編輯客戶網格"); // "Edit Custom Mesh" + LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("細調網格"); // "Fine Tuning Mesh" + LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("完成編輯網格"); // "Done Editing Mesh" + LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("創設客戶網格"); // "Build Custom Mesh" + LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("創設網格"); // "Build Mesh" #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("創設 $ 網格"); // "Build PREHEAT_1_LABEL Mesh" - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("批准 $ 網格"); // "Validate PREHEAT_1_LABEL Mesh" + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("創設 $ 網格"); // "Build PREHEAT_1_LABEL Mesh" + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("批准 $ 網格"); // "Validate PREHEAT_1_LABEL Mesh" #endif - PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("創設冷網格"); // "Build Cold Mesh" - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("調整網格高度"); // "Adjust Mesh Height" - PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("高度合計"); // "Height Amount" - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("批准網格"); // "Validate 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" - PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("格子網格調平"); // "Grid Mesh Leveling" - PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("調平網格"); // "Level Mesh" - PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("邊點"); // "Side Points" - PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("圖類型"); // "Map Type" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("輸出網格圖"); // "Output Mesh Map" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("輸出到主機"); // "Output for Host" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("輸出到CSV"); // "Output for CSV" - PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("輸出到備份"); // "Off Printer Backup" - PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("輸出UBL信息"); // "Output UBL Info" - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("填充合計"); // "Fill-in Amount" - PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("手工填充"); // "Manual Fill-in" - PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("聰明填充"); // "Smart Fill-in" - PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("填充網格"); // "Fill-in Mesh" - PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("作廢所有的"); // "Invalidate All" - PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("作廢最近的"); // "Invalidate Closest" - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("細調所有的"); // "Fine Tune All" - PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("細調最近的"); // "Fine Tune Closest" - PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("網格存儲"); // "Mesh Storage" - PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("存儲槽"); // "Memory Slot" - PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("裝載熱床網格"); // "Load Bed Mesh" - PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("保存熱床網格"); // "Save Bed Mesh" - PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("網格 %i 已裝載"); // "Mesh %i loaded" - PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("網格 %i 已保存"); // "Mesh %i saved" - 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. 創設冷網格"); - PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. 聰明填充"); - PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. 批准網格"); - PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. 細調所有的"); - PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. 批准網格"); - PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. 細調所有的"); - PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. 保存熱床網格"); + LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("創設冷網格"); // "Build Cold Mesh" + LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("調整網格高度"); // "Adjust Mesh Height" + LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("高度合計"); // "Height Amount" + LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("批准網格"); // "Validate Mesh" + LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("批准客戶網格"); // "Validate Custom Mesh" + LSTR MSG_G26_HEATING_BED = _UxGT("G26 加熱熱床"); // "G26 Heating Bed" + LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 加熱噴嘴"); //"G26 Heating Nozzle" + LSTR MSG_G26_MANUAL_PRIME = _UxGT("手動填裝"); // "Manual priming..." + LSTR MSG_G26_FIXED_LENGTH = _UxGT("固定距離填裝"); // "Fixed Length Prime" + LSTR MSG_G26_PRIME_DONE = _UxGT("完成填裝"); // "Done Priming" + LSTR MSG_G26_CANCELED = _UxGT("G26已取消"); // "G26 Canceled" + LSTR MSG_G26_LEAVING = _UxGT("離開 G26"); // "Leaving G26" + LSTR MSG_UBL_CONTINUE_MESH = _UxGT("繼續熱床網格"); // "Continue Bed Mesh" + LSTR MSG_UBL_MESH_LEVELING = _UxGT("網格調平"); // "Mesh Leveling" + LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("三點調平"); // "3-Point Leveling" + LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("格子網格調平"); // "Grid Mesh Leveling" + LSTR MSG_UBL_MESH_LEVEL = _UxGT("調平網格"); // "Level Mesh" + LSTR MSG_UBL_SIDE_POINTS = _UxGT("邊點"); // "Side Points" + LSTR MSG_UBL_MAP_TYPE = _UxGT("圖類型"); // "Map Type" + LSTR MSG_UBL_OUTPUT_MAP = _UxGT("輸出網格圖"); // "Output Mesh Map" + LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("輸出到主機"); // "Output for Host" + LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("輸出到CSV"); // "Output for CSV" + LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("輸出到備份"); // "Off Printer Backup" + LSTR MSG_UBL_INFO_UBL = _UxGT("輸出UBL信息"); // "Output UBL Info" + LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("填充合計"); // "Fill-in Amount" + LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("手工填充"); // "Manual Fill-in" + LSTR MSG_UBL_SMART_FILLIN = _UxGT("聰明填充"); // "Smart Fill-in" + LSTR MSG_UBL_FILLIN_MESH = _UxGT("填充網格"); // "Fill-in Mesh" + LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("作廢所有的"); // "Invalidate All" + LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("作廢最近的"); // "Invalidate Closest" + LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("細調所有的"); // "Fine Tune All" + LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("細調最近的"); // "Fine Tune Closest" + LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("網格存儲"); // "Mesh Storage" + LSTR MSG_UBL_STORAGE_SLOT = _UxGT("存儲槽"); // "Memory Slot" + LSTR MSG_UBL_LOAD_MESH = _UxGT("裝載熱床網格"); // "Load Bed Mesh" + LSTR MSG_UBL_SAVE_MESH = _UxGT("保存熱床網格"); // "Save Bed Mesh" + LSTR MSG_MESH_LOADED = _UxGT("網格 %i 已裝載"); // "Mesh %i loaded" + LSTR MSG_MESH_SAVED = _UxGT("網格 %i 已保存"); // "Mesh %i saved" + LSTR MSG_UBL_NO_STORAGE = _UxGT("沒有存儲"); // "No storage" + LSTR MSG_UBL_SAVE_ERROR = _UxGT("錯誤: UBL保存"); // "Err: UBL Save" + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("錯誤: UBL還原"); // "Err: UBL Restore" + LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-偏移:"); // "Z-Offset: " + LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z偏移已停止"); // "Z-Offset Stopped" + LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("一步步UBL"); // "Step-By-Step UBL" + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. 創設冷網格"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. 聰明填充"); + LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. 批准網格"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. 細調所有的"); + LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. 批准網格"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. 細調所有的"); + LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. 保存熱床網格"); - PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("燈管控制"); // "LED Control") - PROGMEM Language_Str MSG_LEDS = _UxGT("燈"); // "Lights") - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("燈預置"); // "Light Presets") - PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("红"); // "Red") - PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("橙"); // "Orange") - PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("黃"); // "Yellow") - PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("綠"); // "Green") - PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("藍"); // "Blue") - 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_CUSTOM_LEDS = _UxGT("定制燈"); // "Custom Lights") - PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("紅飽和度"); // "Red Intensity") - PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("綠飽和度"); // "Green Intensity") - PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("藍飽和度"); // "Blue Intensity") - PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("白飽和度"); // "White Intensity") - PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("亮度"); // "Brightness") + LSTR MSG_LED_CONTROL = _UxGT("燈管控制"); // "LED Control") + LSTR MSG_LEDS = _UxGT("燈"); // "Lights") + LSTR MSG_LED_PRESETS = _UxGT("燈預置"); // "Light Presets") + LSTR MSG_SET_LEDS_RED = _UxGT("红"); // "Red") + LSTR MSG_SET_LEDS_ORANGE = _UxGT("橙"); // "Orange") + LSTR MSG_SET_LEDS_YELLOW = _UxGT("黃"); // "Yellow") + LSTR MSG_SET_LEDS_GREEN = _UxGT("綠"); // "Green") + LSTR MSG_SET_LEDS_BLUE = _UxGT("藍"); // "Blue") + LSTR MSG_SET_LEDS_INDIGO = _UxGT("青"); // "Indigo") + LSTR MSG_SET_LEDS_VIOLET = _UxGT("紫"); // "Violet") + LSTR MSG_SET_LEDS_WHITE = _UxGT("白"); // "White") + LSTR MSG_SET_LEDS_DEFAULT = _UxGT("復歸"); // "Default") + LSTR MSG_CUSTOM_LEDS = _UxGT("定制燈"); // "Custom Lights") + LSTR MSG_INTENSITY_R = _UxGT("紅飽和度"); // "Red Intensity") + LSTR MSG_INTENSITY_G = _UxGT("綠飽和度"); // "Green Intensity") + LSTR MSG_INTENSITY_B = _UxGT("藍飽和度"); // "Blue Intensity") + LSTR MSG_INTENSITY_W = _UxGT("白飽和度"); // "White Intensity") + LSTR MSG_LED_BRIGHTNESS = _UxGT("亮度"); // "Brightness") - PROGMEM Language_Str MSG_MOVING = _UxGT("移動 ..."); // "Moving...") - PROGMEM Language_Str MSG_FREE_XY = _UxGT("釋放 XY"); // "Free XY") - PROGMEM Language_Str MSG_MOVE_X = _UxGT("移動X"); // "Move X" - 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("擠出機 *"); // "Extruder *" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); // "Hotend too cold" - PROGMEM Language_Str MSG_MOVE_N_MM = _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" - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); // "Move 10mm" - PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); // "Move 100mm" - PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); // "Speed" - PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); // "Bed Z" - 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_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_FLOW = _UxGT("擠出速率"); - PROGMEM Language_Str MSG_FLOW_N = _UxGT("擠出速率 ~"); // "Flow" - PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); // "Control" - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" - 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" + LSTR MSG_MOVING = _UxGT("移動 ..."); // "Moving...") + LSTR MSG_FREE_XY = _UxGT("釋放 XY"); // "Free XY") + LSTR MSG_MOVE_X = _UxGT("移動X"); // "Move X" + LSTR MSG_MOVE_Y = _UxGT("移動Y"); // "Move Y" + LSTR MSG_MOVE_Z = _UxGT("移動Z"); // "Move Z" + LSTR MSG_MOVE_E = _UxGT("擠出機"); // "Extruder" + LSTR MSG_MOVE_EN = _UxGT("擠出機 *"); // "Extruder *" + LSTR MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); // "Hotend too cold" + LSTR MSG_MOVE_N_MM = _UxGT("移動 %s mm"); // "Move 0.025mm" + LSTR MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); // "Move 0.1mm" + LSTR MSG_MOVE_1MM = _UxGT("移動 1 mm"); // "Move 1mm" + LSTR MSG_MOVE_10MM = _UxGT("移動 10 mm"); // "Move 10mm" + LSTR MSG_MOVE_100MM = _UxGT("移動 100 mm"); // "Move 100mm" + LSTR MSG_SPEED = _UxGT("速率"); // "Speed" + LSTR MSG_BED_Z = _UxGT("熱床Z"); // "Bed Z" + LSTR MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); // "Nozzle" 噴嘴 + LSTR MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴 ~"); + LSTR MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" 熱床"); // "Bed" + LSTR MSG_CHAMBER = _UxGT("Enclosure"); + LSTR MSG_FAN_SPEED = _UxGT("風扇速率"); // "Fan speed" + LSTR MSG_FAN_SPEED_N = _UxGT("風扇速率 ="); + LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ="); + LSTR MSG_EXTRA_FAN_SPEED = _UxGT("額外風扇速率"); // "Extra fan speed" + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("額外風扇速率 ="); + LSTR MSG_FLOW = _UxGT("擠出速率"); + LSTR MSG_FLOW_N = _UxGT("擠出速率 ~"); // "Flow" + LSTR MSG_CONTROL = _UxGT("控制"); // "Control" + LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" 最小"); // " " LCD_STR_THERMOMETER " Min" + LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" 最大"); // " " LCD_STR_THERMOMETER " Max" + LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 系數"); // " " LCD_STR_THERMOMETER " Fact" + LSTR MSG_AUTOTEMP = _UxGT("自動控溫"); // "Autotemp" + LSTR MSG_LCD_ON = _UxGT("開 "); // "On" + LSTR MSG_LCD_OFF = _UxGT("關 "); // "Off" - PROGMEM Language_Str MSG_SELECT = _UxGT("選擇"); // "Select" - PROGMEM Language_Str MSG_SELECT_E = _UxGT("選擇 *"); - PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); // "Accel" acceleration - PROGMEM Language_Str MSG_JERK = _UxGT("抖動速率"); // "Jerk" - PROGMEM Language_Str MSG_VA_JERK = _UxGT("軸抖動速率") LCD_STR_A; // "Va-jerk" - PROGMEM Language_Str MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; - PROGMEM Language_Str MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; - PROGMEM Language_Str MSG_VI_JERK = _UxGT("軸抖動速率") LCD_STR_I; - PROGMEM Language_Str MSG_VJ_JERK = _UxGT("軸抖動速率") LCD_STR_J; - PROGMEM Language_Str MSG_VK_JERK = _UxGT("軸抖動速率") LCD_STR_K; - PROGMEM Language_Str MSG_VE_JERK = _UxGT("擠出機抖動速率"); + LSTR MSG_SELECT = _UxGT("選擇"); // "Select" + LSTR MSG_SELECT_E = _UxGT("選擇 *"); + LSTR MSG_ACC = _UxGT("加速度"); // "Accel" acceleration + LSTR MSG_JERK = _UxGT("抖動速率"); // "Jerk" + LSTR MSG_VA_JERK = _UxGT("軸抖動速率") LCD_STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; + LSTR MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; + LSTR MSG_VI_JERK = _UxGT("軸抖動速率") LCD_STR_I; + LSTR MSG_VJ_JERK = _UxGT("軸抖動速率") LCD_STR_J; + LSTR MSG_VK_JERK = _UxGT("軸抖動速率") LCD_STR_K; + LSTR MSG_VE_JERK = _UxGT("擠出機抖動速率"); - 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; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("最大進料速率") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_I = _UxGT("最大進料速率") LCD_STR_I; - PROGMEM Language_Str MSG_VMAX_J = _UxGT("最大進料速率") LCD_STR_J; - PROGMEM Language_Str MSG_VMAX_K = _UxGT("最大進料速率") LCD_STR_K; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("最大進料速率") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("最大進料速率 *"); // "Vmax " max_feedrate_mm_s - PROGMEM Language_Str MSG_VMIN = _UxGT("最小進料速率"); // "Vmin" min_feedrate_mm_s - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("最小移動速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move - PROGMEM Language_Str MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - PROGMEM Language_Str MSG_AMAX_A = _UxGT("最大列印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_AMAX_B = _UxGT("最大列印加速度") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("最大列印加速度") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_I = _UxGT("最大列印加速度") LCD_STR_I; - PROGMEM Language_Str MSG_AMAX_J = _UxGT("最大列印加速度") LCD_STR_J; - PROGMEM Language_Str MSG_AMAX_K = _UxGT("最大列印加速度") LCD_STR_K; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("最大列印加速度") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("最大列印加速度 *"); // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("回縮加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts - PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("非列印移動加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves - PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("軸步數/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" 軸步數/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" 軸步數/mm"); - PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" 軸步數/mm"); - PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" 軸步數/mm"); - PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" 軸步數/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("擠出機步數/mm"); // "Esteps/mm" - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("擠出機~步數/mm"); - PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("溫度"); // "Temperature" - PROGMEM Language_Str MSG_MOTION = _UxGT("運作"); // "Motion" - PROGMEM Language_Str MSG_FILAMENT = _UxGT("絲料測容"); // "Filament" menu_control_volumetric - PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled - PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("絲料直徑"); // "Fil. Dia." - 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 failsafe" - PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("初始化設置"); // "Initialize EEPROM" - 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. " - PROGMEM Language_Str MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("回縮長度mm"); // "Retract mm" retract_length, retract length (positive mm) - PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("換手回抽長度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("回縮速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("回縮恢復長度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("換手回縮恢復長度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) - PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回縮恢復後進料速率mm/s"); // "Unretract 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("自動回縮"); // "Auto-Retract" 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_SPEED = _UxGT("最高速度"); // "Prime Speed" - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _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" - PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("裝載絲料 *"); - 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_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" + LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" + LSTR MSG_VMAX_A = _UxGT("最大進料速率") LCD_STR_A; // "Vmax " max_feedrate_mm_s + LSTR MSG_VMAX_B = _UxGT("最大進料速率") LCD_STR_B; + LSTR MSG_VMAX_C = _UxGT("最大進料速率") LCD_STR_C; + LSTR MSG_VMAX_I = _UxGT("最大進料速率") LCD_STR_I; + LSTR MSG_VMAX_J = _UxGT("最大進料速率") LCD_STR_J; + LSTR MSG_VMAX_K = _UxGT("最大進料速率") LCD_STR_K; + LSTR MSG_VMAX_E = _UxGT("最大進料速率") LCD_STR_E; + LSTR MSG_VMAX_EN = _UxGT("最大進料速率 *"); // "Vmax " max_feedrate_mm_s + LSTR MSG_VMIN = _UxGT("最小進料速率"); // "Vmin" min_feedrate_mm_s + LSTR MSG_VTRAV_MIN = _UxGT("最小移動速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move + LSTR MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" + LSTR MSG_AMAX_A = _UxGT("最大列印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + LSTR MSG_AMAX_B = _UxGT("最大列印加速度") LCD_STR_B; + LSTR MSG_AMAX_C = _UxGT("最大列印加速度") LCD_STR_C; + LSTR MSG_AMAX_I = _UxGT("最大列印加速度") LCD_STR_I; + LSTR MSG_AMAX_J = _UxGT("最大列印加速度") LCD_STR_J; + LSTR MSG_AMAX_K = _UxGT("最大列印加速度") LCD_STR_K; + LSTR MSG_AMAX_E = _UxGT("最大列印加速度") LCD_STR_E; + LSTR MSG_AMAX_EN = _UxGT("最大列印加速度 *"); // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + LSTR MSG_A_RETRACT = _UxGT("回縮加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts + LSTR MSG_A_TRAVEL = _UxGT("非列印移動加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves + LSTR MSG_STEPS_PER_MM = _UxGT("軸步數/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 + LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 + LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" 軸步數/mm"); + LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" 軸步數/mm"); + LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" 軸步數/mm"); + LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" 軸步數/mm"); + LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" 軸步數/mm"); + LSTR MSG_E_STEPS = _UxGT("擠出機步數/mm"); // "Esteps/mm" + LSTR MSG_EN_STEPS = _UxGT("擠出機~步數/mm"); + LSTR MSG_TEMPERATURE = _UxGT("溫度"); // "Temperature" + LSTR MSG_MOTION = _UxGT("運作"); // "Motion" + LSTR MSG_FILAMENT = _UxGT("絲料測容"); // "Filament" menu_control_volumetric + LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("測容積mm") SUPERSCRIPT_THREE; // "E in mm3" volumetric_enabled + LSTR MSG_FILAMENT_DIAM = _UxGT("絲料直徑"); // "Fil. Dia." + LSTR MSG_FILAMENT_DIAM_E = _UxGT("絲料直徑 *"); + LSTR MSG_FILAMENT_UNLOAD = _UxGT("卸載 mm"); // "Unload mm" + LSTR MSG_FILAMENT_LOAD = _UxGT("装載 mm"); // "Load mm" + LSTR MSG_ADVANCE_K = _UxGT("Advance K"); + LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); + LSTR MSG_CONTRAST = _UxGT("LCD對比度"); // "LCD contrast" + LSTR MSG_STORE_EEPROM = _UxGT("保存設置"); // "Store memory" + LSTR MSG_LOAD_EEPROM = _UxGT("載入設置"); // "Load memory" + LSTR MSG_RESTORE_DEFAULTS = _UxGT("恢復安全值"); // "Restore failsafe" + LSTR MSG_INIT_EEPROM = _UxGT("初始化設置"); // "Initialize EEPROM" + LSTR MSG_ERR_EEPROM_CRC = _UxGT("錯誤: EEPROM CRC"); // "Err: EEPROM CRC" + LSTR MSG_ERR_EEPROM_INDEX = _UxGT("錯誤: EEPROM Index"); // "Err: EEPROM Index" + LSTR MSG_ERR_EEPROM_VERSION = _UxGT("錯誤: EEPROM Version"); // "EEPROM Version" + LSTR MSG_MEDIA_UPDATE = _UxGT("媒體更新"); // "Media Update" + LSTR MSG_RESET_PRINTER = _UxGT("重置打印機"); // "Reset Printer + LSTR MSG_REFRESH = _UxGT("刷新"); // "Refresh" + LSTR MSG_INFO_SCREEN = _UxGT("資訊界面"); // "Info screen" + LSTR MSG_PREPARE = _UxGT("準備"); // "Prepare" + LSTR MSG_TUNE = _UxGT("調整"); // "Tune" + LSTR MSG_START_PRINT = _UxGT("開始列印"); // "Start Print" + LSTR MSG_BUTTON_NEXT = _UxGT("下一個"); // "Next" + LSTR MSG_BUTTON_INIT = _UxGT("初始 "); // "Init" + LSTR MSG_BUTTON_STOP = _UxGT("停止 "); // "Stop" + LSTR MSG_BUTTON_PRINT = _UxGT("列印 "); // "Print" + LSTR MSG_BUTTON_RESET = _UxGT("復歸 "); // "Reset" + LSTR MSG_BUTTON_CANCEL = _UxGT("放棄 "); // "Cancel" + LSTR MSG_BUTTON_DONE = _UxGT("確認 "); // "Done" + LSTR MSG_BUTTON_BACK = _UxGT("返回 "); // "Back" + LSTR MSG_BUTTON_PROCEED = _UxGT("繼續 "); // "Proceed" + LSTR MSG_PAUSE_PRINT = _UxGT("暫停列印"); // "Pause print" + LSTR MSG_RESUME_PRINT = _UxGT("恢復列印"); // "Resume print" + LSTR MSG_STOP_PRINT = _UxGT("停止列印"); // "Stop print" + LSTR MSG_PRINTING_OBJECT = _UxGT("列印物件"); // "Printing Object" + LSTR MSG_CANCEL_OBJECT = _UxGT("中止物件"); // "Cancel Object" + LSTR MSG_CANCEL_OBJECT_N = _UxGT("中止物件 ="); // "Cancel Object =" + LSTR MSG_OUTAGE_RECOVERY = _UxGT("中斷恢復"); // "Outage Recovery" + LSTR MSG_MEDIA_MENU = _UxGT("從記憶卡上列印"); // "Print from SD" + LSTR MSG_NO_MEDIA = _UxGT("無記憶卡"); // "No SD card" + LSTR MSG_DWELL = _UxGT("休眠 ..."); // "Sleep..." + LSTR MSG_USERWAIT = _UxGT("點擊繼續 ..."); // "Click to resume..." + LSTR MSG_PRINT_PAUSED = _UxGT("列印已暫停"); // "Print paused" + LSTR MSG_PRINTING = _UxGT("列印中 ..."); // "Printing..." + LSTR MSG_PRINT_ABORTED = _UxGT("已取消列印"); // "Print aborted" + LSTR MSG_NO_MOVE = _UxGT("無移動"); // "No move." + LSTR MSG_KILLED = _UxGT("已砍掉"); // "KILLED. " + LSTR MSG_STOPPED = _UxGT("已停止"); // "STOPPED. " + LSTR MSG_CONTROL_RETRACT = _UxGT("回縮長度mm"); // "Retract mm" retract_length, retract length (positive mm) + LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("換手回抽長度mm"); // "Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change + LSTR MSG_CONTROL_RETRACTF = _UxGT("回縮速率mm/s"); // "Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) + LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hop mm"); // "Hop mm" retract_zraise, retract Z-lift + LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("回縮恢復長度mm"); // "UnRet +mm" retract_recover_extra, additional recover length (mm, added to retract length when recovering) + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("換手回縮恢復長度mm"); // "S UnRet+mm" swap_retract_recover_extra, additional swap recover length (mm, added to retract length when recovering from extruder change) + LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回縮恢復後進料速率mm/s"); // "Unretract V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) + LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); // "S UnRet V" + LSTR MSG_AUTORETRACT = _UxGT("自動回縮"); // "Auto-Retract" autoretract_enabled, + LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("交換長度"); // "Swap Length" + LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("清除長度"); // "Purge Length" + LSTR MSG_TOOL_CHANGE = _UxGT("交換工具"); //"Tool Change" + LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z軸提昇"); // "Z Raise" + LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("最高速度"); // "Prime Speed" + LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("收回速度"); // "Retract Speed" + LSTR MSG_NOZZLE_STANDBY = _UxGT("噴嘴待機"); //"Nozzle Standby" + LSTR MSG_FILAMENTCHANGE = _UxGT("更換絲料"); // "Change filament" + LSTR MSG_FILAMENTCHANGE_E = _UxGT("更換絲料 *"); + LSTR MSG_FILAMENTLOAD = _UxGT("裝載絲料"); // "Load filament" + LSTR MSG_FILAMENTLOAD_E = _UxGT("裝載絲料 *"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("卸載絲料"); // "Unload filament" + LSTR MSG_FILAMENTUNLOAD_E = _UxGT("卸載絲料 *"); // "Unload filament" + LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("卸載全部"); // "Unload All" + LSTR MSG_INIT_MEDIA = _UxGT("初始化記憶卡"); // "Init. SD card" + LSTR MSG_ATTACH_MEDIA = _UxGT("連接記憶卡"); // "Attach Media + LSTR MSG_CHANGE_MEDIA = _UxGT("更換記憶卡"); // "Change SD card" + LSTR MSG_RELEASE_MEDIA = _UxGT("釋放媒體"); // "Release Media" + LSTR MSG_ZPROBE_OUT = _UxGT("Z探針在熱床之外"); // "Z probe out. bed" Z probe is not within the physical limits + LSTR MSG_SKEW_FACTOR = _UxGT("偏斜因數"); // "Skew Factor" - 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_STOW = _UxGT("裝載BLTouch"); // "Stow BLTouch" - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" + LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch 自檢"); // "BLTouch Self-Test" + LSTR MSG_BLTOUCH_RESET = _UxGT("重置BLTouch"); // "Reset BLTouch" + LSTR MSG_BLTOUCH_STOW = _UxGT("裝載BLTouch"); // "Stow BLTouch" + LSTR MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); // "Home ... first" - 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("錯誤:冗餘溫度"); // "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_HALTED = _UxGT("印表機停機"); // "PRINTER HALTED" - PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); // "Please reset" - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only - 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" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校準Z"); // "Calibrate Z" - PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校準中心"); // "Calibrate Center" - 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" - PROGMEM Language_Str MSG_INFO_MENU = _UxGT("關於印表機"); // "About Printer" - 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_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_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" + LSTR MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); // "Home ... first" + LSTR MSG_ZPROBE_OFFSETS = _UxGT("探針偏移"); //Probe Offsets + LSTR MSG_ZPROBE_XOFFSET = _UxGT("探針X偏移量"); //Probe X Offset + LSTR MSG_ZPROBE_YOFFSET = _UxGT("探針Y偏移量"); //Probe Y Offset + LSTR MSG_ZPROBE_ZOFFSET = _UxGT("探針Z偏移量"); //Probe Z Offset + LSTR MSG_BABYSTEP_X = _UxGT("微量調整X軸"); // "Babystep X" lcd_babystep_x, Babystepping enables the user to control the axis in tiny amounts + LSTR MSG_BABYSTEP_Y = _UxGT("微量調整Y軸"); // "Babystep Y" + LSTR MSG_BABYSTEP_Z = _UxGT("微量調整Z軸"); // "Babystep Z" + LSTR MSG_BABYSTEP_TOTAL = _UxGT("總計"); // "Total" + LSTR MSG_ENDSTOP_ABORT = _UxGT("擋塊終止"); // "Endstop abort" + LSTR MSG_HEATING_FAILED_LCD = _UxGT("加熱失敗"); // "Heating failed" + LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("錯誤:冗餘溫度"); // "Err: REDUNDANT TEMP" + LSTR MSG_THERMAL_RUNAWAY = _UxGT("溫度失控"); // "THERMAL RUNAWAY" + LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("熱床溫度失控"); // "BED THERMAL RUNAWAY" + LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("機箱溫度失控"); // "CHAMBER T. RUNAWAY" + LSTR MSG_ERR_MAXTEMP = _UxGT("錯誤:最高溫度"); // "Err: MAXTEMP" + LSTR MSG_ERR_MINTEMP = _UxGT("錯誤:最低溫度"); // "Err: MINTEMP" + LSTR MSG_HALTED = _UxGT("印表機停機"); // "PRINTER HALTED" + LSTR MSG_PLEASE_RESET = _UxGT("請重置"); // "Please reset" + LSTR MSG_SHORT_DAY = _UxGT("天"); // "d" // One character only + LSTR MSG_SHORT_HOUR = _UxGT("時"); // "h" // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("分"); // "m" // One character only + LSTR MSG_HEATING = _UxGT("加熱中 ..."); // "Heating..." + LSTR MSG_COOLING = _UxGT("冷卻中 ..."); // "Cooling..." + LSTR MSG_BED_HEATING = _UxGT("加熱熱床中 ..."); // "Bed Heating..." + LSTR MSG_BED_COOLING = _UxGT("熱床冷卻中 ..."); // "Bed Cooling..." + LSTR MSG_CHAMBER_HEATING = _UxGT("機箱加熱中 .."); // "Chamber Heating..." + LSTR MSG_CHAMBER_COOLING = _UxGT("機箱冷卻中 ..."); //Chamber Cooling... + LSTR MSG_DELTA_CALIBRATE = _UxGT("⊿校準"); // "Delta Calibration" + LSTR MSG_DELTA_CALIBRATE_X = _UxGT("⊿校準X"); // "Calibrate X" + LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("⊿校準Y"); // "Calibrate Y" + LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("⊿校準Z"); // "Calibrate Z" + LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("⊿校準中心"); // "Calibrate Center" + LSTR MSG_DELTA_SETTINGS = _UxGT("⊿設置"); // "Delta Settings" + LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("⊿自動校準"); // "Auto Calibration" + LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("設置⊿高度"); // "Set Delta Height" + LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z偏移"); + LSTR MSG_DELTA_DIAG_ROD = _UxGT("⊿斜柱"); // "Diag Rod" + LSTR MSG_DELTA_HEIGHT = _UxGT("⊿高度"); // "Height" + LSTR MSG_DELTA_RADIUS = _UxGT("⊿半徑"); // "Radius" + LSTR MSG_INFO_MENU = _UxGT("關於印表機"); // "About Printer" + LSTR MSG_INFO_PRINTER_MENU = _UxGT("印表機訊息"); // "Printer Info" + LSTR MSG_3POINT_LEVELING = _UxGT("三點調平"); // "3-Point Leveling" + LSTR MSG_LINEAR_LEVELING = _UxGT("線性調平"); // "Linear Leveling" + LSTR MSG_BILINEAR_LEVELING = _UxGT(" 雙線性調平"); // "Bilinear Leveling" + LSTR MSG_UBL_LEVELING = _UxGT("統一熱床調平(UBL)"); // "Unified Bed Leveling" + LSTR MSG_MESH_LEVELING = _UxGT("網格調平"); // "Mesh Leveling" + LSTR MSG_INFO_STATS_MENU = _UxGT("印表機統計"); // "Printer Stats" + LSTR MSG_INFO_BOARD_MENU = _UxGT("主板訊息"); // "Board Info" + LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("溫度計"); // "Thermistors" + LSTR MSG_INFO_EXTRUDERS = _UxGT(" 擠出機"); // "Extruders" + LSTR MSG_INFO_BAUDRATE = _UxGT("傳輸率"); // "Baud" + LSTR MSG_INFO_PROTOCOL = _UxGT("協議"); // "Protocol" + LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("監測溫度失控:關"); // "Runaway Watch: OFF" + LSTR 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_KILL_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" + LSTR MSG_CASE_LIGHT = _UxGT("外殼燈"); // "Case light" + LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("燈亮度"); // "Light BRIGHTNESS" + LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); // "Print Count" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("已完成"); // "Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總列印時間"); // "Total print time" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長工作時間"); // "Longest job time" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("總計擠出"); // "Extruded total" + LSTR MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); // "Print Count" + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("已完成"); // "Completed" + LSTR MSG_INFO_PRINT_TIME = _UxGT("總列印時間"); // "Total print time" + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("最長工作時間"); // "Longest job time" + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("總計擠出"); // "Extruded total" #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("列印數"); // "Prints" - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("總共"); // "Total" - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("最長"); // "Longest" - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("已擠出"); // "Extruded" + LSTR MSG_INFO_PRINT_COUNT = _UxGT("列印數"); // "Prints" + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("完成"); // "Completed" + LSTR MSG_INFO_PRINT_TIME = _UxGT("總共"); // "Total" + LSTR MSG_INFO_PRINT_LONGEST = _UxGT("最長"); // "Longest" + LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("已擠出"); // "Extruded" #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("最低溫度"); // "Min Temp" - 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_A = LCD_STR_A _UxGT(" 驅動 %"); // X Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驅動 %"); // Y Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驅動 %"); // Z Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驅動 %"); // I Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驅動 %"); // J Driver % - PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驅動 %"); // K 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" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢複選項:"); // "RESUME OPTIONS:" - 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_KILL_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" - PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" + LSTR MSG_INFO_MIN_TEMP = _UxGT("最低溫度"); // "Min Temp" + LSTR MSG_INFO_MAX_TEMP = _UxGT("最高溫度"); // "Max Temp" + LSTR MSG_INFO_PSU = _UxGT("電源供應"); // "Power Supply" + LSTR MSG_DRIVE_STRENGTH = _UxGT("驅動力度"); // "Drive Strength" + LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" 驅動 %"); // X Driver % + LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驅動 %"); // Y Driver % + LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驅動 %"); // Z Driver % + LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驅動 %"); // I Driver % + LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驅動 %"); // J Driver % + LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驅動 %"); // K Driver % + LSTR MSG_DAC_PERCENT_E = _UxGT("E 驅動 %"); //E Driver % + LSTR MSG_ERROR_TMC = _UxGT("TMC連接錯誤"); // "TMC CONNECTION ERROR" + LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驅動設置"); // "DAC EEPROM Write" + LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("更換絲料"); // "FILAMENT CHANGE" + LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("列印已暫停"); // "PRINT PAUSED" + LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("裝載絲料"); // "LOAD FILAMENT" + LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("卸載絲料"); // "UNLOAD FILAMENT" + LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("恢複選項:"); // "RESUME OPTIONS:" + LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("清除更多"); // "Purge more" + LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("恢復列印"); // "Resume print" + LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 噴嘴: "); // " Nozzle: " + LSTR MSG_RUNOUT_SENSOR = _UxGT("斷絲偵測"); // "Runout Sensor" + LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("絲距離mm"); // "Runout Dist mm" + LSTR MSG_KILL_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" + LSTR MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" // // 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_PARKING = _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_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" + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("按下按鈕", "恢復列印")); //"Press Button to resume print" + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); // "Parking..." + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("等待開始", "絲料", "變更")); // "Wait for start of the filament change" + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("等待", "卸下絲料")); // "Wait for filament unload" + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("插入絲料", "並按鍵", "繼續 ...")); // "Insert filament and press button to continue..." + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("按下按鈕", "加熱噴嘴.")); // "Press button to heat nozzle." + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("加熱噴嘴", "請等待 ...")); // "Heating nozzle Please wait..." + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("等待", "進料")); // "Wait for filament load" + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("等待", "絲料清除")); // "Wait for filament purge" + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("按下完成","絲料清除")); //"Press button to filament purge" + LSTR 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_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); // "Parking..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); // "Please wait..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); // "Insert and Click" - 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_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成..")); // "Click to finish" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢復中 ...")); // "Resuming..." + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下繼續..")); // "Click to continue" + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("停車中 ...")); // "Parking..." + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); // "Please wait..." + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); // "Insert and Click" + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加熱..")); // "Click to heat" + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("加熱中 ...")); // "Heating..." + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("退出中 ...")); // "Ejecting..." + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("載入中 ...")); // "Loading..." + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("清除中 ...")); // "Purging..." + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成..")); // "Click to finish" + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢復中 ...")); // "Resuming..." #endif // LCD_HEIGHT < 4 } diff --git a/buildroot/share/scripts/findMissingTranslations.sh b/buildroot/share/scripts/findMissingTranslations.sh index 0cf77366d2..6e605ceeba 100755 --- a/buildroot/share/scripts/findMissingTranslations.sh +++ b/buildroot/share/scripts/findMissingTranslations.sh @@ -13,37 +13,34 @@ LANGHOME="Marlin/src/lcd/language" [ -d $LANGHOME ] && cd $LANGHOME -FILES=$(ls language_*.h | grep -v -E "(_en|_test)\.h" | sed -E 's/language_([^\.]+)\.h/\1/') -declare -A STRING_MAP +FILES=$(ls language_*.h | grep -v -E "(_en|_test)\.h" | sed -E 's/language_([^\.]+)\.h/\1/' | tr '\n' ' ') # Get files matching the given arguments -TEST_LANGS=$FILES +TEST_LANGS="" if [[ -n $@ ]]; then - TEST_LANGS="" for K in "$@"; do for F in $FILES; do - [[ "$F" != "${F%$K*}" ]] && TEST_LANGS="$TEST_LANGS $F" + [[ "$F" != "${F%$K*}" ]] && TEST_LANGS+="$F " done done + [[ -z $TEST_LANGS ]] && { echo "No languages matching $@." ; exit 0 ; } +else + TEST_LANGS=$FILES fi -echo -n "Building list of missing strings..." +echo "Missing strings for $TEST_LANGS..." -for i in $(awk '/Language_Str/{print $3}' language_en.h); do - [[ $i == "MSG_CUBED" ]] && continue +for WORD in $(awk '/LSTR/{print $2}' language_en.h); do LANG_LIST="" - for j in $TEST_LANGS; do - [[ $(grep -c " ${i} " language_${j}.h) -eq 0 ]] && LANG_LIST="$LANG_LIST $j" + for LANG in $TEST_LANGS; do + if [[ $(grep -c -E "^ *LSTR +$WORD\b" language_${LANG}.h) -eq 0 ]]; then + INHERIT=$(awk '/using namespace/{print $3}' language_${LANG}.h | sed -E 's/Language_([a-zA-Z_]+)\s*;/\1/') + if [[ -z $INHERIT || $INHERIT == "en" ]]; then + LANG_LIST+=" $LANG" + elif [[ $(grep -c -E "^ *LSTR +$WORD\b" language_${INHERIT}.h) -eq 0 ]]; then + LANG_LIST+=" $LANG" + fi + fi done - [[ -z $LANG_LIST ]] && continue - STRING_MAP[$i]=$LANG_LIST -done - -echo - -for K in $( printf "%s\n" "${!STRING_MAP[@]}" | sort ); do - case "$#" in - 1 ) echo $K ;; - * ) printf "%-35s :%s\n" "$K" "${STRING_MAP[$K]}" ;; - esac + [[ -n $LANG_LIST ]] && printf "%-38s :%s\n" "$WORD" "$LANG_LIST" done From 008284934c2f07ea335beec6086afd56a30d5829 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Sep 2021 18:58:12 -0500 Subject: [PATCH 0704/2168] =?UTF-8?q?=F0=9F=94=A8=20Case-insensitive=20tes?= =?UTF-8?q?ts=20list?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/mftest | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index 7a55033e9e..4ed1b9d951 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -208,7 +208,7 @@ if [[ $TESTENV == '-' ]]; then NAMES=() MENU=() BIGLEN=0 - for FILE in $( ls -1 $TESTPATH/* ) + for FILE in $( ls -1 $TESTPATH/* | sort -f ) do let IND++ TNAME=${FILE/$TESTPATH\//} From 216a66b42c8240f37befe98e6a410d1e3694ff4e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 19 Sep 2021 19:25:01 -0500 Subject: [PATCH 0705/2168] =?UTF-8?q?=F0=9F=8C=90=20Skip=20non-essential?= =?UTF-8?q?=20translations?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../extui/ftdi_eve_touch_ui/theme/bitmaps.h | 2 +- .../extui/ftdi_eve_touch_ui/theme/sounds.cpp | 2 +- .../extui/ftdi_eve_touch_ui/theme/sounds.h | 2 +- Marlin/src/lcd/language/language_an.h | 3 - Marlin/src/lcd/language/language_ca.h | 3 - Marlin/src/lcd/language/language_cz.h | 9 - Marlin/src/lcd/language/language_da.h | 3 - Marlin/src/lcd/language/language_de.h | 7 - Marlin/src/lcd/language/language_en.h | 43 ++--- Marlin/src/lcd/language/language_es.h | 10 -- Marlin/src/lcd/language/language_eu.h | 3 - Marlin/src/lcd/language/language_fr.h | 6 - Marlin/src/lcd/language/language_gl.h | 10 -- Marlin/src/lcd/language/language_hr.h | 1 - Marlin/src/lcd/language/language_hu.h | 17 -- Marlin/src/lcd/language/language_it.h | 7 - Marlin/src/lcd/language/language_jp_kana.h | 3 - Marlin/src/lcd/language/language_nl.h | 3 - Marlin/src/lcd/language/language_pl.h | 155 ------------------ Marlin/src/lcd/language/language_pt_br.h | 3 - Marlin/src/lcd/language/language_ro.h | 10 -- Marlin/src/lcd/language/language_ru.h | 6 +- Marlin/src/lcd/language/language_sk.h | 9 - Marlin/src/lcd/language/language_sv.h | 9 - Marlin/src/lcd/language/language_tr.h | 7 - Marlin/src/lcd/language/language_zh_CN.h | 6 - Marlin/src/lcd/language/language_zh_TW.h | 1 - .../share/scripts/findMissingTranslations.sh | 1 + 28 files changed, 30 insertions(+), 311 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h index 59394b89a6..c194225d99 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -256,4 +256,4 @@ namespace Theme { constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; constexpr PROGMEM uint32_t BACKGROUND_OFFSET = 40000; -}; // namespace Theme +} // namespace Theme diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp index 1ed712ded1..efeed19201 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp @@ -385,7 +385,7 @@ namespace Theme { {CHACK}, {SILENCE, END_SONG, 0} }; -}; // namespace Theme +} // namespace Theme #define N_ELEMENTS(a) (sizeof(a)/sizeof(a[0])) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h index 66c1cb810c..0ca78d4b62 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.h @@ -40,4 +40,4 @@ namespace Theme { extern const PROGMEM SoundPlayer::sound_t warble[]; extern const PROGMEM SoundPlayer::sound_t carousel[]; extern const PROGMEM SoundPlayer::sound_t all_instruments[]; -}; // namespace Theme +} // namespace Theme diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 7d0ff7320f..4669f0c233 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -177,9 +177,6 @@ namespace Language_an { LSTR MSG_ERR_MINTEMP = _UxGT("Error: Temp Min"); LSTR MSG_HALTED = _UxGT("IMPRESORA ATURADA"); LSTR MSG_PLEASE_RESET = _UxGT("Per favor reinic."); - LSTR MSG_SHORT_DAY = _UxGT("d"); - LSTR MSG_SHORT_HOUR = _UxGT("h"); - LSTR MSG_SHORT_MINUTE = _UxGT("m"); LSTR MSG_HEATING = _UxGT("Calentando..."); LSTR MSG_BED_HEATING = _UxGT("Calentando base..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 06db1e8186..c8f0d26a32 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -165,9 +165,6 @@ namespace Language_ca { LSTR MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); LSTR MSG_HALTED = _UxGT("IMPRESSORA PARADA"); LSTR MSG_PLEASE_RESET = _UxGT("Reinicieu"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Escalfant..."); LSTR MSG_BED_HEATING = _UxGT("Escalfant llit..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Calibratge Delta"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 0e10cd4be0..2ee0534f9d 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -420,9 +420,6 @@ namespace Language_cz { LSTR MSG_ERR_MINTEMP = _UxGT("NÍZKA TEPLOTA"); LSTR MSG_HALTED = _UxGT("TISK. ZASTAVENA"); LSTR MSG_PLEASE_RESET = _UxGT("Proveďte reset"); - LSTR MSG_SHORT_DAY = _UxGT("d"); - LSTR MSG_SHORT_HOUR = _UxGT("h"); - LSTR MSG_SHORT_MINUTE = _UxGT("m"); LSTR MSG_HEATING = _UxGT("Zahřívání..."); LSTR MSG_COOLING = _UxGT("Chlazení..."); #if LCD_WIDTH >= 20 @@ -602,12 +599,6 @@ namespace Language_cz { LSTR MSG_SERVICE_RESET = _UxGT("Reset"); LSTR MSG_SERVICE_IN = _UxGT(" za:"); LSTR MSG_BACKLASH = _UxGT("Vůle"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekce"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Vyhlazení"); } diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 4ce6089442..ef11906ed6 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -144,9 +144,6 @@ namespace Language_da { LSTR MSG_ERR_MINTEMP = _UxGT("Fejl: Min temp"); LSTR MSG_HALTED = _UxGT("PRINTER STOPPET"); LSTR MSG_PLEASE_RESET = _UxGT("Reset Venligst"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // Kun et bogstav - LSTR MSG_SHORT_HOUR = _UxGT("h"); // Kun et bogstav - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // Kun et bogstav LSTR MSG_HEATING = _UxGT("Opvarmer..."); LSTR MSG_BED_HEATING = _UxGT("Opvarmer plade..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 4c8b5e5af9..4aef4ac45c 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -35,7 +35,6 @@ namespace Language_de { LSTR LANGUAGE = _UxGT("Deutsch"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" bereit"); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("JA"); LSTR MSG_NO = _UxGT("NEIN"); LSTR MSG_BACK = _UxGT("Zurück"); @@ -630,12 +629,6 @@ namespace Language_de { LSTR MSG_SERVICE_RESET = _UxGT("Reset"); LSTR MSG_SERVICE_IN = _UxGT(" im:"); LSTR MSG_BACKLASH = _UxGT("Spiel"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); LSTR MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 520b5f7b21..85c689222b 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -47,8 +47,8 @@ namespace Language_en { constexpr uint8_t CHARSIZE = 2; LSTR LANGUAGE = _UxGT("English"); + // These strings should be translated LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Ready."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("YES"); LSTR MSG_NO = _UxGT("NO"); LSTR MSG_BACK = _UxGT("Back"); @@ -339,16 +339,6 @@ namespace Language_en { LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - LSTR MSG_PID_P = _UxGT("PID-P"); - LSTR MSG_PID_P_E = _UxGT("PID-P *"); - LSTR MSG_PID_I = _UxGT("PID-I"); - LSTR MSG_PID_I_E = _UxGT("PID-I *"); - LSTR MSG_PID_D = _UxGT("PID-D"); - LSTR MSG_PID_D_E = _UxGT("PID-D *"); - LSTR MSG_PID_C = _UxGT("PID-C"); - LSTR MSG_PID_C_E = _UxGT("PID-C *"); - LSTR MSG_PID_F = _UxGT("PID-F"); - LSTR MSG_PID_F_E = _UxGT("PID-F *"); LSTR MSG_SELECT = _UxGT("Select"); LSTR MSG_SELECT_E = _UxGT("Select *"); LSTR MSG_ACC = _UxGT("Accel"); @@ -542,9 +532,6 @@ namespace Language_en { LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Heating..."); LSTR MSG_COOLING = _UxGT("Cooling..."); LSTR MSG_BED_HEATING = _UxGT("Bed Heating..."); @@ -727,12 +714,6 @@ namespace Language_en { LSTR MSG_SERVICE_RESET = _UxGT("Reset"); LSTR MSG_SERVICE_IN = _UxGT(" in:"); LSTR MSG_BACKLASH = _UxGT("Backlash"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correction"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); @@ -764,6 +745,28 @@ namespace Language_en { LSTR MSG_SD_CARD = _UxGT("SD Card"); LSTR MSG_USB_DISK = _UxGT("USB Disk"); + + // These strings can be the same in all languages + LSTR MSG_MARLIN = _UxGT("Marlin"); + LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_PID_P = _UxGT("PID-P"); + LSTR MSG_PID_P_E = _UxGT("PID-P *"); + LSTR MSG_PID_I = _UxGT("PID-I"); + LSTR MSG_PID_I_E = _UxGT("PID-I *"); + LSTR MSG_PID_D = _UxGT("PID-D"); + LSTR MSG_PID_D_E = _UxGT("PID-D *"); + LSTR MSG_PID_C = _UxGT("PID-C"); + LSTR MSG_PID_C_E = _UxGT("PID-C *"); + LSTR MSG_PID_F = _UxGT("PID-F"); + LSTR MSG_PID_F_E = _UxGT("PID-F *"); + LSTR MSG_BACKLASH_A = LCD_STR_A; + LSTR MSG_BACKLASH_B = LCD_STR_B; + LSTR MSG_BACKLASH_C = LCD_STR_C; + LSTR MSG_BACKLASH_I = LCD_STR_I; + LSTR MSG_BACKLASH_J = LCD_STR_J; + LSTR MSG_BACKLASH_K = LCD_STR_K; } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 65930e6564..315a8413df 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -35,7 +35,6 @@ namespace Language_es { LSTR LANGUAGE = _UxGT("Spanish"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Lista"); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("SI"); LSTR MSG_NO = _UxGT("NO"); LSTR MSG_BACK = _UxGT("Atrás"); @@ -427,9 +426,6 @@ namespace Language_es { LSTR MSG_ERR_MINTEMP = _UxGT("Err:TEMP. MIN"); LSTR MSG_HALTED = _UxGT("IMPRESORA DETENIDA"); LSTR MSG_PLEASE_RESET = _UxGT("Por favor, reinicie"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Calentando..."); LSTR MSG_COOLING = _UxGT("Enfriando..."); LSTR MSG_BED_HEATING = _UxGT("Calentando Cama..."); @@ -588,12 +584,6 @@ namespace Language_es { LSTR MSG_SERVICE_RESET = _UxGT("Reiniciar"); LSTR MSG_SERVICE_IN = _UxGT(" dentro:"); LSTR MSG_BACKLASH = _UxGT("Backlash"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index a7e5bb2c58..fc8f2e0f62 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -252,9 +252,6 @@ namespace Language_eu { LSTR MSG_ERR_MINTEMP = _UxGT("Err: Tenp Minimoa"); LSTR MSG_HALTED = _UxGT("INPRIMA. GELDIRIK"); LSTR MSG_PLEASE_RESET = _UxGT("Berrabia. Mesedez"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Berotzen..."); LSTR MSG_BED_HEATING = _UxGT("Ohea Berotzen..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibraketa"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 46dd712ec2..be8daaa3dc 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -625,12 +625,6 @@ namespace Language_fr { LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop activé"); LSTR MSG_SERVICE_RESET = _UxGT("Réinit."); LSTR MSG_SERVICE_IN = _UxGT(" dans:"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correction"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Lissage"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 54a323034e..ad85ac9b48 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -37,7 +37,6 @@ namespace Language_gl { LSTR LANGUAGE = _UxGT("Galician"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" lista."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("SI"); LSTR MSG_NO = _UxGT("NON"); LSTR MSG_BACK = _UxGT("Atrás"); @@ -443,9 +442,6 @@ namespace Language_gl { LSTR MSG_ERR_MINTEMP = _UxGT("Erro:TEMP MÍN"); LSTR MSG_HALTED = _UxGT("IMPRESORA DETIDA"); LSTR MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Quentando..."); LSTR MSG_COOLING = _UxGT("Arrefriando..."); LSTR MSG_BED_HEATING = _UxGT("Quentando cama..."); @@ -605,12 +601,6 @@ namespace Language_gl { LSTR MSG_SERVICE_RESET = _UxGT("Reiniciar"); LSTR MSG_SERVICE_IN = _UxGT(" dentro:"); LSTR MSG_BACKLASH = _UxGT("Reacción"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index f0da04b063..e828b489f6 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -166,6 +166,5 @@ namespace Language_hr { #else // Up to 2 lines allowed LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT("Pričekaj..."); - //LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_2_LINE("?", "?")); #endif } diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 83e58de158..2c06a51c19 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -40,7 +40,6 @@ namespace Language_hu { LSTR LANGUAGE = _UxGT("Magyar"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Kész."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("IGEN"); LSTR MSG_NO = _UxGT("NEM"); LSTR MSG_BACK = _UxGT("Vissza"); @@ -317,16 +316,6 @@ namespace Language_hu { LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); LSTR MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); - LSTR MSG_PID_P = _UxGT("PID-P"); - LSTR MSG_PID_P_E = _UxGT("PID-P *"); - LSTR MSG_PID_I = _UxGT("PID-I"); - LSTR MSG_PID_I_E = _UxGT("PID-I *"); - LSTR MSG_PID_D = _UxGT("PID-D"); - LSTR MSG_PID_D_E = _UxGT("PID-D *"); - LSTR MSG_PID_C = _UxGT("PID-C"); - LSTR MSG_PID_C_E = _UxGT("PID-C *"); - LSTR MSG_PID_F = _UxGT("PID-F"); - LSTR MSG_PID_F_E = _UxGT("PID-F *"); LSTR MSG_SELECT = _UxGT("Kiválaszt"); LSTR MSG_SELECT_E = _UxGT("Kiválaszt *"); LSTR MSG_ACC = _UxGT("Gyorsítás"); @@ -703,12 +692,6 @@ namespace Language_hu { LSTR MSG_SERVICE_RESET = _UxGT("Újraindítás"); LSTR MSG_SERVICE_IN = _UxGT(" be:"); LSTR MSG_BACKLASH = _UxGT("Holtjáték"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrekció"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Simítás"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index c8ee795e61..e005567985 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -44,7 +44,6 @@ namespace Language_it { LSTR LANGUAGE = _UxGT("Italiano"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("Si"); LSTR MSG_NO = _UxGT("No"); LSTR MSG_BACK = _UxGT("Indietro"); @@ -700,12 +699,6 @@ namespace Language_it { LSTR MSG_SERVICE_IN = _UxGT(" tra:"); LSTR MSG_BACKLASH = _UxGT("Gioco"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 5864280dd5..1d291ed3ad 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -192,9 +192,6 @@ namespace Language_jp_kana { LSTR MSG_ERR_MINTEMP = _UxGT("エラー:サイテイオンミマン"); // "Err: MINTEMP" LSTR MSG_HALTED = _UxGT("プリンターハテイシシマシタ"); // "PRINTER HALTED" LSTR MSG_PLEASE_RESET = _UxGT("リセットシテクダサイ"); // "Please reset" - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("カネツチュウ"); // "Heating..." LSTR MSG_BED_HEATING = _UxGT("ベッド カネツチュウ"); // "Bed Heating..." LSTR MSG_DELTA_CALIBRATE = _UxGT("デルタ コウセイ"); // "Delta Calibration" diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 786fa88298..b44d09d07c 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -166,9 +166,6 @@ namespace Language_nl { LSTR MSG_ERR_MINTEMP = _UxGT("Err: Min. temp"); LSTR MSG_HALTED = _UxGT("PRINTER GESTOPT"); LSTR MSG_PLEASE_RESET = _UxGT("Reset A.U.B."); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only. Keep English standard - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Voorwarmen..."); LSTR MSG_BED_HEATING = _UxGT("Bed voorverw..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Calibratie"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 3e19150a77..b37e1d80cf 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -44,7 +44,6 @@ namespace Language_pl { LSTR LANGUAGE = _UxGT("Polski"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); - //LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("TAK"); LSTR MSG_NO = _UxGT("NIE"); LSTR MSG_BACK = _UxGT("Wstecz"); @@ -56,7 +55,6 @@ namespace Language_pl { LSTR MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); - //LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); LSTR MSG_MAIN = _UxGT("Menu główne"); @@ -71,7 +69,6 @@ namespace Language_pl { LSTR MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); - //LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); LSTR MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); @@ -80,12 +77,8 @@ namespace Language_pl { LSTR MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); - //LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); - //LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); - //LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); LSTR MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); - //LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); LSTR MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); LSTR MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if PREHEAT_COUNT @@ -113,15 +106,6 @@ namespace Language_pl { LSTR MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); LSTR MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); LSTR MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); - //LSTR MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); - //LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); - //LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); - //LSTR MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); - //LSTR MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); - //LSTR MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); - //LSTR MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); - //LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); - //LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); LSTR MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); LSTR MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); LSTR MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); @@ -131,10 +115,6 @@ namespace Language_pl { LSTR MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); LSTR MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); LSTR MSG_BED_TRAMMING = _UxGT("Narożniki poziomowania"); - //LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Raise Bed Until Probe Triggered"); - //LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); - //LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); - //LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); LSTR MSG_MESH_EDITOR = _UxGT("Edytor siatki"); LSTR MSG_EDIT_MESH = _UxGT("Edycja siatki"); @@ -146,7 +126,6 @@ namespace Language_pl { LSTR MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); LSTR MSG_M48_TEST = _UxGT("M48 Test sondy"); LSTR MSG_M48_POINT = _UxGT("M48 Punky"); - //LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); LSTR MSG_M48_DEVIATION = _UxGT("Odchylenie"); LSTR MSG_IDEX_MENU = _UxGT("Tryb IDEX"); LSTR MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); @@ -154,16 +133,13 @@ namespace Language_pl { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); - //LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); LSTR MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); LSTR MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); LSTR MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); - //LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); - //LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); LSTR MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); LSTR MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); LSTR MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); @@ -247,8 +223,6 @@ namespace Language_pl { LSTR MSG_SET_LEDS_WHITE = _UxGT("Biały"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); LSTR MSG_LED_CHANNEL_N = _UxGT("Kanał ="); - //LSTR MSG_LEDS2 = _UxGT("Lights #2"); - //LSTR MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); LSTR MSG_CUSTOM_LEDS = _UxGT("Własne światła"); LSTR MSG_INTENSITY_R = _UxGT("Czerwony"); @@ -277,29 +251,17 @@ namespace Language_pl { LSTR MSG_BED_Z = _UxGT("Stół Z"); LSTR MSG_NOZZLE = _UxGT("Dysza"); LSTR MSG_NOZZLE_N = _UxGT("Dysza ~"); - //LSTR MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); LSTR MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); LSTR MSG_BED = _UxGT("Stół"); LSTR MSG_CHAMBER = _UxGT("Obudowa"); - //LSTR MSG_COOLER = _UxGT("Laser Coolant"); - //LSTR MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); - //LSTR MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); - //LSTR MSG_LASER = _UxGT("Laser"); LSTR MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); LSTR MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); - //LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); LSTR MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); - //LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); - //LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); - //LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); - //LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); LSTR MSG_FLOW = _UxGT("Przepływ"); LSTR MSG_FLOW_N = _UxGT("Przepływ ~"); LSTR MSG_CONTROL = _UxGT("Ustawienia"); - //LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - //LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); LSTR MSG_AUTOTEMP = _UxGT("Auto. temperatura"); LSTR MSG_LCD_ON = _UxGT("Wł."); @@ -307,19 +269,6 @@ namespace Language_pl { LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); - //LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); - //LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); - //LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); - //LSTR MSG_PID_P = _UxGT("PID-P"); - //LSTR MSG_PID_P_E = _UxGT("PID-P *"); - //LSTR MSG_PID_I = _UxGT("PID-I"); - //LSTR MSG_PID_I_E = _UxGT("PID-I *"); - //LSTR MSG_PID_D = _UxGT("PID-D"); - //LSTR MSG_PID_D_E = _UxGT("PID-D *"); - //LSTR MSG_PID_C = _UxGT("PID-C"); - //LSTR MSG_PID_C_E = _UxGT("PID-C *"); - //LSTR MSG_PID_F = _UxGT("PID-F"); - //LSTR MSG_PID_F_E = _UxGT("PID-F *"); LSTR MSG_SELECT = _UxGT("Wybierz"); LSTR MSG_SELECT_E = _UxGT("Wybierz *"); LSTR MSG_ACC = _UxGT("Przyspieszenie"); @@ -331,7 +280,6 @@ namespace Language_pl { LSTR MSG_VJ_JERK = _UxGT("Zryw V") LCD_STR_J; LSTR MSG_VK_JERK = _UxGT("Zryw V") LCD_STR_K; LSTR MSG_VE_JERK = _UxGT("Zryw Ve"); - //LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_VELOCITY = _UxGT("Prędkość (V)"); LSTR MSG_VTRAV_MIN = _UxGT("Vskok min"); @@ -340,7 +288,6 @@ namespace Language_pl { LSTR MSG_A_RETRACT = _UxGT("A-wycofanie"); LSTR MSG_A_TRAVEL = _UxGT("A-przesuń."); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); - //LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); LSTR MSG_STEPS_PER_MM = _UxGT("kroki/mm"); LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); @@ -352,39 +299,28 @@ namespace Language_pl { LSTR MSG_EN_STEPS = _UxGT("* kroki/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); LSTR MSG_MOTION = _UxGT("Ruch"); - //LSTR MSG_FILAMENT = _UxGT("Filament"); LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; - //LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; - //LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); LSTR MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); LSTR MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); LSTR MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); LSTR MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); - //LSTR MSG_ADVANCE_K = _UxGT("Advance K"); - //LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); LSTR MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); LSTR MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); LSTR MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); - //LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); - //LSTR MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); - //LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); - //LSTR MSG_SETTINGS_STORED = _UxGT("Settings Stored"); LSTR MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); LSTR MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); LSTR MSG_INFO_SCREEN = _UxGT("Ekran główny"); LSTR MSG_PREPARE = _UxGT("Przygotuj"); LSTR MSG_TUNE = _UxGT("Strojenie"); - //LSTR MSG_POWER_MONITOR = _UxGT("Power monitor"); LSTR MSG_CURRENT = _UxGT("Natężenie"); LSTR MSG_VOLTAGE = _UxGT("Napięcie"); LSTR MSG_POWER = _UxGT("Moc"); LSTR MSG_START_PRINT = _UxGT("Start wydruku"); LSTR MSG_BUTTON_NEXT = _UxGT("Następny"); LSTR MSG_BUTTON_INIT = _UxGT("Inic."); - //LSTR MSG_BUTTON_STOP = _UxGT("Stop"); LSTR MSG_BUTTON_PRINT = _UxGT("Drukuj"); LSTR MSG_BUTTON_RESET = _UxGT("Resetuj"); LSTR MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); @@ -396,9 +332,7 @@ namespace Language_pl { LSTR MSG_PAUSING = _UxGT("Wstrzymywanie..."); LSTR MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); LSTR MSG_RESUME_PRINT = _UxGT("Wznowienie"); - //LSTR MSG_HOST_START_PRINT = _UxGT("Host Start"); LSTR MSG_STOP_PRINT = _UxGT("Stop"); - //LSTR MSG_END_LOOPS = _UxGT("End Repeat Loops"); LSTR MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); LSTR MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); @@ -420,26 +354,14 @@ namespace Language_pl { LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); - //LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); LSTR MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); - //LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); LSTR MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); - //LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); - //LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); - //LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); - //LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); - //LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); - //LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); - //LSTR MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); - //LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); - //LSTR MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); - //LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); LSTR MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); LSTR MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); LSTR MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); @@ -452,35 +374,12 @@ namespace Language_pl { LSTR MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); LSTR MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); - //LSTR MSG_BLTOUCH = _UxGT("BLTouch"); LSTR MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); LSTR MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - //LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); - //LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - //LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - //LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - //LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - //LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); - //LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); - //LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); - //LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); - //LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - //LSTR MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); - //LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); - //LSTR MSG_TOUCHMI_SAVE = _UxGT("Save"); - //LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); - //LSTR MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); - //LSTR MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); LSTR MSG_HOME_FIRST = _UxGT("Najpierw Home %s%s%s"); - //LSTR MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); - //LSTR MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); - //LSTR MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); - //LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); - //LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - //LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); LSTR MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); @@ -488,24 +387,17 @@ namespace Language_pl { LSTR MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); - //LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); - //LSTR MSG_COOLING_FAILED = _UxGT("Cooling Failed"); LSTR MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); LSTR MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); LSTR MSG_HALTED = _UxGT("Drukarka zatrzym."); LSTR MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); - //LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only LSTR MSG_SHORT_HOUR = _UxGT("g"); // One character only - //LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Rozgrzewanie..."); LSTR MSG_COOLING = _UxGT("Chłodzenie..."); LSTR MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); LSTR MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); - //LSTR MSG_PROBE_HEATING = _UxGT("Probe Heating..."); - //LSTR MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); LSTR MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); LSTR MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); - //LSTR MSG_LASER_COOLING = _UxGT("Laser Cooling..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); @@ -523,9 +415,7 @@ namespace Language_pl { LSTR MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); LSTR MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); LSTR MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); - //LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); LSTR MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); - //LSTR MSG_MESH_DONE = _UxGT("Mesh probing done"); LSTR MSG_INFO_STATS_MENU = _UxGT("Statystyki"); LSTR MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -534,7 +424,6 @@ namespace Language_pl { LSTR MSG_INFO_PROTOCOL = _UxGT("Protokół"); LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); - //LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); LSTR MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); @@ -554,8 +443,6 @@ namespace Language_pl { LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #endif - //LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - //LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("Zasilacz"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Siła %"); @@ -581,7 +468,6 @@ namespace Language_pl { LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); - //LSTR MSG_MMU2_MENU = _UxGT("MMU"); LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); LSTR MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); @@ -596,7 +482,6 @@ namespace Language_pl { LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); LSTR MSG_MMU2_ALL = _UxGT("Wszystko"); - //LSTR MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); LSTR MSG_MMU2_RESET = _UxGT("Resetuj MMU"); LSTR MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); @@ -604,30 +489,12 @@ namespace Language_pl { LSTR MSG_MIX = _UxGT("Miks"); LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); LSTR MSG_MIXER = _UxGT("Mikser"); - //LSTR MSG_GRADIENT = _UxGT("Gradient"); LSTR MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); LSTR MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); - //LSTR MSG_CYCLE_MIX = _UxGT("Cycle Mix"); - //LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); LSTR MSG_REVERSE_GRADIENT = _UxGT("Odwrotny gradient"); - //LSTR MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); - //LSTR MSG_START_VTOOL = _UxGT("Start V-tool"); - //LSTR MSG_END_VTOOL = _UxGT(" End V-tool"); - //LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); - //LSTR MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); - //LSTR MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); - //LSTR MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); - //LSTR MSG_START_Z = _UxGT("Start Z:"); - //LSTR MSG_END_Z = _UxGT(" End Z:"); LSTR MSG_GAMES = _UxGT("Gry"); - //LSTR MSG_BRICKOUT = _UxGT("Brickout"); - //LSTR MSG_INVADERS = _UxGT("Invaders"); - //LSTR MSG_SNAKE = _UxGT("Sn4k3"); - //LSTR MSG_MAZE = _UxGT("Maze"); - //LSTR MSG_BAD_PAGE = _UxGT("Bad page index"); - //LSTR MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); LSTR MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); LSTR MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); @@ -671,40 +538,18 @@ namespace Language_pl { #endif LSTR MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); LSTR MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); - //LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); LSTR MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); - //LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); - //LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); - //LSTR MSG_SERVICE_RESET = _UxGT("Reset"); - //LSTR MSG_SERVICE_IN = _UxGT(" in:"); - //LSTR MSG_BACKLASH = _UxGT("Backlash"); LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekcja"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); LSTR MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); LSTR MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); - #if ENABLED(TOUCH_UI_FTDI_EVE) - //LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); - #else - //LSTR MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); - #endif - //LSTR MSG_REHEAT = _UxGT("Reheat"); - //LSTR MSG_REHEATING = _UxGT("Reheating..."); - - //LSTR MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); - //LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); - //LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); LSTR MSG_SOUND = _UxGT("Dźwięk"); - //LSTR MSG_TOP_LEFT = _UxGT("Top Left"); - //LSTR MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); - //LSTR MSG_TOP_RIGHT = _UxGT("Top Right"); - //LSTR MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); - //LSTR MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index f5ab03c44a..45e1879d4c 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -365,9 +365,6 @@ namespace Language_pt_br { LSTR MSG_ERR_MINTEMP = _UxGT("Erro:Temp Mínima"); LSTR MSG_HALTED = _UxGT("IMPRESSORA PAROU"); LSTR MSG_PLEASE_RESET = _UxGT("Favor resetar"); - LSTR MSG_SHORT_DAY = _UxGT("d"); - LSTR MSG_SHORT_HOUR = _UxGT("h"); - LSTR MSG_SHORT_MINUTE = _UxGT("m"); LSTR MSG_HEATING = _UxGT("Aquecendo..."); LSTR MSG_COOLING = _UxGT("Resfriando..."); LSTR MSG_BED_HEATING = _UxGT("Aquecendo mesa..."); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 364a83fb3f..6db2fe38fa 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -36,7 +36,6 @@ namespace Language_ro { LSTR LANGUAGE = _UxGT("Romanian"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Pregatit."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("DA"); LSTR MSG_NO = _UxGT("NU"); LSTR MSG_BACK = _UxGT("Inapoi"); @@ -449,9 +448,6 @@ namespace Language_ro { LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Heating..."); LSTR MSG_COOLING = _UxGT("Cooling..."); LSTR MSG_BED_HEATING = _UxGT("Bed Heating..."); @@ -618,12 +614,6 @@ namespace Language_ro { LSTR MSG_SERVICE_RESET = _UxGT("Reset"); LSTR MSG_SERVICE_IN = _UxGT(" in:"); LSTR MSG_BACKLASH = _UxGT("Backlash"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Corectare"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 83fd5a3ac3..25ea5fd471 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -40,9 +40,9 @@ namespace Language_ru { LSTR MSG_NO = _UxGT("Нет"); LSTR MSG_BACK = _UxGT("Назад"); LSTR MSG_MEDIA_ABORTING = _UxGT("Прерывание..."); - LSTR MSG_MEDIA_INSERTED = _UxGT("SD-карта вставлена"); - LSTR MSG_MEDIA_REMOVED = _UxGT("SD-карта извлечена"); - LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD-карту"); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD карта вставлена"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD карта извлечена"); + LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD карту"); #if LCD_WIDTH > 21 LSTR MSG_SD_INIT_FAIL = _UxGT("Сбой инициализации SD"); #else diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 4fe67494e2..3a9eb23a8f 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -530,9 +530,6 @@ namespace Language_sk { LSTR MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); LSTR MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); LSTR MSG_PLEASE_RESET = _UxGT("Reštartuje ju"); - LSTR MSG_SHORT_DAY = _UxGT("d"); - LSTR MSG_SHORT_HOUR = _UxGT("h"); - LSTR MSG_SHORT_MINUTE = _UxGT("m"); LSTR MSG_HEATING = _UxGT("Ohrev..."); LSTR MSG_COOLING = _UxGT("Ochladzovanie..."); LSTR MSG_BED_HEATING = _UxGT("Ohrev podložky..."); @@ -715,12 +712,6 @@ namespace Language_sk { LSTR MSG_SERVICE_RESET = _UxGT("Vynulovať"); LSTR MSG_SERVICE_IN = _UxGT("za:"); LSTR MSG_BACKLASH = _UxGT("Kompenz. vôle"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korekcia"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Vyhladzovanie"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 9194dc4861..91a842fe2d 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -37,7 +37,6 @@ namespace Language_sv { LSTR LANGUAGE = _UxGT("Swedish"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Redo."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("JA"); LSTR MSG_NO = _UxGT("NEJ"); LSTR MSG_BACK = _UxGT("Bakåt"); @@ -483,9 +482,7 @@ namespace Language_sv { LSTR MSG_ERR_MINTEMP = _UxGT("Fel: MINTEMP"); LSTR MSG_HALTED = _UxGT("Utskrift stoppad"); LSTR MSG_PLEASE_RESET = _UxGT("Snälla Återställ"); - LSTR MSG_SHORT_DAY = _UxGT("d"); // One character only LSTR MSG_SHORT_HOUR = _UxGT("t"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only LSTR MSG_HEATING = _UxGT("Värmer..."); LSTR MSG_COOLING = _UxGT("Kyler..."); LSTR MSG_BED_HEATING = _UxGT("Bädd Värmer..."); @@ -665,12 +662,6 @@ namespace Language_sv { LSTR MSG_SERVICE_RESET = _UxGT("Återställ"); LSTR MSG_SERVICE_IN = _UxGT(" in:"); LSTR MSG_BACKLASH = _UxGT("Backlash"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrigering"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glättning"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index e56071405c..9525a952a1 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -41,7 +41,6 @@ namespace Language_tr { LSTR LANGUAGE = _UxGT("Turkish"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" hazır."); - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("EVET"); LSTR MSG_NO = _UxGT("HAYIR"); LSTR MSG_BACK = _UxGT("Geri"); @@ -583,12 +582,6 @@ namespace Language_tr { LSTR MSG_SERVICE_RESET = _UxGT("Resetle"); LSTR MSG_SERVICE_IN = _UxGT(" içinde:"); LSTR MSG_BACKLASH = _UxGT("Ters Tepki"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("Düzeltme"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Yumuşatma"); } diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 2d9dc725f9..60ffb27337 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -617,12 +617,6 @@ namespace Language_zh_CN { LSTR MSG_SERVICE_RESET = _UxGT("复位"); LSTR MSG_SERVICE_IN = _UxGT(" 在:"); LSTR MSG_BACKLASH = _UxGT("回差"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; LSTR MSG_BACKLASH_CORRECTION = _UxGT("校正"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("平滑的"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 42bb5be080..fd43fefd29 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -34,7 +34,6 @@ namespace Language_zh_TW { LSTR LANGUAGE = _UxGT("Traditional Chinese"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); // " ready." - LSTR MSG_MARLIN = _UxGT("Marlin"); LSTR MSG_YES = _UxGT("是"); // "YES" LSTR MSG_NO = _UxGT("否"); // "NO" LSTR MSG_BACK = _UxGT("返回"); // "Back" diff --git a/buildroot/share/scripts/findMissingTranslations.sh b/buildroot/share/scripts/findMissingTranslations.sh index 6e605ceeba..24a2a910a2 100755 --- a/buildroot/share/scripts/findMissingTranslations.sh +++ b/buildroot/share/scripts/findMissingTranslations.sh @@ -31,6 +31,7 @@ fi echo "Missing strings for $TEST_LANGS..." for WORD in $(awk '/LSTR/{print $2}' language_en.h); do + [[ $WORD == "MSG_MARLIN" ]] && break LANG_LIST="" for LANG in $TEST_LANGS; do if [[ $(grep -c -E "^ *LSTR +$WORD\b" language_${LANG}.h) -eq 0 ]]; then From e60e4b8f57806147741e87e2820c258c4b51cf91 Mon Sep 17 00:00:00 2001 From: Lefteris Garyfalakis <46350667+lefterisgar@users.noreply.github.com> Date: Mon, 20 Sep 2021 03:26:46 +0300 Subject: [PATCH 0706/2168] =?UTF-8?q?=F0=9F=8C=90=20Update=20Greek=20langu?= =?UTF-8?q?age=20(#22799)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 4 +- Marlin/src/core/language.h | 4 +- .../{langdata_el_gr.h => langdata_el_CY.h} | 2 +- Marlin/src/lcd/language/language_el.h | 2 +- Marlin/src/lcd/language/language_el_CY.h | 38 +++++++++++++++++++ buildroot/share/fonts/genallfont.sh | 2 +- buildroot/tests/mega2560 | 4 +- 7 files changed, 47 insertions(+), 9 deletions(-) rename Marlin/src/lcd/dogm/fontdata/{langdata_el_gr.h => langdata_el_CY.h} (99%) create mode 100644 Marlin/src/lcd/language/language_el_CY.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5abb4fd729..13dc6a2b2c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2044,10 +2044,10 @@ * * Select the language to display on the LCD. These languages are available: * - * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it, + * en, an, bg, ca, cz, da, de, el, el_CY, es, eu, fi, fr, gl, hr, hu, it, * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek (Greece)', 'el_CY':'Greek (Cyprus)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' } */ #define LCD_LANGUAGE en diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 7588a7b28c..6c034d6b13 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -48,8 +48,8 @@ // cz Czech // da Danish // de German -// el Greek -// el_gr Greek (Greece) +// el Greek (Greece) +// el_CY Greek (Cyprus) // en English // es Spanish // eu Basque-Euskera diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h b/Marlin/src/lcd/dogm/fontdata/langdata_el_CY.h similarity index 99% rename from Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h rename to Marlin/src/lcd/dogm/fontdata/langdata_el_CY.h index 8d7cba8615..c3a2264aec 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_el_gr.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_el_CY.h @@ -77,7 +77,7 @@ const u8g_fntpgm_uint8_t fontpage_64_166_166[24] U8G_FONT_SECTION("fontpage_64_1 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0xA6,0xA6,0x00,0x01,0x00,0x00, 0x00,0x05,0x01,0x01,0x06,0x00,0x00,0xA8}; -static const uxg_fontinfo_t g_fontinfo_el_gr[] PROGMEM = { +static const uxg_fontinfo_t g_fontinfo_el_CY[] PROGMEM = { FONTDATA_ITEM(7, 136, 136, fontpage_7_136_136), // 'Έ' -- 'Έ' FONTDATA_ITEM(7, 145, 157, fontpage_7_145_157), // 'Α' -- 'Ν' FONTDATA_ITEM(7, 159, 161, fontpage_7_159_161), // 'Ο' -- 'Ρ' diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 625c3840d0..21f5ca6503 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -34,7 +34,7 @@ namespace Language_el { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - LSTR LANGUAGE = _UxGT("Greek"); + LSTR LANGUAGE = _UxGT("Greek (Greece)"); LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" έτοιμος."); LSTR MSG_YES = _UxGT("ΝΑΙ"); diff --git a/Marlin/src/lcd/language/language_el_CY.h b/Marlin/src/lcd/language/language_el_CY.h new file mode 100644 index 0000000000..68e9ee1459 --- /dev/null +++ b/Marlin/src/lcd/language/language_el_CY.h @@ -0,0 +1,38 @@ +/** + * 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 + +/** + * Greek (Cyprus) + * + * LCD Menu Messages + * See also https://marlinfw.org/docs/development/lcd_language.html + */ + +#include "language_el.h" + +namespace Language_el_CY { + using namespace Language_el; // Inherit undefined strings from Greek (or English) + + constexpr uint8_t CHARSIZE = 2; + LSTR LANGUAGE = _UxGT("Greek (Cyprus)"); +} diff --git a/buildroot/share/fonts/genallfont.sh b/buildroot/share/fonts/genallfont.sh index bffe715b9d..ebb99b273f 100755 --- a/buildroot/share/fonts/genallfont.sh +++ b/buildroot/share/fonts/genallfont.sh @@ -62,7 +62,7 @@ OLDWD=`pwd` # # By default loop through all languages # -LANGS_DEFAULT="an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana ko_KR nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test" +LANGS_DEFAULT="an bg ca cz da de el el_CY en es eu fi fr gl hr hu it jp_kana ko_KR nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test" # # Generate data for language list MARLIN_LANGS or all if not provided diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 723d133081..7d28a00d92 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -215,11 +215,11 @@ exec_test $1 $2 "MEGA2560 RAMPS | Redundant temperature sensor | 2x MAX6675" "$3 # #restore_configs #opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done +#for lang in an bg ca cz da de el el_CY en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done # #restore_configs #opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT -#for lang in an bg ca cz da de el el_gr en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done +#for lang in an bg ca cz da de el el_CY en es eu fi fr gl hr hu it jp_kana nl pl pt pt_br ro ru sk sv tr uk vi zh_CN zh_TW test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; exec_test $1 $2 "Stuff" "$3"; done ######## Example Configurations ############## # From f3864a1ae7b45fbc0359a65e4dc75ce062e39479 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 20 Sep 2021 01:03:16 +0000 Subject: [PATCH 0707/2168] [cron] Bump distribution date (2021-09-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 727ca38d89..4164248807 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-19" +//#define STRING_DISTRIBUTION_DATE "2021-09-20" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 16ab0c5458..664fbd87cf 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 "2021-09-19" + #define STRING_DISTRIBUTION_DATE "2021-09-20" #endif /** From 3344071f24b505d180dd1423b11510172c3f1c1c Mon Sep 17 00:00:00 2001 From: Dan Royer Date: Mon, 20 Sep 2021 13:42:33 -0700 Subject: [PATCH 0708/2168] Polargraph / Makelangelo kinematics (#22790) --- Marlin/Configuration.h | 7 + Marlin/src/MarlinCore.cpp | 2 + Marlin/src/core/language.h | 7 +- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 2 + Marlin/src/gcode/calibrate/M665.cpp | 25 ++- Marlin/src/gcode/control/M280.cpp | 36 +++- Marlin/src/gcode/control/M282.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/gcode/gcode.h | 1 + Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/lcd/menu/menu_advanced.cpp | 6 +- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/motion.h | 8 + Marlin/src/module/planner.cpp | 4 +- Marlin/src/module/planner.h | 2 + Marlin/src/module/polargraph.cpp | 47 +++++ Marlin/src/module/polargraph.h | 33 ++++ Marlin/src/module/settings.cpp | 171 ++++++++++-------- Marlin/src/pins/ramps/pins_RUMBA.h | 27 ++- buildroot/tests/mega1280 | 1 + buildroot/tests/mega2560 | 10 +- ini/features.ini | 1 + platformio.ini | 4 +- 24 files changed, 304 insertions(+), 104 deletions(-) create mode 100644 Marlin/src/module/polargraph.cpp create mode 100644 Marlin/src/module/polargraph.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 13dc6a2b2c..7afb86dac7 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -761,6 +761,13 @@ // Enable for a belt style printer with endless "Z" motion //#define BELTPRINTER +// Enable for Polargraph Kinematics +//#define POLARGRAPH +#if ENABLED(POLARGRAPH) + #define POLARGRAPH_MAX_BELT_LEN 1035.0 + #define POLAR_SEGMENTS_PER_SECOND 5 +#endif + //=========================================================================== //============================== Endstop Settings =========================== //=========================================================================== diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 147853eaf9..280c619ad2 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -168,6 +168,8 @@ #if ENABLED(DELTA) #include "module/delta.h" +#elif ENABLED(POLARGRAPH) + #include "module/polargraph.h" #elif IS_SCARA #include "module/scara.h" #endif diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 6c034d6b13..03bffb8bd9 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -264,9 +264,10 @@ // Settings Report Strings #define STR_Z_AUTO_ALIGN "Z Auto-Align" #define STR_BACKLASH_COMPENSATION "Backlash compensation" -#define STR_DELTA_SETTINGS "Delta settings (L R H S XYZ ABC)" -#define STR_SCARA_SETTINGS "SCARA settings" -#define STR_SCARA_S "S" +#define STR_S_SEG_PER_SEC "S" +#define STR_DELTA_SETTINGS "Delta (L R H S XYZ ABC)" +#define STR_SCARA_SETTINGS "SCARA" +#define STR_POLARGRAPH_SETTINGS "Polargraph" #define STR_SCARA_P_T_Z "P T Z" #define STR_ENDSTOP_ADJUSTMENT "Endstop adjustment" #define STR_SKEW_FACTOR "Skew Factor" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index be5f6fee12..f7e98c9fa7 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -324,6 +324,8 @@ #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm #elif ENABLED(DELTA) #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND) + #elif ENABLED(POLARGRAPH) + #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND) #else // CARTESIAN #ifdef LEVELED_SEGMENT_LENGTH #define DELTA_SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 09b5ec8d4e..11de1ce434 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -132,7 +132,7 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_SCARA_S TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); + report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); SERIAL_ECHOLNPGM_P( PSTR(" M665 S"), segments_per_second #if HAS_SCARA_OFFSET @@ -143,6 +143,29 @@ ); } +#elif ENABLED(POLARGRAPH) + + #include "../../module/polargraph.h" + + /** + * M665: Set POLARGRAPH settings + * + * Parameters: + * + * S[segments-per-second] - Segments-per-second + */ + void GcodeSuite::M665() { + if (parser.seenval('S')) + segments_per_second = parser.value_float(); + else + M665_report(); + } + + void GcodeSuite::M665_report(const bool forReplay/*=true*/) { + report_heading_etc(forReplay, PSTR(STR_POLARGRAPH_SETTINGS " (" STR_S_SEG_PER_SEC ")")); + SERIAL_ECHOLNPGM(" M665 S", segments_per_second); + } + #endif #endif // IS_KINEMATIC diff --git a/Marlin/src/gcode/control/M280.cpp b/Marlin/src/gcode/control/M280.cpp index f285adf47f..2a8e73eafb 100644 --- a/Marlin/src/gcode/control/M280.cpp +++ b/Marlin/src/gcode/control/M280.cpp @@ -26,22 +26,44 @@ #include "../gcode.h" #include "../../module/servo.h" +#include "../../module/planner.h" /** - * M280: Get or set servo position. P [S] + * M280: Get or set servo position. + * P - Servo index + * S - Angle to set, omit to read current angle, or use -1 to detach + * + * With POLARGRAPH: + * T - Duration of servo move */ void GcodeSuite::M280() { - if (!parser.seen('P')) return; + if (!parser.seenval('P')) return; + + TERN_(POLARGRAPH, planner.synchronize()); const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) { - if (parser.seen('S')) { - const int a = parser.value_int(); - if (a == -1) - DETACH_SERVO(servo_index); + if (parser.seenval('S')) { + const int anew = parser.value_int(); + if (anew >= 0) { + #if ENABLED(POLARGRAPH) + if (parser.seen('T')) { // (ms) Total duration of servo move + const int16_t t = constrain(parser.value_int(), 0, 10000); + const int aold = servo[servo_index].read(); + millis_t now = millis(); + const millis_t start = now, end = start + t; + while (PENDING(now, end)) { + safe_delay(50); + now = _MIN(millis(), end); + MOVE_SERVO(servo_index, LROUND(aold + (anew - aold) * (float(now - start) / t))); + } + } + #endif // POLARGRAPH + MOVE_SERVO(servo_index, anew); + } else - MOVE_SERVO(servo_index, a); + DETACH_SERVO(servo_index); } else SERIAL_ECHO_MSG(" Servo ", servo_index, ": ", servo[servo_index].read()); diff --git a/Marlin/src/gcode/control/M282.cpp b/Marlin/src/gcode/control/M282.cpp index 5fe2e6e328..e6f5ce7dcc 100644 --- a/Marlin/src/gcode/control/M282.cpp +++ b/Marlin/src/gcode/control/M282.cpp @@ -32,7 +32,7 @@ */ void GcodeSuite::M282() { - if (!parser.seen('P')) return; + if (!parser.seenval('P')) return; const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 4e7c3df78d..0fc6db07d6 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -885,8 +885,8 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 605: M605(); break; // M605: Set Dual X Carriage movement mode #endif - #if ENABLED(DELTA) - case 665: M665(); break; // M665: Set delta configurations + #if IS_KINEMATIC + case 665: M665(); break; // M665: Set Delta/SCARA parameters #endif #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index aa38b7de4a..b10f0bf06a 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -244,6 +244,7 @@ * M603 - Configure filament change: "M603 T U L". (Requires ADVANCED_PAUSE_FEATURE) * M605 - Set Dual X-Carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) * M665 - Set delta configurations: "M665 H L R S B X Y Z (Requires DELTA) + * Set SCARA configurations: "M665 S P T Z (Requires MORGAN_SCARA or MP_SCARA) * M666 - Set/get offsets for delta (Requires DELTA) or dual endstops. (Requires [XYZ]_DUAL_ENDSTOPS) * M672 - Set/Reset Duet Smart Effector's sensitivity. (Requires DUET_SMART_EFFECTOR and SMART_EFFECTOR_MOD_PIN) * M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 023bf46426..5feb3959f6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1061,7 +1061,7 @@ #if ANY(MORGAN_SCARA, MP_SCARA, AXEL_TPARA) #define IS_SCARA 1 #define IS_KINEMATIC 1 -#elif ENABLED(DELTA) +#elif EITHER(DELTA, POLARGRAPH) #define IS_KINEMATIC 1 #else #define IS_CARTESIAN 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 53b8783647..159284e84a 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1340,8 +1340,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Servo deactivation depends on servo endstops, switching nozzle, or switching extruder */ -#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_PROBE && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR) && !defined(SWITCHING_TOOLHEAD_SERVO_NR) - #error "Z_PROBE_SERVO_NR, switching nozzle, switching toolhead or switching extruder is required for DEACTIVATE_SERVOS_AFTER_MOVE." +#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && NONE(HAS_Z_SERVO_PROBE, POLARGRAPH) && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR) && !defined(SWITCHING_TOOLHEAD_SERVO_NR) + #error "Z_PROBE_SERVO_NR, switching nozzle, switching toolhead, switching extruder, or POLARGRAPH is required for DEACTIVATE_SERVOS_AFTER_MOVE." #endif /** diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 8834ee6eac..cfb7e5fc70 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -466,9 +466,11 @@ void menu_backlash(); #ifdef MAX_JERK_EDIT_VALUES MAX_JERK_EDIT_VALUES #elif ENABLED(LIMITED_JERK_EDITING) - { (DEFAULT_XJERK) * 2, (DEFAULT_YJERK) * 2, (DEFAULT_ZJERK) * 2, (DEFAULT_EJERK) * 2 } + { LOGICAL_AXIS_LIST((DEFAULT_EJERK) * 2, + (DEFAULT_XJERK) * 2, (DEFAULT_YJERK) * 2, (DEFAULT_ZJERK) * 2, + (DEFAULT_IJERK) * 2, (DEFAULT_JJERK) * 2, (DEFAULT_KJERK) * 2) } #else - { 990, 990, 990, 990 } + { LOGICAL_AXIS_LIST(990, 990, 990, 990, 990, 990, 990) } #endif ; #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)]) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index cdd425c472..397c2ac1d0 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -489,7 +489,7 @@ void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); #endif - #if EITHER(DELTA, IS_SCARA) + #if IS_KINEMATIC if (!position_is_reachable(x, y)) return; destination = current_position; // sync destination at the start #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index c41738a5ab..50df5675e6 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -504,6 +504,14 @@ void home_if_needed(const bool keeplev=false); return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset + fslop); + #elif ENABLED(POLARGRAPH) + + const float x1 = rx - (X_MIN_POS), x2 = (X_MAX_POS) - rx, y = ry - (Y_MAX_POS), + a = HYPOT(x1, y), b = HYPOT(x2, y); + return a < (POLARGRAPH_MAX_BELT_LEN) + 1 + && b < (POLARGRAPH_MAX_BELT_LEN) + 1 + && (a + b) > _MIN(X_BED_SIZE, Y_BED_SIZE); + #elif ENABLED(AXEL_TPARA) const float R2 = HYPOT2(rx - TPARA_OFFSET_X, ry - TPARA_OFFSET_Y); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 3e030c84d2..04fabd2df7 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3021,7 +3021,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons #else const feedRate_t feedrate = fr_mm_s; #endif - delta.e = machine.e; + TERN_(HAS_EXTRUDERS, delta.e = machine.e); if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) { position_cart = cart; return true; @@ -3126,7 +3126,7 @@ void Planner::set_position_mm(const xyze_pos_t &xyze) { #if IS_KINEMATIC position_cart = xyze; inverse_kinematics(machine); - delta.e = machine.e; + TERN_(HAS_EXTRUDERS, delta.e = machine.e); set_machine_position_mm(delta); #else set_machine_position_mm(machine); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 5e3922c897..ea63f862e0 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -48,6 +48,8 @@ #if ENABLED(DELTA) #include "delta.h" +#elif ENABLED(POLARGRAPH) + #include "polargraph.h" #endif #if ABL_PLANAR diff --git a/Marlin/src/module/polargraph.cpp b/Marlin/src/module/polargraph.cpp new file mode 100644 index 0000000000..b7eeeee8af --- /dev/null +++ b/Marlin/src/module/polargraph.cpp @@ -0,0 +1,47 @@ +/** + * 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 . + * + */ + +/** + * polargraph.cpp + */ + +#include "../inc/MarlinConfig.h" + +#if ENABLED(POLARGRAPH) + +#include "polargraph.h" +#include "motion.h" + +// For homing: +#include "planner.h" +#include "endstops.h" +#include "../lcd/marlinui.h" +#include "../MarlinCore.h" + +float segments_per_second; // Initialized by settings.load() + +void inverse_kinematics(const xyz_pos_t &raw) { + const float x1 = raw.x - (X_MIN_POS), x2 = (X_MAX_POS) - raw.x, y = raw.y - (Y_MAX_POS); + delta.set(HYPOT(x1, y), HYPOT(x2, y), raw.z); +} + +#endif // POLARGRAPH diff --git a/Marlin/src/module/polargraph.h b/Marlin/src/module/polargraph.h new file mode 100644 index 0000000000..0406034253 --- /dev/null +++ b/Marlin/src/module/polargraph.h @@ -0,0 +1,33 @@ +/** + * 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 + +/** + * polargraph.h - Polargraph-specific functions + */ + +#include "../core/types.h" +#include "../core/macros.h" + +extern float segments_per_second; + +void inverse_kinematics(const xyz_pos_t &raw); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8e4c758854..d8d9f20276 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -36,7 +36,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V84" +#define EEPROM_VERSION "V85" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -279,17 +279,24 @@ typedef struct SettingsDataStruct { bool bltouch_last_written_mode; // - // DELTA / [XYZ]_DUAL_ENDSTOPS + // Kinematic Settings // - #if ENABLED(DELTA) - float delta_height; // M666 H - abc_float_t delta_endstop_adj; // M666 X Y Z - float delta_radius, // M665 R - delta_diagonal_rod, // M665 L - segments_per_second; // M665 S - abc_float_t delta_tower_angle_trim, // M665 X Y Z - delta_diagonal_rod_trim; // M665 A B C - #elif HAS_EXTRA_ENDSTOPS + #if IS_KINEMATIC + float segments_per_second; // M665 S + #if ENABLED(DELTA) + float delta_height; // M666 H + abc_float_t delta_endstop_adj; // M666 X Y Z + float delta_radius, // M665 R + delta_diagonal_rod; // M665 L + abc_float_t delta_tower_angle_trim, // M665 X Y Z + delta_diagonal_rod_trim; // M665 A B C + #endif + #endif + + // + // Extra Endstops offsets + // + #if HAS_EXTRA_ENDSTOPS float x2_endstop_adj, // M666 X y2_endstop_adj, // M666 Y z2_endstop_adj, // M666 (S2) Z @@ -857,45 +864,49 @@ void MarlinSettings::postprocess() { } // - // DELTA Geometry or Dual Endstops offsets + // Kinematic Settings // + #if IS_KINEMATIC { + EEPROM_WRITE(segments_per_second); #if ENABLED(DELTA) - _FIELD_TEST(delta_height); - EEPROM_WRITE(delta_height); // 1 float EEPROM_WRITE(delta_endstop_adj); // 3 floats EEPROM_WRITE(delta_radius); // 1 float EEPROM_WRITE(delta_diagonal_rod); // 1 float - EEPROM_WRITE(segments_per_second); // 1 float EEPROM_WRITE(delta_tower_angle_trim); // 3 floats EEPROM_WRITE(delta_diagonal_rod_trim); // 3 floats - - #elif HAS_EXTRA_ENDSTOPS - - _FIELD_TEST(x2_endstop_adj); - - // Write dual endstops in X, Y, Z order. Unused = 0.0 - 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(dummyf); - #endif - - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 - EEPROM_WRITE(endstops.z4_endstop_adj); // 1 float - #else - EEPROM_WRITE(dummyf); - #endif - #endif } + #endif + + // + // Extra Endstops offsets + // + #if HAS_EXTRA_ENDSTOPS + { + _FIELD_TEST(x2_endstop_adj); + + // Write dual endstops in X, Y, Z order. Unused = 0.0 + 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(dummyf); + #endif + + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + EEPROM_WRITE(endstops.z4_endstop_adj); // 1 float + #else + EEPROM_WRITE(dummyf); + #endif + } + #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) EEPROM_WRITE(z_stepper_align.xy); @@ -1724,42 +1735,46 @@ void MarlinSettings::postprocess() { } // - // DELTA Geometry or Dual Endstops offsets + // Kinematic Segments-per-second // + #if IS_KINEMATIC { + EEPROM_READ(segments_per_second); #if ENABLED(DELTA) - _FIELD_TEST(delta_height); - EEPROM_READ(delta_height); // 1 float EEPROM_READ(delta_endstop_adj); // 3 floats EEPROM_READ(delta_radius); // 1 float EEPROM_READ(delta_diagonal_rod); // 1 float - EEPROM_READ(segments_per_second); // 1 float EEPROM_READ(delta_tower_angle_trim); // 3 floats EEPROM_READ(delta_diagonal_rod_trim); // 3 floats - - #elif HAS_EXTRA_ENDSTOPS - - _FIELD_TEST(x2_endstop_adj); - - 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(dummyf); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 - EEPROM_READ(endstops.z4_endstop_adj); // 1 float - #else - EEPROM_READ(dummyf); - #endif - #endif } + #endif + + // + // Extra Endstops offsets + // + #if HAS_EXTRA_ENDSTOPS + { + _FIELD_TEST(x2_endstop_adj); + + 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(dummyf); + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + EEPROM_READ(endstops.z4_endstop_adj); // 1 float + #else + EEPROM_READ(dummyf); + #endif + } + #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) EEPROM_READ(z_stepper_align.xy); @@ -2721,20 +2736,30 @@ void MarlinSettings::reset() { //#endif // - // Endstop Adjustments + // Kinematic settings // - #if ENABLED(DELTA) - const abc_float_t adj = DELTA_ENDSTOP_ADJ, dta = DELTA_TOWER_ANGLE_TRIM, ddr = DELTA_DIAGONAL_ROD_TRIM_TOWER; - delta_height = DELTA_HEIGHT; - delta_endstop_adj = adj; - delta_radius = DELTA_RADIUS; - delta_diagonal_rod = DELTA_DIAGONAL_ROD; - segments_per_second = DELTA_SEGMENTS_PER_SECOND; - delta_tower_angle_trim = dta; - delta_diagonal_rod_trim = ddr; + #if IS_KINEMATIC + segments_per_second = ( + TERN_(DELTA, DELTA_SEGMENTS_PER_SECOND) + TERN_(IS_SCARA, SCARA_SEGMENTS_PER_SECOND) + TERN_(POLARGRAPH, POLAR_SEGMENTS_PER_SECOND) + ); + #if ENABLED(DELTA) + const abc_float_t adj = DELTA_ENDSTOP_ADJ, dta = DELTA_TOWER_ANGLE_TRIM, ddr = DELTA_DIAGONAL_ROD_TRIM_TOWER; + delta_height = DELTA_HEIGHT; + delta_endstop_adj = adj; + delta_radius = DELTA_RADIUS; + delta_diagonal_rod = DELTA_DIAGONAL_ROD; + delta_tower_angle_trim = dta; + delta_diagonal_rod_trim = ddr; + #endif #endif + // + // Endstop Adjustments + // + #if ENABLED(X_DUAL_ENDSTOPS) #ifndef X2_ENDSTOP_ADJUSTMENT #define X2_ENDSTOP_ADJUSTMENT 0 @@ -3137,7 +3162,7 @@ void MarlinSettings::reset() { TERN_(EDITABLE_SERVO_ANGLES, gcode.M281_report(forReplay)); // - // Delta / SCARA Kinematics + // Kinematic Settings // TERN_(IS_KINEMATIC, gcode.M665_report(forReplay)); diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 942afafd7a..d8e2dd0971 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -47,12 +47,27 @@ // // Limit Switches // -#define X_MIN_PIN 37 -#define X_MAX_PIN 36 -#define Y_MIN_PIN 35 -#define Y_MAX_PIN 34 -#define Z_MIN_PIN 33 -#define Z_MAX_PIN 32 +#ifndef X_MIN_PIN + #define X_MIN_PIN 37 +#endif +#ifndef X_MIN_PIN + #define X_MIN_PIN 37 +#endif +#ifndef X_MAX_PIN + #define X_MAX_PIN 36 +#endif +#ifndef Y_MIN_PIN + #define Y_MIN_PIN 35 +#endif +#ifndef Y_MAX_PIN + #define Y_MAX_PIN 34 +#endif +#ifndef Z_MIN_PIN + #define Z_MIN_PIN 33 +#endif +#ifndef Z_MAX_PIN + #define Z_MAX_PIN 32 +#endif // // Z Probe (when not Z_MIN_PIN) diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index d8cefbaf81..cae747017f 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -46,6 +46,7 @@ exec_test $1 $2 "RAMPS | DELTA | RRD LCD | DELTA_AUTO_CALIBRATION | DELTA_CALIBR # # Delta Config (generic) + ABL bilinear + BLTOUCH +# use_example_configs delta/generic opt_set LCD_LANGUAGE cz \ Z_MIN_PROBE_ENDSTOP_INVERTING false \ diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 7d28a00d92..bf3290b9d0 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -182,7 +182,7 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_C opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 -exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" +exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 12864 LCD | meatpack | SERIAL_PORT_2 " "$3" # # Test Laser features with 44780 LCD @@ -197,7 +197,7 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_C opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER I2C_AMMETER -exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" +exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" # # Test redundant temperature sensors + MAX TC @@ -210,6 +210,12 @@ opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 1 \ exec_test $1 $2 "MEGA2560 RAMPS | Redundant temperature sensor | 2x MAX6675" "$3" +# +# Polargraph Config +# +use_example_configs Polargraph +exec_test $1 $2 "RUMBA | POLARGRAPH | RRD LCD" "$3" + # # Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER # diff --git a/ini/features.ini b/ini/features.ini index 949c55c06e..f54b645f85 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -219,6 +219,7 @@ NEED_LSF = src_filter=+ + NOZZLE_CLEAN_FEATURE = src_filter=+ + DELTA = src_filter=+ + +POLARGRAPH = src_filter=+ BEZIER_CURVE_SUPPORT = src_filter=+ + PRINTCOUNTER = src_filter=+ HAS_BED_PROBE = src_filter=+ + + + diff --git a/platformio.ini b/platformio.ini index bd2a4ed21f..106e454d10 100644 --- a/platformio.ini +++ b/platformio.ini @@ -158,6 +158,7 @@ default_src_filter = + - - + - - - + - - - - @@ -239,9 +240,10 @@ default_src_filter = + - - + - - - - + - - - - - - + - - - - - - From 58301837e0a1ea0d682d23e0510619bd85841d5c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 20 Sep 2021 18:44:35 -0500 Subject: [PATCH 0709/2168] =?UTF-8?q?=F0=9F=A9=B9=20Remove=20extra=20#incl?= =?UTF-8?q?ude,=20misc.=20style?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 4 +--- Marlin/src/pins/stm32f4/pins_ANET_ET4.h | 2 -- .../share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h | 2 +- .../share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h | 2 +- .../share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h | 2 +- .../PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h | 2 +- .../share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h | 2 +- buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h | 2 +- .../share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h | 2 +- 9 files changed, 8 insertions(+), 12 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index b1cb030025..2a6a320889 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1483,9 +1483,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; next_filament_display = ms + 5000UL; // Show status message for 5s #endif - #if ENABLED(STATUS_MESSAGE_SCROLLING) - status_scroll_offset = 0; - #endif + TERN_(STATUS_MESSAGE_SCROLLING, status_scroll_offset = 0); #else // HAS_WIRED_LCD UNUSED(persist); #endif diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index 196a779c8d..8343010432 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -23,8 +23,6 @@ #include "env_validate.h" -#include "env_validate.h" - #if HOTENDS > 1 || E_STEPPERS > 1 #error "Anet ET4 only supports one hotend / E-stepper. Comment out this line to continue." #endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h index 59a7f24527..5657450100 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h @@ -244,7 +244,7 @@ extern "C" { #define PIN_WIRE_SCL PB6 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM7 #define TIMER_SERVO TIM5 #define TIMER_SERIAL TIM2 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h index 42f21ce5a6..646d635679 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_E3_RRF/variant.h @@ -244,7 +244,7 @@ extern "C" { #define PIN_WIRE_SCL PB8 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM7 #define TIMER_SERVO TIM5 #define TIMER_SERIAL TIM8 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h index 732e0c51f1..41e4641102 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_GTR_V1/variant.h @@ -254,7 +254,7 @@ extern "C" { #endif // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM10 #define TIMER_SERVO TIM5 #define TIMER_SERIAL TIM7 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h index f9091a4f91..11ebf561f3 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_SKR_PRO_11/variant.h @@ -254,7 +254,7 @@ extern "C" { #endif // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM2 #define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins #define TIMER_SERIAL TIM7 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h index 5be18f9aa4..74f29514a8 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BTT_SKR_SE_BX/variant.h @@ -156,7 +156,7 @@ extern "C" { #define NUM_ANALOG_FIRST 108 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM2 #define TIMER_SERVO TIM5 #define TIMER_SERIAL TIM7 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h index 4e7e299f1c..3eed147309 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h @@ -298,7 +298,7 @@ extern "C" { #define PIN_WIRE_SCL PB6 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM6 // Do not use basic timer: OC is required diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h index 6fb271dea6..fd9a5c7741 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FLY_F407ZG/variant.h @@ -184,7 +184,7 @@ extern "C" { #define PIN_WIRE_SCL PB6 // Timer Definitions -//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +// Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c #define TIMER_TONE TIM6 // Do not use basic timer: OC is required From 5b934e02fad7cbff79e14d1bd6b8d0a8fbe24de5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 21 Sep 2021 01:01:29 +0000 Subject: [PATCH 0710/2168] [cron] Bump distribution date (2021-09-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4164248807..2b7215529e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-20" +//#define STRING_DISTRIBUTION_DATE "2021-09-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 664fbd87cf..0531a37550 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 "2021-09-20" + #define STRING_DISTRIBUTION_DATE "2021-09-21" #endif /** From 58adb849d3e2f81075eeb02db8e1d5b3f297d59b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Sep 2021 02:42:01 -0500 Subject: [PATCH 0711/2168] =?UTF-8?q?=F0=9F=94=A8=20Improve=20pins=5Fset?= =?UTF-8?q?=20script?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/pins_set | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/buildroot/bin/pins_set b/buildroot/bin/pins_set index 158c5224e6..31b4480449 100755 --- a/buildroot/bin/pins_set +++ b/buildroot/bin/pins_set @@ -3,9 +3,13 @@ IFS='/' read -r -a PINPATH <<< "$1" DIR=${PINPATH[0]} NAM=${PINPATH[1]} -PIN=$2 -VAL=$3 SED=$(which gsed sed | head -n1) -eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || -(echo "ERROR: pins_set Can't find ${PIN}" >&2 && exit 9) + +shift +while [[ $# > 1 ]]; do + PIN=$1 ; VAL=$2 + eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || + (echo "ERROR: pins_set Can't find ${PIN}" >&2 && exit 9) + shift 2 +done From b88117d6364b8919a8a7df6c80d8132af98a6afc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Sep 2021 06:25:13 -0500 Subject: [PATCH 0712/2168] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20L64xx=20enable,?= =?UTF-8?q?=20clean=20up=20conditionals?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/gcode/feature/leds/M150.cpp | 4 +- Marlin/src/inc/Conditionals_post.h | 307 +++++++++--------- Marlin/src/inc/SanityCheck.h | 64 ++-- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 16 +- .../lcd/extui/dgus_reloaded/DGUSTxHandler.cpp | 10 +- .../extui/dgus_reloaded/config/DGUS_Addr.h | 4 +- .../dgus_reloaded/definition/DGUS_VPList.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 4 +- Marlin/src/module/probe.cpp | 24 +- Marlin/src/module/probe.h | 2 +- Marlin/src/module/stepper/indirection.h | 144 ++------ Marlin/src/module/stepper/trinamic.h | 18 +- Marlin/src/sd/cardreader.h | 9 +- 14 files changed, 256 insertions(+), 356 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 6dfd19a3a0..24cd52e548 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -207,7 +207,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load #if ENABLED(MULTI_FILAMENT_SENSOR) #define _CASE_INSERTED(N) case N-1: if (READ(FIL_RUNOUT##N##_PIN) != FIL_RUNOUT##N##_STATE) wait_for_user = false; break; switch (active_extruder) { - REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _CASE_INSERTED) + REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_INSERTED) } #else if (READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_STATE) wait_for_user = false; diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index 4d271007e5..45278fe1f5 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -56,10 +56,10 @@ void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) const int8_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) - int8_t brightness, unit = parser.intval('S', -1); + int8_t brightness = neo.brightness(), unit = parser.intval('S', -1); switch (unit) { case -1: neo2.neoindex = index; // fall-thru - case 0: neo.neoindex = index; brightness = neo.brightness(); break; + case 0: neo.neoindex = index; break; case 1: neo2.neoindex = index; brightness = neo2.brightness(); break; } #else diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 5c1aa5321f..ccb7cdde7c 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -94,6 +94,8 @@ #endif #if HAS_Z_AXIS #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#else + #undef CONTROLLER_FAN_USE_Z_ONLY #endif #if LINEAR_AXES >= 4 #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS)) @@ -470,31 +472,6 @@ #define NO_LCD_REINIT 1 // Suppress LCD re-initialization #endif -/** - * Set defaults for missing (newer) options - */ -#ifndef DISABLE_INACTIVE_X - #define DISABLE_INACTIVE_X DISABLE_X -#endif -#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y) - #define DISABLE_INACTIVE_Y DISABLE_Y -#endif -#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z) - #define DISABLE_INACTIVE_Z DISABLE_Z -#endif -#ifndef DISABLE_INACTIVE_E - #define DISABLE_INACTIVE_E DISABLE_E -#endif -#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I) - #define DISABLE_INACTIVE_I DISABLE_I -#endif -#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J) - #define DISABLE_INACTIVE_J DISABLE_J -#endif -#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K) - #define DISABLE_INACTIVE_K DISABLE_K -#endif - /** * Power Supply */ @@ -1468,7 +1445,7 @@ #define HAS_X_MS_PINS 1 #endif -#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) +#if PIN_EXISTS(X2_ENABLE) || AXIS_IS_L64XX(X2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) #define HAS_X2_ENABLE 1 #endif #if PIN_EXISTS(X2_DIR) @@ -1481,8 +1458,15 @@ #define HAS_X2_MS_PINS 1 #endif +/** + * Set defaults for missing (newer) options + */ +#if !defined(DISABLE_INACTIVE_X) && ENABLED(DISABLE_X) + #define DISABLE_INACTIVE_X 1 +#endif + #if HAS_Y_AXIS - #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) + #if PIN_EXISTS(Y_ENABLE) || AXIS_IS_L64XX(Y) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) #define HAS_Y_ENABLE 1 #endif #if PIN_EXISTS(Y_DIR) @@ -1495,7 +1479,7 @@ #define HAS_Y_MS_PINS 1 #endif - #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) + #if PIN_EXISTS(Y2_ENABLE) || AXIS_IS_L64XX(Y2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) #define HAS_Y2_ENABLE 1 #endif #if PIN_EXISTS(Y2_DIR) @@ -1507,10 +1491,15 @@ #if PIN_EXISTS(Y2_MS1) #define HAS_Y2_MS_PINS 1 #endif + #if !defined(DISABLE_INACTIVE_Y) && ENABLED(DISABLE_Y) + #define DISABLE_INACTIVE_Y 1 + #endif +#else + #undef DISABLE_INACTIVE_Y #endif #if HAS_Z_AXIS - #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) + #if PIN_EXISTS(Z_ENABLE) || AXIS_IS_L64XX(Z) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) #define HAS_Z_ENABLE 1 #endif #if PIN_EXISTS(Z_DIR) @@ -1522,10 +1511,15 @@ #if PIN_EXISTS(Z_MS1) #define HAS_Z_MS_PINS 1 #endif + #if !defined(DISABLE_INACTIVE_Z) && ENABLED(DISABLE_Z) + #define DISABLE_INACTIVE_Z 1 + #endif +#else + #undef DISABLE_INACTIVE_Z #endif #if NUM_Z_STEPPER_DRIVERS >= 2 - #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) + #if PIN_EXISTS(Z2_ENABLE) || AXIS_IS_L64XX(Z2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) #define HAS_Z2_ENABLE 1 #endif #if PIN_EXISTS(Z2_DIR) @@ -1540,7 +1534,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 3 - #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) + #if PIN_EXISTS(Z3_ENABLE) || AXIS_IS_L64XX(Z3) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) #define HAS_Z3_ENABLE 1 #endif #if PIN_EXISTS(Z3_DIR) @@ -1555,7 +1549,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 4 - #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) + #if PIN_EXISTS(Z4_ENABLE) || AXIS_IS_L64XX(Z4) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) #define HAS_Z4_ENABLE 1 #endif #if PIN_EXISTS(Z4_DIR) @@ -1570,7 +1564,7 @@ #endif #if LINEAR_AXES >= 4 - #if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) + #if PIN_EXISTS(I_ENABLE) || AXIS_IS_L64XX(I) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) #define HAS_I_ENABLE 1 #endif #if PIN_EXISTS(I_DIR) @@ -1582,10 +1576,15 @@ #if PIN_EXISTS(I_MS1) #define HAS_I_MS_PINS 1 #endif + #if !defined(DISABLE_INACTIVE_I) && ENABLED(DISABLE_I) + #define DISABLE_INACTIVE_I 1 + #endif +#else + #undef DISABLE_INACTIVE_I #endif #if LINEAR_AXES >= 5 - #if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) + #if PIN_EXISTS(J_ENABLE) || AXIS_IS_L64XX(J) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) #define HAS_J_ENABLE 1 #endif #if PIN_EXISTS(J_DIR) @@ -1597,10 +1596,15 @@ #if PIN_EXISTS(J_MS1) #define HAS_J_MS_PINS 1 #endif + #if !defined(DISABLE_INACTIVE_J) && ENABLED(DISABLE_J) + #define DISABLE_INACTIVE_J 1 + #endif +#else + #undef DISABLE_INACTIVE_J #endif #if LINEAR_AXES >= 6 - #if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) + #if PIN_EXISTS(K_ENABLE) || AXIS_IS_L64XX(K) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) #define HAS_K_ENABLE 1 #endif #if PIN_EXISTS(K_DIR) @@ -1612,12 +1616,17 @@ #if PIN_EXISTS(K_MS1) #define HAS_K_MS_PINS 1 #endif + #if !defined(DISABLE_INACTIVE_K) && ENABLED(DISABLE_K) + #define DISABLE_INACTIVE_K 1 + #endif +#else + #undef DISABLE_INACTIVE_K #endif // Extruder steppers and solenoids #if HAS_EXTRUDERS - #if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) + #if PIN_EXISTS(E0_ENABLE) || AXIS_IS_L64XX(E0) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) #define HAS_E0_ENABLE 1 #endif #if PIN_EXISTS(E0_DIR) @@ -1633,118 +1642,137 @@ #define HAS_SOLENOID_0 1 #endif - #if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) - #define HAS_E1_ENABLE 1 - #endif - #if PIN_EXISTS(E1_DIR) - #define HAS_E1_DIR 1 - #endif - #if PIN_EXISTS(E1_STEP) - #define HAS_E1_STEP 1 - #endif - #if PIN_EXISTS(E1_MS1) - #define HAS_E1_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL1) - #define HAS_SOLENOID_1 1 + #if E_STEPPERS > 1 + #if PIN_EXISTS(E1_ENABLE) || AXIS_IS_L64XX(E1) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) + #define HAS_E1_ENABLE 1 + #endif + #if PIN_EXISTS(E1_DIR) + #define HAS_E1_DIR 1 + #endif + #if PIN_EXISTS(E1_STEP) + #define HAS_E1_STEP 1 + #endif + #if PIN_EXISTS(E1_MS1) + #define HAS_E1_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL1) + #define HAS_SOLENOID_1 1 + #endif #endif - #if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) - #define HAS_E2_ENABLE 1 - #endif - #if PIN_EXISTS(E2_DIR) - #define HAS_E2_DIR 1 - #endif - #if PIN_EXISTS(E2_STEP) - #define HAS_E2_STEP 1 - #endif - #if PIN_EXISTS(E2_MS1) - #define HAS_E2_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL2) - #define HAS_SOLENOID_2 1 + #if E_STEPPERS > 2 + #if PIN_EXISTS(E2_ENABLE) || AXIS_IS_L64XX(E2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) + #define HAS_E2_ENABLE 1 + #endif + #if PIN_EXISTS(E2_DIR) + #define HAS_E2_DIR 1 + #endif + #if PIN_EXISTS(E2_STEP) + #define HAS_E2_STEP 1 + #endif + #if PIN_EXISTS(E2_MS1) + #define HAS_E2_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL2) + #define HAS_SOLENOID_2 1 + #endif #endif - #if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) - #define HAS_E3_ENABLE 1 - #endif - #if PIN_EXISTS(E3_DIR) - #define HAS_E3_DIR 1 - #endif - #if PIN_EXISTS(E3_STEP) - #define HAS_E3_STEP 1 - #endif - #if PIN_EXISTS(E3_MS1) - #define HAS_E3_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL3) - #define HAS_SOLENOID_3 1 + #if E_STEPPERS > 3 + #if PIN_EXISTS(E3_ENABLE) || AXIS_IS_L64XX(E3) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) + #define HAS_E3_ENABLE 1 + #endif + #if PIN_EXISTS(E3_DIR) + #define HAS_E3_DIR 1 + #endif + #if PIN_EXISTS(E3_STEP) + #define HAS_E3_STEP 1 + #endif + #if PIN_EXISTS(E3_MS1) + #define HAS_E3_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL3) + #define HAS_SOLENOID_3 1 + #endif #endif - #if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) - #define HAS_E4_ENABLE 1 - #endif - #if PIN_EXISTS(E4_DIR) - #define HAS_E4_DIR 1 - #endif - #if PIN_EXISTS(E4_STEP) - #define HAS_E4_STEP 1 - #endif - #if PIN_EXISTS(E4_MS1) - #define HAS_E4_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL4) - #define HAS_SOLENOID_4 1 + #if E_STEPPERS > 4 + #if PIN_EXISTS(E4_ENABLE) || AXIS_IS_L64XX(E4) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) + #define HAS_E4_ENABLE 1 + #endif + #if PIN_EXISTS(E4_DIR) + #define HAS_E4_DIR 1 + #endif + #if PIN_EXISTS(E4_STEP) + #define HAS_E4_STEP 1 + #endif + #if PIN_EXISTS(E4_MS1) + #define HAS_E4_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL4) + #define HAS_SOLENOID_4 1 + #endif #endif - #if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) - #define HAS_E5_ENABLE 1 - #endif - #if PIN_EXISTS(E5_DIR) - #define HAS_E5_DIR 1 - #endif - #if PIN_EXISTS(E5_STEP) - #define HAS_E5_STEP 1 - #endif - #if PIN_EXISTS(E5_MS1) - #define HAS_E5_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL5) - #define HAS_SOLENOID_5 1 + #if E_STEPPERS > 5 + #if PIN_EXISTS(E5_ENABLE) || AXIS_IS_L64XX(E5) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) + #define HAS_E5_ENABLE 1 + #endif + #if PIN_EXISTS(E5_DIR) + #define HAS_E5_DIR 1 + #endif + #if PIN_EXISTS(E5_STEP) + #define HAS_E5_STEP 1 + #endif + #if PIN_EXISTS(E5_MS1) + #define HAS_E5_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL5) + #define HAS_SOLENOID_5 1 + #endif #endif - #if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) - #define HAS_E6_ENABLE 1 - #endif - #if PIN_EXISTS(E6_DIR) - #define HAS_E6_DIR 1 - #endif - #if PIN_EXISTS(E6_STEP) - #define HAS_E6_STEP 1 - #endif - #if PIN_EXISTS(E6_MS1) - #define HAS_E6_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL6) - #define HAS_SOLENOID_6 1 + #if E_STEPPERS > 6 + #if PIN_EXISTS(E6_ENABLE) || AXIS_IS_L64XX(E6) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) + #define HAS_E6_ENABLE 1 + #endif + #if PIN_EXISTS(E6_DIR) + #define HAS_E6_DIR 1 + #endif + #if PIN_EXISTS(E6_STEP) + #define HAS_E6_STEP 1 + #endif + #if PIN_EXISTS(E6_MS1) + #define HAS_E6_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL6) + #define HAS_SOLENOID_6 1 + #endif #endif - #if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) - #define HAS_E7_ENABLE 1 - #endif - #if PIN_EXISTS(E7_DIR) - #define HAS_E7_DIR 1 - #endif - #if PIN_EXISTS(E7_STEP) - #define HAS_E7_STEP 1 - #endif - #if PIN_EXISTS(E7_MS1) - #define HAS_E7_MS_PINS 1 - #endif - #if PIN_EXISTS(SOL7) - #define HAS_SOLENOID_7 1 + #if E_STEPPERS > 7 + #if PIN_EXISTS(E7_ENABLE) || AXIS_IS_L64XX(E7) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) + #define HAS_E7_ENABLE 1 + #endif + #if PIN_EXISTS(E7_DIR) + #define HAS_E7_DIR 1 + #endif + #if PIN_EXISTS(E7_STEP) + #define HAS_E7_STEP 1 + #endif + #if PIN_EXISTS(E7_MS1) + #define HAS_E7_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL7) + #define HAS_SOLENOID_7 1 + #endif #endif + #if !defined(DISABLE_INACTIVE_E) && ENABLED(DISABLE_E) + #define DISABLE_INACTIVE_E 1 + #endif +#else + #undef DISABLE_INACTIVE_E #endif // HAS_EXTRUDERS // @@ -1997,12 +2025,6 @@ #endif #endif -#if (HAS_E_DRIVER(TMC2660) \ - || ( E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != X_ENABLE_PIN \ - && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) ) - #define HAS_E_STEPPER_ENABLE 1 -#endif - #if ANY_AXIS_HAS(HW_SERIAL) #define HAS_TMC_HW_SERIAL 1 #endif @@ -3260,11 +3282,6 @@ #define SD_SPI_SPEED SPI_FULL_SPEED #endif -// Defined here to catch the above defines -#if ENABLED(SDCARD_SORT_ALPHA) && (FOLDER_SORTING || ENABLED(SDSORT_GCODE)) - #define HAS_FOLDER_SORTING 1 -#endif - #if HAS_WIRED_LCD // Get LCD character width/height, which may be overridden by pins, configs, etc. #ifndef LCD_WIDTH diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 159284e84a..720a04c502 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2355,46 +2355,30 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if E_STEPPERS - #if !(PINS_EXIST(E0_STEP, E0_DIR) && HAS_E0_ENABLE) - #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 1 - #if !(PINS_EXIST(E1_STEP, E1_DIR) && HAS_E1_ENABLE) - #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 2 - #if !(PINS_EXIST(E2_STEP, E2_DIR) && HAS_E2_ENABLE) - #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 3 - #if !(PINS_EXIST(E3_STEP, E3_DIR) && HAS_E3_ENABLE) - #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 4 - #if !(PINS_EXIST(E4_STEP, E4_DIR) && HAS_E4_ENABLE) - #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 5 - #if !(PINS_EXIST(E5_STEP, E5_DIR) && HAS_E5_ENABLE) - #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 6 - #if !(PINS_EXIST(E6_STEP, E6_DIR) && HAS_E6_ENABLE) - #error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board." - #endif - #if E_STEPPERS > 7 - #if !(PINS_EXIST(E7_STEP, E7_DIR) && HAS_E7_ENABLE) - #error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board." - #endif - #endif // E_STEPPERS > 7 - #endif // E_STEPPERS > 6 - #endif // E_STEPPERS > 5 - #endif // E_STEPPERS > 4 - #endif // E_STEPPERS > 3 - #endif // E_STEPPERS > 2 - #endif // E_STEPPERS > 1 -#endif // E_STEPPERS +#if E_STEPPERS > 0 && !(PINS_EXIST(E0_STEP, E0_DIR) && HAS_E0_ENABLE) + #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 1 && !(PINS_EXIST(E1_STEP, E1_DIR) && HAS_E1_ENABLE) + #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 2 && !(PINS_EXIST(E2_STEP, E2_DIR) && HAS_E2_ENABLE) + #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 3 && !(PINS_EXIST(E3_STEP, E3_DIR) && HAS_E3_ENABLE) + #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 4 && !(PINS_EXIST(E4_STEP, E4_DIR) && HAS_E4_ENABLE) + #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 5 && !(PINS_EXIST(E5_STEP, E5_DIR) && HAS_E5_ENABLE) + #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 6 && !(PINS_EXIST(E6_STEP, E6_DIR) && HAS_E6_ENABLE) + #error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board." +#endif +#if E_STEPPERS > 7 && !(PINS_EXIST(E7_STEP, E7_DIR) && HAS_E7_ENABLE) + #error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board." +#endif /** * Endstop Tests diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 20a4bee234..42731cd866 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -229,13 +229,9 @@ void DGUSRxHandler::Flowrate(DGUS_VP &vp, void *data_ptr) { switch (vp.addr) { default: return; case DGUS_Addr::ADJUST_SetFlowrate_CUR: - #if EXTRUDERS > 1 - ExtUI::setFlow_percent(flowrate, ExtUI::getActiveTool()); - #else - ExtUI::setFlow_percent(flowrate, ExtUI::E0); - #endif + ExtUI::setFlow_percent(flowrate, TERN(HAS_MULTI_EXTRUDER, ExtUI::getActiveTool(), ExtUI::E0)); break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case DGUS_Addr::ADJUST_SetFlowrate_E0: ExtUI::setFlow_percent(flowrate, ExtUI::E0); break; @@ -557,9 +553,7 @@ void DGUSRxHandler::FilamentSelect(DGUS_VP &vp, void *data_ptr) { default: return; case DGUS_Data::Extruder::CURRENT: case DGUS_Data::Extruder::E0: - #if EXTRUDERS > 1 - case DGUS_Data::Extruder::E1: - #endif + TERN_(HAS_MULTI_EXTRUDER, case DGUS_Data::Extruder::E1:) dgus_screen_handler.filament_extruder = extruder; break; } @@ -590,14 +584,14 @@ void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { switch (dgus_screen_handler.filament_extruder) { default: return; case DGUS_Data::Extruder::CURRENT: - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER extruder = ExtUI::getActiveTool(); break; #endif case DGUS_Data::Extruder::E0: extruder = ExtUI::E0; break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case DGUS_Data::Extruder::E1: extruder = ExtUI::E1; break; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index b2fa8c18b3..b419428fbc 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -249,13 +249,9 @@ void DGUSTxHandler::Flowrate(DGUS_VP &vp) { switch (vp.addr) { default: return; case DGUS_Addr::ADJUST_Flowrate_CUR: - #if EXTRUDERS > 1 - flowrate = ExtUI::getFlow_percent(ExtUI::getActiveTool()); - #else - flowrate = ExtUI::getFlow_percent(ExtUI::E0); - #endif + flowrate = ExtUI::getFlow_percent(TERN(HAS_MULTI_EXTRUDER, ExtUI::getActiveTool(), ExtUI::E0)); break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case DGUS_Addr::ADJUST_Flowrate_E0: flowrate = ExtUI::getFlow_percent(ExtUI::E0); break; @@ -366,7 +362,7 @@ void DGUSTxHandler::FilamentIcons(DGUS_VP &vp) { switch (dgus_screen_handler.filament_extruder) { default: return; case DGUS_Data::Extruder::CURRENT: - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER switch (ExtUI::getActiveTool()) { default: break; case ExtUI::E0: diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h index de64fe2b10..00cdecb689 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h @@ -55,7 +55,7 @@ enum class DGUS_Addr : uint16_t { STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) #endif @@ -113,7 +113,7 @@ enum class DGUS_Addr : uint16_t { STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) #endif diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp index 3f5690cfe7..486f00f6ed 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp @@ -92,7 +92,7 @@ const struct DGUS_VP vp_list[] PROGMEM = { VP_HELPER_RX(DGUS_Addr::ADJUST_SetFeedrate, &DGUSRxHandler::Feedrate), VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_CUR, &DGUSRxHandler::Flowrate), - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E0, &DGUSRxHandler::Flowrate), VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E1, &DGUSRxHandler::Flowrate), #endif @@ -194,7 +194,7 @@ const struct DGUS_VP vp_list[] PROGMEM = { VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_CUR, nullptr, &DGUSTxHandler::Flowrate), - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_E0, nullptr, &DGUSTxHandler::Flowrate), diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 0e937b2baa..e4140edc79 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -988,11 +988,11 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { if (card.isFileOpen()) { //saved_feedrate_percentage = feedrate_percentage; feedrate_percentage = 100; - #if EXTRUDERS + #if HAS_EXTRUDERS planner.flow_percentage[0] = 100; planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; #endif - #if EXTRUDERS == 2 + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; #endif diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 071ff25c20..3aca68845d 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -48,8 +48,17 @@ #include "delta.h" #endif -#if ENABLED(BABYSTEP_ZPROBE_OFFSET) - #include "planner.h" +#if ANY(HAS_QUIET_PROBING, USE_SENSORLESS) + #include "stepper/indirection.h" + #if BOTH(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) + #include "stepper.h" + #endif + #if USE_SENSORLESS + #include "../feature/tmc_util.h" + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + #include "planner.h" + #endif + #endif #endif #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) @@ -68,15 +77,6 @@ #include "servo.h" #endif -#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) - #include "stepper.h" - #include "../feature/tmc_util.h" -#endif - -#if HAS_QUIET_PROBING - #include "stepper/indirection.h" -#endif - #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) @@ -818,7 +818,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai #endif // HAS_Z_SERVO_PROBE -#if EITHER(SENSORLESS_PROBING, SENSORLESS_HOMING) +#if USE_SENSORLESS sensorless_t stealth_states { false }; diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 5da5ea3a22..f9275ba9fd 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -263,7 +263,7 @@ public: #endif // Basic functions for Sensorless Homing and Probing - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #if USE_SENSORLESS static void enable_stallguard_diag1(); static void disable_stallguard_diag1(); static void set_homing_current(const bool onoff); diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index beba03699e..312a09f716 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -667,183 +667,87 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset // #ifndef ENABLE_STEPPER_X - #if HAS_X_ENABLE - #define ENABLE_STEPPER_X() X_ENABLE_WRITE( X_ENABLE_ON) - #else - #define ENABLE_STEPPER_X() NOOP - #endif + #define ENABLE_STEPPER_X() TERN(HAS_X_ENABLE, X_ENABLE_WRITE( X_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_X - #if HAS_X_ENABLE - #define DISABLE_STEPPER_X() X_ENABLE_WRITE(!X_ENABLE_ON) - #else - #define DISABLE_STEPPER_X() NOOP - #endif + #define DISABLE_STEPPER_X() TERN(HAS_X_ENABLE, X_ENABLE_WRITE(!X_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_X2 - #if HAS_X2_ENABLE - #define ENABLE_STEPPER_X2() X2_ENABLE_WRITE( X_ENABLE_ON) - #else - #define ENABLE_STEPPER_X2() NOOP - #endif + #define ENABLE_STEPPER_X2() TERN(HAS_X2_ENABLE, X2_ENABLE_WRITE( X_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_X2 - #if HAS_X2_ENABLE - #define DISABLE_STEPPER_X2() X2_ENABLE_WRITE(!X_ENABLE_ON) - #else - #define DISABLE_STEPPER_X2() NOOP - #endif + #define DISABLE_STEPPER_X2() TERN(HAS_X2_ENABLE, X2_ENABLE_WRITE(!X_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Y - #if HAS_Y_ENABLE - #define ENABLE_STEPPER_Y() Y_ENABLE_WRITE( Y_ENABLE_ON) - #else - #define ENABLE_STEPPER_Y() NOOP - #endif + #define ENABLE_STEPPER_Y() TERN(HAS_Y_ENABLE, Y_ENABLE_WRITE( Y_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Y - #if HAS_Y_ENABLE - #define DISABLE_STEPPER_Y() Y_ENABLE_WRITE(!Y_ENABLE_ON) - #else - #define DISABLE_STEPPER_Y() NOOP - #endif + #define DISABLE_STEPPER_Y() TERN(HAS_Y_ENABLE, Y_ENABLE_WRITE(!Y_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Y2 - #if HAS_Y2_ENABLE - #define ENABLE_STEPPER_Y2() Y2_ENABLE_WRITE( Y_ENABLE_ON) - #else - #define ENABLE_STEPPER_Y2() NOOP - #endif + #define ENABLE_STEPPER_Y2() TERN(HAS_Y2_ENABLE, Y2_ENABLE_WRITE( Y_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Y2 - #if HAS_Y2_ENABLE - #define DISABLE_STEPPER_Y2() Y2_ENABLE_WRITE(!Y_ENABLE_ON) - #else - #define DISABLE_STEPPER_Y2() NOOP - #endif + #define DISABLE_STEPPER_Y2() TERN(HAS_Y2_ENABLE, Y2_ENABLE_WRITE(!Y_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Z - #if HAS_Z_ENABLE - #define ENABLE_STEPPER_Z() Z_ENABLE_WRITE( Z_ENABLE_ON) - #else - #define ENABLE_STEPPER_Z() NOOP - #endif + #define ENABLE_STEPPER_Z() TERN(HAS_Z_ENABLE, Z_ENABLE_WRITE( Z_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Z - #if HAS_Z_ENABLE - #define DISABLE_STEPPER_Z() Z_ENABLE_WRITE(!Z_ENABLE_ON) - #else - #define DISABLE_STEPPER_Z() NOOP - #endif + #define DISABLE_STEPPER_Z() TERN(HAS_Z_ENABLE, Z_ENABLE_WRITE(!Z_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Z2 - #if HAS_Z2_ENABLE - #define ENABLE_STEPPER_Z2() Z2_ENABLE_WRITE( Z_ENABLE_ON) - #else - #define ENABLE_STEPPER_Z2() NOOP - #endif + #define ENABLE_STEPPER_Z2() TERN(HAS_Z2_ENABLE, Z2_ENABLE_WRITE( Z_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Z2 - #if HAS_Z2_ENABLE - #define DISABLE_STEPPER_Z2() Z2_ENABLE_WRITE(!Z_ENABLE_ON) - #else - #define DISABLE_STEPPER_Z2() NOOP - #endif + #define DISABLE_STEPPER_Z2() TERN(HAS_Z2_ENABLE, Z2_ENABLE_WRITE(!Z_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Z3 - #if HAS_Z3_ENABLE - #define ENABLE_STEPPER_Z3() Z3_ENABLE_WRITE( Z_ENABLE_ON) - #else - #define ENABLE_STEPPER_Z3() NOOP - #endif + #define ENABLE_STEPPER_Z3() TERN(HAS_Z3_ENABLE, Z3_ENABLE_WRITE( Z_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Z3 - #if HAS_Z3_ENABLE - #define DISABLE_STEPPER_Z3() Z3_ENABLE_WRITE(!Z_ENABLE_ON) - #else - #define DISABLE_STEPPER_Z3() NOOP - #endif + #define DISABLE_STEPPER_Z3() TERN(HAS_Z3_ENABLE, Z3_ENABLE_WRITE(!Z_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_Z4 - #if HAS_Z4_ENABLE - #define ENABLE_STEPPER_Z4() Z4_ENABLE_WRITE( Z_ENABLE_ON) - #else - #define ENABLE_STEPPER_Z4() NOOP - #endif + #define ENABLE_STEPPER_Z4() TERN(HAS_Z4_ENABLE, Z4_ENABLE_WRITE( Z_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_Z4 - #if HAS_Z4_ENABLE - #define DISABLE_STEPPER_Z4() Z4_ENABLE_WRITE(!Z_ENABLE_ON) - #else - #define DISABLE_STEPPER_Z4() NOOP - #endif + #define DISABLE_STEPPER_Z4() TERN(HAS_Z4_ENABLE, Z4_ENABLE_WRITE(!Z_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_I - #if HAS_I_ENABLE - #define ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON) - #else - #define ENABLE_STEPPER_I() NOOP - #endif + #define ENABLE_STEPPER_I() TERN(HAS_I_ENABLE, I_ENABLE_WRITE( I_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_I - #if HAS_I_ENABLE - #define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON) - #else - #define DISABLE_STEPPER_I() NOOP - #endif + #define DISABLE_STEPPER_I() TERN(HAS_I_ENABLE, I_ENABLE_WRITE(!I_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_J - #if HAS_J_ENABLE - #define ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON) - #else - #define ENABLE_STEPPER_J() NOOP - #endif + #define ENABLE_STEPPER_J() TERN(HAS_J_ENABLE, J_ENABLE_WRITE( J_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_J - #if HAS_J_ENABLE - #define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON) - #else - #define DISABLE_STEPPER_J() NOOP - #endif + #define DISABLE_STEPPER_J() TERN(HAS_J_ENABLE, J_ENABLE_WRITE(!J_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_K - #if HAS_K_ENABLE - #define ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON) - #else - #define ENABLE_STEPPER_K() NOOP - #endif + #define ENABLE_STEPPER_K() TERN(HAS_K_ENABLE, K_ENABLE_WRITE( K_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_K - #if HAS_K_ENABLE - #define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON) - #else - #define DISABLE_STEPPER_K() NOOP - #endif + #define DISABLE_STEPPER_K() TERN(HAS_K_ENABLE, K_ENABLE_WRITE(!K_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_E0 - #if HAS_E0_ENABLE - #define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON) - #else - #define ENABLE_STEPPER_E0() NOOP - #endif + #define ENABLE_STEPPER_E0() TERN(HAS_E0_ENABLE, E0_ENABLE_WRITE( E_ENABLE_ON), NOOP) #endif #ifndef DISABLE_STEPPER_E0 - #if HAS_E0_ENABLE - #define DISABLE_STEPPER_E0() E0_ENABLE_WRITE(!E_ENABLE_ON) - #else - #define DISABLE_STEPPER_E0() NOOP - #endif + #define DISABLE_STEPPER_E0() TERN(HAS_E0_ENABLE, E0_ENABLE_WRITE(!E_ENABLE_ON), NOOP) #endif #ifndef ENABLE_STEPPER_E1 diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 7957a1b353..0a956a70b3 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -194,7 +194,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z #endif static constexpr chopper_timing_t chopper_timing_Z2 = CHOPPER_TIMING_Z2; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define Z2_ENABLE_INIT() NOOP #define Z2_ENABLE_WRITE(STATE) stepperZ2.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z2.toff : 0) #define Z2_ENABLE_READ() stepperZ2.isEnabled() @@ -287,7 +287,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E0 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E0 = CHOPPER_TIMING_E0; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E0_ENABLE_INIT() NOOP #define E0_ENABLE_WRITE(STATE) stepperE0.toff((STATE)==E_ENABLE_ON ? chopper_timing_E0.toff : 0) #define E0_ENABLE_READ() stepperE0.isEnabled() @@ -304,7 +304,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E1 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E1 = CHOPPER_TIMING_E1; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E1_ENABLE_INIT() NOOP #define E1_ENABLE_WRITE(STATE) stepperE1.toff((STATE)==E_ENABLE_ON ? chopper_timing_E1.toff : 0) #define E1_ENABLE_READ() stepperE1.isEnabled() @@ -321,7 +321,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E2 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E2 = CHOPPER_TIMING_E2; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E2_ENABLE_INIT() NOOP #define E2_ENABLE_WRITE(STATE) stepperE2.toff((STATE)==E_ENABLE_ON ? chopper_timing_E2.toff : 0) #define E2_ENABLE_READ() stepperE2.isEnabled() @@ -338,7 +338,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E3 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E3 = CHOPPER_TIMING_E3; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E3_ENABLE_INIT() NOOP #define E3_ENABLE_WRITE(STATE) stepperE3.toff((STATE)==E_ENABLE_ON ? chopper_timing_E3.toff : 0) #define E3_ENABLE_READ() stepperE3.isEnabled() @@ -355,7 +355,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E4 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E4 = CHOPPER_TIMING_E4; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E4_ENABLE_INIT() NOOP #define E4_ENABLE_WRITE(STATE) stepperE4.toff((STATE)==E_ENABLE_ON ? chopper_timing_E4.toff : 0) #define E4_ENABLE_READ() stepperE4.isEnabled() @@ -372,7 +372,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E5 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E5 = CHOPPER_TIMING_E5; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E5_ENABLE_INIT() NOOP #define E5_ENABLE_WRITE(STATE) stepperE5.toff((STATE)==E_ENABLE_ON ? chopper_timing_E5.toff : 0) #define E5_ENABLE_READ() stepperE5.isEnabled() @@ -389,7 +389,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E6 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E6 = CHOPPER_TIMING_E6; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E6_ENABLE_INIT() NOOP #define E6_ENABLE_WRITE(STATE) stepperE6.toff((STATE)==E_ENABLE_ON ? chopper_timing_E6.toff : 0) #define E6_ENABLE_READ() stepperE6.isEnabled() @@ -406,7 +406,7 @@ void reset_trinamic_drivers(); #define CHOPPER_TIMING_E7 CHOPPER_TIMING_E #endif static constexpr chopper_timing_t chopper_timing_E7 = CHOPPER_TIMING_E7; - #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7) + #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define E7_ENABLE_INIT() NOOP #define E7_ENABLE_WRITE(STATE) stepperE7.toff((STATE)==E_ENABLE_ON ? chopper_timing_E7.toff : 0) #define E7_ENABLE_READ() stepperE7.isEnabled() diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 66cb97baeb..97003e1d13 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -27,8 +27,13 @@ extern const char M23_STR[], M24_STR[]; -#if BOTH(SDCARD_SORT_ALPHA, SDSORT_DYNAMIC_RAM) - #define SD_RESORT 1 +#if ENABLED(SDCARD_SORT_ALPHA) + #if ENABLED(SDSORT_DYNAMIC_RAM) + #define SD_RESORT 1 + #endif + #if FOLDER_SORTING || ENABLED(SDSORT_GCODE) + #define HAS_FOLDER_SORTING 1 + #endif #endif #if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) From 0387f94632d24b9d43397b063767940fe17acc62 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 22 Sep 2021 01:02:28 +0000 Subject: [PATCH 0713/2168] [cron] Bump distribution date (2021-09-22) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 2b7215529e..c1d23db990 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-21" +//#define STRING_DISTRIBUTION_DATE "2021-09-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0531a37550..6a31ac6cdd 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 "2021-09-21" + #define STRING_DISTRIBUTION_DATE "2021-09-22" #endif /** From 11ceea25ce145c8485b516fdb010809409d2bb06 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Sep 2021 00:19:26 -0500 Subject: [PATCH 0714/2168] =?UTF-8?q?=F0=9F=8E=A8=20Less=20use=20of=20unde?= =?UTF-8?q?f=20for=20RAMPS=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 29 ++-- Marlin/src/pins/ramps/pins_3DRAG.h | 135 +++++++++--------- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 102 +++++++------ Marlin/src/pins/ramps/pins_K8400.h | 25 ++-- Marlin/src/pins/ramps/pins_K8600.h | 11 +- Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h | 39 ++--- Marlin/src/pins/ramps/pins_ORTUR_4.h | 24 +--- Marlin/src/pins/ramps/pins_RAMPS.h | 38 +++-- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 23 ++- Marlin/src/pins/ramps/pins_RIGIDBOARD.h | 30 ++-- Marlin/src/pins/ramps/pins_TRIGORILLA_13.h | 11 +- 11 files changed, 224 insertions(+), 243 deletions(-) diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 5dea438d70..86aff16f92 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -67,9 +67,19 @@ #define X_DIR_PIN 57 #define X_ENABLE_PIN 59 -#define Y_STEP_PIN 5 -#define Y_DIR_PIN 17 -#define Y_ENABLE_PIN 4 +#if ENABLED(REPRAPWORLD_KEYPAD) && EXTRUDERS <= 2 + #define Y_ENABLE_PIN 23 + #define Y_STEP_PIN 22 + #define Y_DIR_PIN 60 +#else + #define Y_STEP_PIN 5 + #define Y_DIR_PIN 17 + #define Y_ENABLE_PIN 4 + + #define E2_STEP_PIN 22 + #define E2_DIR_PIN 60 + #define E2_ENABLE_PIN 23 +#endif #define Z_STEP_PIN 16 #define Z_DIR_PIN 11 @@ -83,10 +93,6 @@ #define E1_DIR_PIN 24 #define E1_ENABLE_PIN 26 -#define E2_STEP_PIN 22 -#define E2_DIR_PIN 60 -#define E2_ENABLE_PIN 23 - // // Temperature Sensors // @@ -181,15 +187,6 @@ #elif EXTRUDERS <= 2 // Hijack the last extruder so that we can get the PWM signal off the Y breakout // Move Y to the E2 plug. This makes dual Y steppers harder - #undef Y_ENABLE_PIN // 4 - #undef Y_STEP_PIN // 5 - #undef Y_DIR_PIN // 17 - #undef E2_ENABLE_PIN // 23 - #undef E2_STEP_PIN // 22 - #undef E2_DIR_PIN // 60 - #define Y_ENABLE_PIN 23 - #define Y_STEP_PIN 22 - #define Y_DIR_PIN 60 #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 17 // Pullup! #define SPINDLE_DIR_PIN 5 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 316323ef9c..5bd1667356 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -37,6 +37,28 @@ #define DEFAULT_SOURCE_CODE_URL "3dprint.elettronicain.it" #endif +// +// Limit Switches +// +#define Z_STOP_PIN 18 + +// +// Steppers +// +#if HAS_CUTTER + #define Z_DIR_PIN 28 + #define Z_ENABLE_PIN 24 + #define Z_STEP_PIN 26 +#else + #define Z_ENABLE_PIN 63 +#endif + +#if HAS_CUTTER && !HAS_EXTRUDERS + #define E0_DIR_PIN -1 + #define E0_ENABLE_PIN -1 + #define E0_STEP_PIN -1 +#endif + // // Heaters / Fans // @@ -53,19 +75,55 @@ #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header #endif +/** + * M3/M4/M5 - Spindle/Laser Control + * + * If you want to control the speed of your spindle then you'll have + * have to sacrifce the Extruder and pull some signals off the Z stepper + * driver socket. + * + * The following assumes: + * - the Z stepper driver socket is empty + * - the extruder driver socket has a driver board plugged into it + * - the Z stepper wires are attached the the extruder connector + * + * If you want to keep the extruder AND don't have a LCD display then + * you can still control the power on/off and spindle direction. + * + * Where to get spindle signals + * + * stepper signal socket name socket name + * ------- + * SPINDLE_LASER_ENA_PIN /ENABLE O| |O VMOT + * MS1 O| |O GND + * MS2 O| |O 2B + * MS3 O| |O 2A + * /RESET O| |O 1A + * /SLEEP O| |O 1B + * SPINDLE_LASER_PWM_PIN STEP O| |O VDD + * SPINDLE_DIR_PIN DIR O| |O GND + * ------- + * + * Note: Socket names vary from vendor to vendor + */ +#if HAS_CUTTER + #if !HAS_EXTRUDERS + #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 62 // Pullup! + #define SPINDLE_DIR_PIN 48 + #elif !BOTH(IS_ULTRA_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use + #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 17 + #if !NUM_SERVOS // Use servo connector if possible + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #elif HAS_FREE_AUX2_PINS + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #endif + #endif +#endif + #include "pins_RAMPS.h" -// -// Limit Switches -// -#undef Z_MAX_PIN - -// -// Steppers -// -#undef Z_ENABLE_PIN -#define Z_ENABLE_PIN 63 - // // Heaters / Fans // @@ -113,58 +171,3 @@ #define BOARD_ST7920_DELAY_2 188 #define BOARD_ST7920_DELAY_3 0 #endif - -/** - * M3/M4/M5 - Spindle/Laser Control - * - * If you want to control the speed of your spindle then you'll have - * have to sacrifce the Extruder and pull some signals off the Z stepper - * driver socket. - * - * The following assumes: - * - the Z stepper driver socket is empty - * - the extruder driver socket has a driver board plugged into it - * - the Z stepper wires are attached the the extruder connector - * - * If you want to keep the extruder AND don't have a LCD display then - * you can still control the power on/off and spindle direction. - * - * Where to get spindle signals - * - * stepper signal socket name socket name - * ------- - * SPINDLE_LASER_ENA_PIN /ENABLE O| |O VMOT - * MS1 O| |O GND - * MS2 O| |O 2B - * MS3 O| |O 2A - * /RESET O| |O 1A - * /SLEEP O| |O 1B - * SPINDLE_LASER_PWM_PIN STEP O| |O VDD - * SPINDLE_DIR_PIN DIR O| |O GND - * ------- - * - * Note: Socket names vary from vendor to vendor - */ -#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not good with 3DRAG -#undef SPINDLE_LASER_ENA_PIN -#undef SPINDLE_DIR_PIN - -#if HAS_CUTTER - #if !HAS_EXTRUDERS - #undef E0_DIR_PIN - #undef E0_ENABLE_PIN - #undef E0_STEP_PIN - #undef Z_DIR_PIN - #undef Z_ENABLE_PIN - #undef Z_STEP_PIN - #define Z_DIR_PIN 28 - #define Z_ENABLE_PIN 24 - #define Z_STEP_PIN 26 - #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 62 // Pullup! - #define SPINDLE_DIR_PIN 48 - #elif !BOTH(IS_ULTRA_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use - #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! - #define SPINDLE_DIR_PIN 17 - #endif -#endif diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 14f54cdcf3..7715eca7eb 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -30,6 +30,41 @@ #define BOARD_INFO_NAME "ZUM Mega 3D" +// +// Limit Switches +// +#define X_MAX_PIN 79 + +// This board has headers for Z-min, Z-max and IND_S_5V *but* as the bq team +// decided to ship the printer only with the probe and no additional Z-min +// endstop and the instruction manual advises the user to connect the probe to +// IND_S_5V the option Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN will not work. +#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #define Z_MIN_PIN 19 // IND_S_5V + #define Z_MAX_PIN 18 // Z-MIN Label +#endif + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 19 // IND_S_5V +#endif + +// +// Steppers +// +#define Z_ENABLE_PIN 77 + +#define DIGIPOTSS_PIN 22 +#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } + +// +// Temperature Sensors +// +#define TEMP_1_PIN 14 // Analog Input +#define TEMP_BED_PIN 15 // Analog Input + // // Heaters / Fans // @@ -61,72 +96,31 @@ #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM #define SPINDLE_DIR_PIN 42 -// -// Limit Switches -// -#define X_MAX_PIN 79 // 2 - -// -// Import RAMPS 1.3 pins -// -#include "pins_RAMPS_13.h" - -// -// Z Probe (when not Z_MIN_PIN) -// -#undef Z_MIN_PROBE_PIN -#define Z_MIN_PROBE_PIN 19 // IND_S_5V - -#undef Z_ENABLE_PIN -#define Z_ENABLE_PIN 77 // 62 - -// -// Steppers -// -#define DIGIPOTSS_PIN 22 -#define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } - -// -// Temperature Sensors -// -#undef TEMP_1_PIN -#define TEMP_1_PIN 14 // Analog Input (15) - -#undef TEMP_BED_PIN -#define TEMP_BED_PIN 15 // Analog Input (14) - // // Misc. Functions // -#undef PS_ON_PIN // 12 #define PS_ON_PIN 81 // External Power Supply #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN 44 // Hardware PWM #endif -// This board has headers for Z-min, Z-max and IND_S_5V *but* as the bq team -// decided to ship the printer only with the probe and no additional Z-min -// endstop and the instruction manual advises the user to connect the probe to -// IND_S_5V the option Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN will not work. -#ifdef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - #undef Z_MIN_PIN - #undef Z_MAX_PIN - #define Z_MIN_PIN 19 // IND_S_5V - #define Z_MAX_PIN 18 // Z-MIN Label -#endif - -// -// Used by the Hephestos 2 heated bed upgrade kit -// -#if ENABLED(HEPHESTOS2_HEATED_BED_KIT) - #undef HEATER_BED_PIN - #define HEATER_BED_PIN 8 -#endif - // Alter timing for graphical display #if ENABLED(U8GLIB_ST7920) #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 0 #define BOARD_ST7920_DELAY_3 189 #endif + +// +// Import RAMPS 1.3 pins +// +#include "pins_RAMPS_13.h" + +// +// Used by the Hephestos 2 heated bed upgrade kit +// +#if ENABLED(HEPHESTOS2_HEATED_BED_KIT) + #undef HEATER_BED_PIN + #define HEATER_BED_PIN 8 +#endif diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index af687927f4..bed2238162 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -35,7 +35,14 @@ #define BOARD_INFO_NAME "K8400" #define DEFAULT_MACHINE_NAME "Vertex" -#include "pins_3DRAG.h" +// +// Steppers +// +#if HAS_CUTTER + #define Z_STEP_PIN 32 +#endif + +#define E1_STEP_PIN 32 // // Limit Switches @@ -43,16 +50,7 @@ #define X_STOP_PIN 3 #define Y_STOP_PIN 14 -#undef X_MIN_PIN -#undef X_MAX_PIN -#undef Y_MIN_PIN -#undef Y_MAX_PIN - -// -// Steppers -// -#undef E1_STEP_PIN -#define E1_STEP_PIN 32 +#include "pins_3DRAG.h" // // Heaters / Fans @@ -66,8 +64,3 @@ #undef PS_ON_PIN #undef KILL_PIN #undef SD_DETECT_PIN - -#if Z_STEP_PIN == 26 - #undef Z_STEP_PIN - #define Z_STEP_PIN 32 -#endif diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 9049308ba8..d312490dbe 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -40,6 +40,11 @@ #define Z_MAX_PIN 18 #define Z_MIN_PIN -1 +// +// Steppers +// +#define Z_ENABLE_PIN 63 + // // Heaters / Fans // @@ -57,12 +62,6 @@ #define IS_RAMPS_EFB // Override autodetection. Bed will be undefined. #include "pins_RAMPS.h" -// -// Steppers -// -#undef Z_ENABLE_PIN -#define Z_ENABLE_PIN 63 - // // Heaters / Fans // diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index 5ff3b366be..ccf7ab6793 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -82,11 +82,31 @@ #define Z_MAX_PIN 37 #endif +#undef CHANGE_Y_LIMIT_PINS + +// +// Steppers - No E1 pins +// +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 +#define E1_CS_PIN -1 + // // Z Probe (when not Z_MIN_PIN) // #define Z_MIN_PROBE_PIN -1 +// +// Temperature Sensors +// +#define TEMP_1_PIN -1 + +// +// Průša i3 MK2 Multiplexer Support +// +#define E_MUX2_PIN -1 + // // Misc. Functions // @@ -98,22 +118,3 @@ // #define IS_RAMPS_EFB // Override autodetection. Bed will be undefined. #include "pins_RAMPS_13.h" - -// -// Steppers -// -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN -#undef E1_CS_PIN - -// -// Temperature Sensors -// -#undef TEMP_1_PIN - -// -// Průša i3 MK2 Multiplexer Support -// -#undef E_MUX2_PIN -#undef CHANGE_Y_LIMIT_PINS diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h index 428279c92a..bc86c1a8c6 100644 --- a/Marlin/src/pins/ramps/pins_ORTUR_4.h +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -45,7 +45,14 @@ // // Steppers // +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 #define E0_CS_PIN 44 + +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 #define E1_CS_PIN 42 // @@ -70,23 +77,6 @@ #include "pins_RAMPS.h" -// -// Steppers -// -#undef E0_STEP_PIN -#undef E0_DIR_PIN -#undef E0_ENABLE_PIN -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 - -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 - // // LCD / Controller // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index b51d212f4f..e90c3d03fc 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -133,22 +133,38 @@ #ifndef Z_STEP_PIN #define Z_STEP_PIN 46 #endif -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#ifndef Z_DIR_PIN + #define Z_DIR_PIN 48 +#endif +#ifndef Z_ENABLE_PIN + #define Z_ENABLE_PIN 62 +#endif #ifndef Z_CS_PIN #define Z_CS_PIN 40 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#ifndef E0_STEP_PIN + #define E0_STEP_PIN 26 +#endif +#ifndef E0_DIR_PIN + #define E0_DIR_PIN 28 +#endif +#ifndef E0_ENABLE_PIN + #define E0_ENABLE_PIN 24 +#endif #ifndef E0_CS_PIN #define E0_CS_PIN 42 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#ifndef E1_STEP_PIN + #define E1_STEP_PIN 36 +#endif +#ifndef E1_DIR_PIN + #define E1_DIR_PIN 34 +#endif +#ifndef E1_ENABLE_PIN + #define E1_ENABLE_PIN 30 +#endif #ifndef E1_CS_PIN #define E1_CS_PIN 44 #endif @@ -219,10 +235,10 @@ #define FAN1_PIN RAMPS_D8_PIN #elif DISABLED(IS_RAMPS_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN RAMPS_D8_PIN - #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) - #define FAN1_PIN MOSFET_D_PIN - #else + #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define HEATER_1_PIN MOSFET_D_PIN + #else + #define FAN1_PIN MOSFET_D_PIN #endif #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 43a769b34d..af91f63bdb 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -44,32 +44,25 @@ #define RAMPS_D8_PIN 10 #define RAMPS_D10_PIN 8 -#include "pins_RAMPS.h" - // -// Steppers - Swap E0 / E1 on 3DYMY +// Steppers // -#undef E0_STEP_PIN -#undef E0_DIR_PIN -#undef E0_ENABLE_PIN - -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN +#define X_CS_PIN -1 +#define Y_CS_PIN -1 +#define Z_CS_PIN -1 +// Swap E0 / E1 on 3DYMY #define E0_STEP_PIN 36 #define E0_DIR_PIN 34 #define E0_ENABLE_PIN 30 +#define E0_CS_PIN -1 #define E1_STEP_PIN 26 #define E1_DIR_PIN 28 #define E1_ENABLE_PIN 24 +#define E1_CS_PIN -1 -#undef X_CS_PIN -#undef Y_CS_PIN -#undef Z_CS_PIN -#undef E0_CS_PIN -#undef E1_CS_PIN +#include "pins_RAMPS.h" #if IS_ULTRA_LCD && NONE(REPRAPWORLD_GRAPHICAL_LCD, CR10_STOCKDISPLAY) && !BOTH(IS_NEWPANEL, PANEL_ONE) #if DISABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306) diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index 203af5e081..0263c78b06 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -29,6 +29,18 @@ #define BOARD_INFO_NAME "RigidBoard" #endif +// +// Steppers +// RigidBot swaps E0 / E1 plugs vs RAMPS 1.3 +// +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 + +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 + // // Z Probe (when not Z_MIN_PIN) // @@ -45,24 +57,6 @@ #include "pins_RAMPS.h" -// -// Steppers -// -// RigidBot swaps E0 / E1 plugs vs RAMPS 1.3 -#undef E0_STEP_PIN -#undef E0_DIR_PIN -#undef E0_ENABLE_PIN -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 - -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 - #define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot // diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h index 9508be0173..ce9e4e5466 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h @@ -29,6 +29,12 @@ #define IS_RAMPS_EFB #define RAMPS_D9_PIN 44 + +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 +#define E1_CS_PIN -1 + #define FAN2_PIN 9 #ifndef E0_AUTO_FAN_PIN @@ -36,8 +42,3 @@ #endif #include "pins_RAMPS_13.h" - -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN -#undef E1_CS_PIN From 64c6475434349f88c61fdd403b4e9e830fd60b35 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 23 Sep 2021 01:04:29 +0000 Subject: [PATCH 0715/2168] [cron] Bump distribution date (2021-09-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c1d23db990..2284ab23c6 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-22" +//#define STRING_DISTRIBUTION_DATE "2021-09-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6a31ac6cdd..7d0b19c00c 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 "2021-09-22" + #define STRING_DISTRIBUTION_DATE "2021-09-23" #endif /** From 1835f8fb25648888cf6df6e17af1cefdd1248d71 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Sep 2021 00:51:35 -0500 Subject: [PATCH 0716/2168] =?UTF-8?q?=F0=9F=A9=B9=20Add=20MarlinSPI=20to?= =?UTF-8?q?=20more=20HALs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 3 ++- Marlin/src/HAL/AVR/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/DUE/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/ESP32/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/LINUX/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/SAMD51/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/TEENSY31_32/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/TEENSY35_36/MarlinSPI.h | 26 ++++++++++++++++++++++++++ Marlin/src/HAL/TEENSY40_41/MarlinSPI.h | 26 ++++++++++++++++++++++++++ 9 files changed, 210 insertions(+), 1 deletion(-) create mode 100644 Marlin/src/HAL/AVR/MarlinSPI.h create mode 100644 Marlin/src/HAL/DUE/MarlinSPI.h create mode 100644 Marlin/src/HAL/ESP32/MarlinSPI.h create mode 100644 Marlin/src/HAL/LINUX/MarlinSPI.h create mode 100644 Marlin/src/HAL/SAMD51/MarlinSPI.h create mode 100644 Marlin/src/HAL/TEENSY31_32/MarlinSPI.h create mode 100644 Marlin/src/HAL/TEENSY35_36/MarlinSPI.h create mode 100644 Marlin/src/HAL/TEENSY40_41/MarlinSPI.h diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 1a1b98b3dd..319d64c8f6 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -74,7 +74,8 @@ void spiBegin() { #elif defined(PRR0) PRR0 #endif - , PRSPI); + , PRSPI + ); SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1); SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X); diff --git a/Marlin/src/HAL/AVR/MarlinSPI.h b/Marlin/src/HAL/AVR/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/AVR/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/DUE/MarlinSPI.h b/Marlin/src/HAL/DUE/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/DUE/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/ESP32/MarlinSPI.h b/Marlin/src/HAL/ESP32/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/ESP32/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/LINUX/MarlinSPI.h b/Marlin/src/HAL/LINUX/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/LINUX/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/SAMD51/MarlinSPI.h b/Marlin/src/HAL/SAMD51/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/SAMD51/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h b/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h b/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h b/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h new file mode 100644 index 0000000000..0c447ba4cb --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#include + +using MarlinSPI = SPIClass; From 7c5727e0ec1c69bf4bb72dcd34d6acce02a8c09e Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 23 Sep 2021 18:58:52 +1200 Subject: [PATCH 0717/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20anycubic=5Fi3meg?= =?UTF-8?q?a=5Flcd=20debug=20macros=20(#22820)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index b739e83dc1..4f51e04c21 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -38,8 +38,8 @@ #define SEND(x) send(x) #define SENDLINE(x) sendLine(x) #if ENABLED(ANYCUBIC_LCD_DEBUG) - #define SENDLINE_DBG_PGM(x,y) (sendLine_P(PSTR(x)), SERIAL_ECHOLNPGM(y)) - #define SENDLINE_DBG_PGM_VAL(x,y,z) (sendLine_P(PSTR(x)), SERIAL_ECHOPGM(y), SERIAL_ECHOLN(z)) + #define SENDLINE_DBG_PGM(x,y) do{ sendLine_P(PSTR(x)); SERIAL_ECHOLNPGM(y); }while(0) + #define SENDLINE_DBG_PGM_VAL(x,y,z) do{ sendLine_P(PSTR(x)); SERIAL_ECHOLNPGM(y, z); }while(0) #else #define SENDLINE_DBG_PGM(x,y) sendLine_P(PSTR(x)) #define SENDLINE_DBG_PGM_VAL(x,y,z) sendLine_P(PSTR(x)) From 9c208a008d4f336f1bdc095af0a50754311092d1 Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Thu, 23 Sep 2021 15:53:48 +0800 Subject: [PATCH 0718/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Improve=20LVGL?= =?UTF-8?q?=20touch=20driver=20(#22817)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../extui/mks_ui/tft_lvgl_configuration.cpp | 46 ++++++++----------- buildroot/tests/mks_robin_maple | 1 + 2 files changed, 19 insertions(+), 28 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 9a742e1f3b..837d7470d6 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -264,9 +264,7 @@ unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick) { } static bool get_point(int16_t *x, int16_t *y) { - bool is_touched = touch.getRawPoint(x, y); - - if (!is_touched) return false; + if (!touch.getRawPoint(x, y)) return false; #if ENABLED(TOUCH_SCREEN_CALIBRATION) const calibrationState state = touch_calibration.get_calibration_state(); @@ -286,34 +284,26 @@ static bool get_point(int16_t *x, int16_t *y) { bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { static int16_t last_x = 0, last_y = 0; - static uint8_t last_touch_state = LV_INDEV_STATE_REL; - static int32_t touch_time1 = 0; - uint32_t tmpTime, diffTime = 0; - - tmpTime = millis(); - diffTime = getTickDiff(tmpTime, touch_time1); - if (diffTime > 20) { - if (get_point(&last_x, &last_y)) { - - if (last_touch_state == LV_INDEV_STATE_PR) return false; - data->state = LV_INDEV_STATE_PR; - - // Set the coordinates (if released use the last-pressed coordinates) + if (get_point(&last_x, &last_y)) { + #if TFT_ROTATION == TFT_ROTATE_180 + data->point.x = TFT_WIDTH - last_x; + data->point.y = TFT_HEIGHT - last_y; + #else data->point.x = last_x; data->point.y = last_y; - - last_x = last_y = 0; - last_touch_state = LV_INDEV_STATE_PR; - } - else { - if (last_touch_state == LV_INDEV_STATE_PR) - data->state = LV_INDEV_STATE_REL; - last_touch_state = LV_INDEV_STATE_REL; - } - - touch_time1 = tmpTime; + #endif + data->state = LV_INDEV_STATE_PR; + } + else { + #if TFT_ROTATION == TFT_ROTATE_180 + data->point.x = TFT_WIDTH - last_x; + data->point.y = TFT_HEIGHT - last_y; + #else + data->point.x = last_x; + data->point.y = last_y; + #endif + data->state = LV_INDEV_STATE_REL; } - return false; // Return `false` since no data is buffering or left to read } diff --git a/buildroot/tests/mks_robin_maple b/buildroot/tests/mks_robin_maple index fcb5118307..ab4e6d7118 100755 --- a/buildroot/tests/mks_robin_maple +++ b/buildroot/tests/mks_robin_maple @@ -16,6 +16,7 @@ exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" use_example_configs Mks/Robin opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 opt_enable TFT_LVGL_UI TFT_RES_480x320 +opt_set TFT_ROTATION TFT_ROTATE_180 exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" # cleanup From dc5bef62ba185461ba969db6af996ebc93a33ba7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Sep 2021 10:01:37 -0500 Subject: [PATCH 0719/2168] =?UTF-8?q?=F0=9F=8E=A8=20Various=20multi-axis?= =?UTF-8?q?=20patches=20(#22823)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 24 ++++----- Marlin/src/HAL/SAMD51/endstop_interrupts.h | 12 +++-- Marlin/src/core/macros.h | 63 +++++++++++++--------- Marlin/src/feature/backlash.cpp | 6 +-- Marlin/src/feature/backlash.h | 2 +- Marlin/src/gcode/config/M217.cpp | 6 +-- Marlin/src/gcode/feature/trinamic/M906.cpp | 26 ++++----- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/queue.cpp | 3 +- Marlin/src/inc/Conditionals_post.h | 26 ++++----- Marlin/src/inc/SanityCheck.h | 12 +++-- Marlin/src/lcd/extui/ui_api.cpp | 12 +++++ Marlin/src/module/planner.cpp | 8 +-- Marlin/src/module/planner.h | 2 +- Marlin/src/module/stepper.cpp | 30 +++++------ Marlin/src/module/stepper.h | 6 +-- Marlin/src/module/stepper/indirection.h | 6 +-- Marlin/src/module/stepper/trinamic.cpp | 17 +++--- Marlin/src/pins/pins_postprocess.h | 36 ++++++++++--- 20 files changed, 174 insertions(+), 127 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 7afb86dac7..c50af25e63 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -794,18 +794,18 @@ #define ENDSTOPPULLUPS #if DISABLED(ENDSTOPPULLUPS) // Disable ENDSTOPPULLUPS to set pullups individually - //#define ENDSTOPPULLUP_XMAX - //#define ENDSTOPPULLUP_YMAX - //#define ENDSTOPPULLUP_ZMAX - //#define ENDSTOPPULLUP_IMAX - //#define ENDSTOPPULLUP_JMAX - //#define ENDSTOPPULLUP_KMAX //#define ENDSTOPPULLUP_XMIN //#define ENDSTOPPULLUP_YMIN //#define ENDSTOPPULLUP_ZMIN //#define ENDSTOPPULLUP_IMIN //#define ENDSTOPPULLUP_JMIN //#define ENDSTOPPULLUP_KMIN + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_IMAX + //#define ENDSTOPPULLUP_JMAX + //#define ENDSTOPPULLUP_KMAX //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -813,18 +813,18 @@ //#define ENDSTOPPULLDOWNS #if DISABLED(ENDSTOPPULLDOWNS) // Disable ENDSTOPPULLDOWNS to set pulldowns individually - //#define ENDSTOPPULLDOWN_XMAX - //#define ENDSTOPPULLDOWN_YMAX - //#define ENDSTOPPULLDOWN_ZMAX - //#define ENDSTOPPULLDOWN_IMAX - //#define ENDSTOPPULLDOWN_JMAX - //#define ENDSTOPPULLDOWN_KMAX //#define ENDSTOPPULLDOWN_XMIN //#define ENDSTOPPULLDOWN_YMIN //#define ENDSTOPPULLDOWN_ZMIN //#define ENDSTOPPULLDOWN_IMIN //#define ENDSTOPPULLDOWN_JMIN //#define ENDSTOPPULLDOWN_KMIN + //#define ENDSTOPPULLDOWN_XMAX + //#define ENDSTOPPULLDOWN_YMAX + //#define ENDSTOPPULLDOWN_ZMAX + //#define ENDSTOPPULLDOWN_IMAX + //#define ENDSTOPPULLDOWN_JMAX + //#define ENDSTOPPULLDOWN_KMAX //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index c46b6e072f..61a06c0d4b 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -162,12 +162,14 @@ void setup_endstop_interrupts() { #error "Z_MIN_PROBE_PIN has no EXTINT line available." #endif _ATTACH(Z_MIN_PROBE_PIN); - #elif HAS_I_MAX + #endif + #if HAS_I_MAX #if !AVAILABLE_EILINE(I_MAX_PIN) #error "I_MAX_PIN has no EXTINT line available." #endif attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); - #elif HAS_I_MIN + #endif + #if HAS_I_MIN #if !AVAILABLE_EILINE(I_MIN_PIN) #error "I_MIN_PIN has no EXTINT line available." #endif @@ -178,7 +180,8 @@ void setup_endstop_interrupts() { #error "J_MAX_PIN has no EXTINT line available." #endif attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); - #elif HAS_J_MIN + #endif + #if HAS_J_MIN #if !AVAILABLE_EILINE(J_MIN_PIN) #error "J_MIN_PIN has no EXTINT line available." #endif @@ -189,7 +192,8 @@ void setup_endstop_interrupts() { #error "K_MAX_PIN has no EXTINT line available." #endif attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); - #elif HAS_K_MIN + #endif + #if HAS_K_MIN #if !AVAILABLE_EILINE(K_MIN_PIN) #error "K_MIN_PIN has no EXTINT line available." #endif diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 0174e21add..22c3767e1d 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -33,32 +33,32 @@ #define _AXIS(A) (A##_AXIS) -#define _XMIN_ 100 -#define _YMIN_ 200 -#define _ZMIN_ 300 -#define _IMIN_ 500 -#define _JMIN_ 600 -#define _KMIN_ 700 -#define _XMAX_ 101 -#define _YMAX_ 201 -#define _ZMAX_ 301 -#define _IMAX_ 501 -#define _JMAX_ 601 -#define _KMAX_ 701 -#define _XDIAG_ 102 -#define _YDIAG_ 202 -#define _ZDIAG_ 302 -#define _IDIAG_ 502 -#define _JDIAG_ 602 -#define _KDIAG_ 702 -#define _E0DIAG_ 400 -#define _E1DIAG_ 401 -#define _E2DIAG_ 402 -#define _E3DIAG_ 403 -#define _E4DIAG_ 404 -#define _E5DIAG_ 405 -#define _E6DIAG_ 406 -#define _E7DIAG_ 407 +#define _XMIN_ 0x11 +#define _YMIN_ 0x12 +#define _ZMIN_ 0x13 +#define _IMIN_ 0x14 +#define _JMIN_ 0x15 +#define _KMIN_ 0x16 +#define _XMAX_ 0x21 +#define _YMAX_ 0x22 +#define _ZMAX_ 0x23 +#define _IMAX_ 0x24 +#define _JMAX_ 0x25 +#define _KMAX_ 0x26 +#define _XDIAG_ 0x31 +#define _YDIAG_ 0x32 +#define _ZDIAG_ 0x33 +#define _IDIAG_ 0x34 +#define _JDIAG_ 0x35 +#define _KDIAG_ 0x36 +#define _E0DIAG_ 0xE0 +#define _E1DIAG_ 0xE1 +#define _E2DIAG_ 0xE2 +#define _E3DIAG_ 0xE3 +#define _E4DIAG_ 0xE4 +#define _E5DIAG_ 0xE5 +#define _E6DIAG_ 0xE6 +#define _E7DIAG_ 0xE7 #define _FORCE_INLINE_ __attribute__((__always_inline__)) __inline__ #define FORCE_INLINE __attribute__((always_inline)) inline @@ -251,6 +251,8 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +#define CODE_11( A,B,C,D,E,F,G,H,I,J,K,...) A; B; C; D; E; F; G; H; I; J; K +#define CODE_10( A,B,C,D,E,F,G,H,I,J,...) A; B; C; D; E; F; G; H; I; J #define CODE_9( A,B,C,D,E,F,G,H,I,...) A; B; C; D; E; F; G; H; I #define CODE_8( A,B,C,D,E,F,G,H,...) A; B; C; D; E; F; G; H #define CODE_7( A,B,C,D,E,F,G,...) A; B; C; D; E; F; G @@ -286,6 +288,10 @@ #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) // Macros for initializing arrays +#define LIST_20(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T +#define LIST_19(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S +#define LIST_18(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R +#define LIST_17(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q #define LIST_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P #define LIST_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O #define LIST_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N @@ -502,6 +508,11 @@ #define INC_13 14 #define INC_14 15 #define INC_15 16 +#define INC_16 17 +#define INC_17 18 +#define INC_18 19 +#define INC_19 20 +#define INC_20 21 #define INCREMENT_(n) INC_##n #define INCREMENT(n) INCREMENT_(n) diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 23dc973049..b646e19f15 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -60,9 +60,9 @@ Backlash backlash; * spread over multiple segments, smoothing out artifacts even more. */ -void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const uint8_t dm, block_t * const block) { - static uint8_t last_direction_bits; - uint8_t changed_dir = last_direction_bits ^ dm; +void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block) { + static axis_bits_t last_direction_bits; + axis_bits_t changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction #if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY) if (!da) CBI(changed_dir, X_AXIS); diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 500168b380..4d4e294038 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -71,7 +71,7 @@ public: return has_measurement(X_AXIS) || has_measurement(Y_AXIS) || has_measurement(Z_AXIS); } - void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const uint8_t dm, block_t * const block); + void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block); }; extern Backlash backlash; diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 11d8c43ef0..923a27d7df 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -141,9 +141,9 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) { SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed), - " U", LINEAR_UNIT(toolchange_settings.unretract_speed), - " F", toolchange_settings.fan_speed, - " G", toolchange_settings.fan_time); + " U", LINEAR_UNIT(toolchange_settings.unretract_speed), + " F", toolchange_settings.fan_speed, + " G", toolchange_settings.fan_time); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) SERIAL_ECHOPGM(" A", migration.automode); diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 8877603c3a..48db266c72 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -206,7 +206,8 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { SERIAL_ECHOPGM(" M906"); }; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) \ + || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) say_M906(forReplay); #if AXIS_IS_TMC(X) SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps()); @@ -217,6 +218,15 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { #if AXIS_IS_TMC(Z) SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.getMilliamps()); #endif + #if AXIS_IS_TMC(I) + SERIAL_ECHOPGM_P(SP_I_STR, stepperI.getMilliamps()); + #endif + #if AXIS_IS_TMC(J) + SERIAL_ECHOPGM_P(SP_J_STR, stepperJ.getMilliamps()); + #endif + #if AXIS_IS_TMC(K) + SERIAL_ECHOPGM_P(SP_K_STR, stepperK.getMilliamps()); + #endif SERIAL_EOL(); #endif @@ -239,25 +249,11 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { say_M906(forReplay); SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.getMilliamps()); #endif - #if AXIS_IS_TMC(Z4) say_M906(forReplay); SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.getMilliamps()); #endif - #if AXIS_IS_TMC(I) - say_M906(forReplay); - SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.getMilliamps()); - #endif - #if AXIS_IS_TMC(J) - say_M906(forReplay); - SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.getMilliamps()); - #endif - #if AXIS_IS_TMC(K) - say_M906(forReplay); - SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.getMilliamps()); - #endif - #if AXIS_IS_TMC(E0) say_M906(forReplay); SERIAL_ECHOLNPGM(" T0 E", stepperE0.getMilliamps()); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0fc6db07d6..888dbe7027 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -74,7 +74,7 @@ millis_t GcodeSuite::previous_move_ms = 0, // Relative motion mode for each logical axis static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; -uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( +axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( | (ar_init.e << REL_E), | (ar_init.x << REL_X), | (ar_init.y << REL_Y), diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index b10f0bf06a..a7fc7ff990 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -327,7 +327,7 @@ extern const char G28_STR[]; class GcodeSuite { public: - static uint8_t axis_relative; + static axis_bits_t axis_relative; static inline bool axis_is_relative(const AxisEnum a) { #if HAS_EXTRUDERS diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 07d7c536a6..d11b2823f2 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -260,8 +260,7 @@ void GCodeQueue::RingBuffer::ok_to_send() { while (NUMERIC_SIGNED(*p)) SERIAL_CHAR(*p++); } - SERIAL_ECHOPGM_P(SP_P_STR, planner.moves_free(), - SP_B_STR, BUFSIZE - length); + SERIAL_ECHOPGM_P(SP_P_STR, planner.moves_free(), SP_B_STR, BUFSIZE - length); #endif SERIAL_EOL(); } diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ccb7cdde7c..6c1511282f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1927,20 +1927,14 @@ #ifndef Z4_INTERPOLATE #define Z4_INTERPOLATE INTERPOLATE #endif - #if LINEAR_AXES >= 4 - #ifndef I_INTERPOLATE - #define I_INTERPOLATE INTERPOLATE - #endif + #if LINEAR_AXES >= 4 && !defined(I_INTERPOLATE) + #define I_INTERPOLATE INTERPOLATE #endif - #if LINEAR_AXES >= 5 - #ifndef J_INTERPOLATE - #define J_INTERPOLATE INTERPOLATE - #endif + #if LINEAR_AXES >= 5 && !defined(J_INTERPOLATE) + #define J_INTERPOLATE INTERPOLATE #endif - #if LINEAR_AXES >= 6 - #ifndef K_INTERPOLATE - #define K_INTERPOLATE INTERPOLATE - #endif + #if LINEAR_AXES >= 6 && !defined(K_INTERPOLATE) + #define K_INTERPOLATE INTERPOLATE #endif #ifndef E0_INTERPOLATE #define E0_INTERPOLATE INTERPOLATE @@ -1967,13 +1961,13 @@ #define E7_INTERPOLATE INTERPOLATE #endif #ifndef X_SLAVE_ADDRESS - #define X_SLAVE_ADDRESS 0 + #define X_SLAVE_ADDRESS 0 #endif #ifndef Y_SLAVE_ADDRESS - #define Y_SLAVE_ADDRESS 0 + #define Y_SLAVE_ADDRESS 0 #endif #ifndef Z_SLAVE_ADDRESS - #define Z_SLAVE_ADDRESS 0 + #define Z_SLAVE_ADDRESS 0 #endif #ifndef I_SLAVE_ADDRESS #define I_SLAVE_ADDRESS 0 @@ -2665,7 +2659,7 @@ #if HAS_EXTRUDERS && PIN_EXISTS(MOTOR_CURRENT_PWM_E) #define HAS_MOTOR_CURRENT_PWM_E 1 #endif -#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z) +#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K) #define HAS_MOTOR_CURRENT_PWM 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 720a04c502..5408f25f38 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1404,8 +1404,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif #if LINEAR_AXES >= 5 - #if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME - #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME" + #if AXIS5_NAME == AXIS4_NAME + #error "AXIS5_NAME must be unique." #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." #elif !defined(J_MIN_POS) || !defined(J_MAX_POS) @@ -1418,7 +1418,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if LINEAR_AXES >= 6 #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME - #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME." + #error "AXIS6_NAME must be unique." #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." #elif !defined(K_MIN_POS) || !defined(K_MAX_POS) @@ -3040,10 +3040,16 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_IMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMIN (or ENDSTOPPULLUPS) when homing to I_MIN." #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX." + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_JMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMIN (or ENDSTOPPULLUPS) when homing to J_MIN." #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX." + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_KMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMIN (or ENDSTOPPULLUPS) when homing to K_MIN." #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX." #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index b838299b18..97b1ab885b 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -423,6 +423,12 @@ namespace ExtUI { #if AXIS_IS_TMC(Z2) case Z2: return stepperZ2.getMilliamps(); #endif + #if AXIS_IS_TMC(Z3) + case Z3: return stepperZ3.getMilliamps(); + #endif + #if AXIS_IS_TMC(Z4) + case Z4: return stepperZ4.getMilliamps(); + #endif default: return NAN; }; } @@ -486,6 +492,12 @@ namespace ExtUI { #if AXIS_IS_TMC(Z2) case Z2: stepperZ2.rms_current(constrain(mA, 400, 1500)); break; #endif + #if AXIS_IS_TMC(Z3) + case Z3: stepperZ3.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(Z4) + case Z4: stepperZ4.rms_current(constrain(mA, 400, 1500)); break; + #endif default: break; }; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 04fabd2df7..511c3b3f43 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1310,7 +1310,7 @@ void Planner::recalculate() { */ void Planner::check_axes_activity() { - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E) xyze_bool_t axis_active = { false }; #endif @@ -1913,7 +1913,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // PREVENT_COLD_EXTRUSION || PREVENT_LENGTHY_EXTRUDE // Compute direction bit-mask for this block - uint8_t dm = 0; + axis_bits_t dm = 0; #if CORE_IS_XY if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y @@ -2345,11 +2345,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #ifdef XY_FREQUENCY_LIMIT - static uint8_t old_direction_bits; // = 0 + static axis_bits_t old_direction_bits; // = 0 if (xy_freq_limit_hz) { // Check and limit the xy direction change frequency - const uint8_t direction_change = block->direction_bits ^ old_direction_bits; + const axis_bits_t direction_change = block->direction_bits ^ old_direction_bits; old_direction_bits = block->direction_bits; segment_time_us = LROUND(float(segment_time_us) / speed_factor); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ea63f862e0..15744c3f9a 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -202,7 +202,7 @@ typedef struct block_t { uint32_t acceleration_rate; // The acceleration rate used for acceleration calculation #endif - uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) + axis_bits_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) // Advance extrusion #if ENABLED(LIN_ADVANCE) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 83aa15063b..aa68ccd4ec 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -149,8 +149,8 @@ Stepper stepper; // Singleton block_t* Stepper::current_block; // (= nullptr) A pointer to the block currently being traced -uint8_t Stepper::last_direction_bits, // = 0 - Stepper::axis_did_move; // = 0 +axis_bits_t Stepper::last_direction_bits, // = 0 + Stepper::axis_did_move; // = 0 bool Stepper::abort_current_block; @@ -503,17 +503,14 @@ void Stepper::set_directions() { #if HAS_Z_DIR SET_STEP_DIR(Z); // C #endif - #if HAS_I_DIR - SET_STEP_DIR(I); // I + SET_STEP_DIR(I); #endif - #if HAS_J_DIR - SET_STEP_DIR(J); // J + SET_STEP_DIR(J); #endif - #if HAS_K_DIR - SET_STEP_DIR(K); // K + SET_STEP_DIR(K); #endif #if DISABLED(LIN_ADVANCE) @@ -1635,7 +1632,7 @@ void Stepper::pulse_phase_isr() { case 0: { const uint8_t low = page_step_state.page[page_step_state.segment_idx], high = page_step_state.page[page_step_state.segment_idx + 1]; - uint8_t dm = last_direction_bits; + axis_bits_t dm = last_direction_bits; PAGE_SEGMENT_UPDATE(X, low >> 4); PAGE_SEGMENT_UPDATE(Y, low & 0xF); @@ -2156,7 +2153,7 @@ uint32_t Stepper::block_phase_isr() { #define Z_MOVE_TEST !!current_block->steps.c #endif - uint8_t axis_bits = 0; + axis_bits_t axis_bits = 0; LINEAR_AXIS_CODE( if (X_MOVE_TEST) SBI(axis_bits, A_AXIS), if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS), @@ -3003,16 +3000,15 @@ void Stepper::report_positions() { const bool z_direction = direction ^ BABYSTEP_INVERT_Z; - ENABLE_AXIS_X(); - ENABLE_AXIS_Y(); - ENABLE_AXIS_Z(); - ENABLE_AXIS_I(); - ENABLE_AXIS_J(); - ENABLE_AXIS_K(); + ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); ENABLE_AXIS_J(); ENABLE_AXIS_K(); DIR_WAIT_BEFORE(); - const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ()); + const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY( + X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), + I_DIR_READ(), J_DIR_READ(), K_DIR_READ() + ); X_DIR_WRITE(INVERT_X_DIR ^ z_direction); #ifdef Y_DIR_WRITE diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index d2f42b63fc..ca88d6b6b1 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -276,8 +276,8 @@ class Stepper { static block_t* current_block; // A pointer to the block currently being traced - static uint8_t last_direction_bits, // The next stepping-bits to be output - axis_did_move; // Last Movement in the given direction is not null, as computed when the last movement was fetched from planner + static axis_bits_t last_direction_bits, // The next stepping-bits to be output + axis_did_move; // Last Movement in the given direction is not null, as computed when the last movement was fetched from planner static bool abort_current_block; // Signals to the stepper that current block should be aborted @@ -523,7 +523,7 @@ class Stepper { static void set_directions(); // Set direction bits and update all stepper DIR states - static void set_directions(const uint8_t bits) { + static void set_directions(const axis_bits_t bits) { last_direction_bits = bits; set_directions(); } diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 312a09f716..3e3ebd411f 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -896,21 +896,21 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif #if LINEAR_AXES >= 4 - #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } + #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); } #else #define ENABLE_AXIS_I() NOOP #define DISABLE_AXIS_I() NOOP #endif #if LINEAR_AXES >= 5 - #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } + #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); } #else #define ENABLE_AXIS_J() NOOP #define DISABLE_AXIS_J() NOOP #endif #if LINEAR_AXES >= 6 - #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } + #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); } #else #define ENABLE_AXIS_K() NOOP diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index fd63027974..e8ecbf1c76 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -164,6 +164,15 @@ enum StealthIndex : uint8_t { #ifndef TMC_Z4_BAUD_RATE #define TMC_Z4_BAUD_RATE TMC_BAUD_RATE #endif +#ifndef TMC_I_BAUD_RATE + #define TMC_I_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_J_BAUD_RATE + #define TMC_J_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_K_BAUD_RATE + #define TMC_K_BAUD_RATE TMC_BAUD_RATE +#endif #ifndef TMC_E0_BAUD_RATE #define TMC_E0_BAUD_RATE TMC_BAUD_RATE #endif @@ -834,12 +843,8 @@ void restore_trinamic_drivers() { void reset_trinamic_drivers() { static constexpr bool stealthchop_by_axis[] = LOGICAL_AXIS_ARRAY( ENABLED(STEALTHCHOP_E), - ENABLED(STEALTHCHOP_XY), - ENABLED(STEALTHCHOP_XY), - ENABLED(STEALTHCHOP_Z), - ENABLED(STEALTHCHOP_I), - ENABLED(STEALTHCHOP_J), - ENABLED(STEALTHCHOP_K) + ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), + ENABLED(STEALTHCHOP_I), ENABLED(STEALTHCHOP_J), ENABLED(STEALTHCHOP_K) ); #if AXIS_IS_TMC(X) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 72313cf3e6..4860e2d800 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -464,11 +464,19 @@ #ifdef I_STOP_PIN #if I_HOME_TO_MIN #define I_MIN_PIN I_STOP_PIN - #define I_MAX_PIN -1 + #ifndef I_MAX_PIN + #define I_MAX_PIN -1 + #endif #else - #define I_MIN_PIN -1 #define I_MAX_PIN I_STOP_PIN + #ifndef I_MIN_PIN + #define I_MIN_PIN -1 + #endif #endif + #elif I_HOME_TO_MIN + #define I_STOP_PIN I_MIN_PIN + #else + #define I_STOP_PIN I_MAX_PIN #endif #else #undef I_MIN_PIN @@ -479,11 +487,19 @@ #ifdef J_STOP_PIN #if J_HOME_TO_MIN #define J_MIN_PIN J_STOP_PIN - #define J_MAX_PIN -1 + #ifndef J_MAX_PIN + #define J_MAX_PIN -1 + #endif #else - #define J_MIN_PIN -1 #define J_MAX_PIN J_STOP_PIN + #ifndef J_MIN_PIN + #define J_MIN_PIN -1 + #endif #endif + #elif J_HOME_TO_MIN + #define J_STOP_PIN J_MIN_PIN + #else + #define J_STOP_PIN J_MAX_PIN #endif #else #undef J_MIN_PIN @@ -494,11 +510,19 @@ #ifdef K_STOP_PIN #if K_HOME_TO_MIN #define K_MIN_PIN K_STOP_PIN - #define K_MAX_PIN -1 + #ifndef K_MAX_PIN + #define K_MAX_PIN -1 + #endif #else - #define K_MIN_PIN -1 #define K_MAX_PIN K_STOP_PIN + #ifndef K_MIN_PIN + #define K_MIN_PIN -1 + #endif #endif + #elif K_HOME_TO_MIN + #define K_STOP_PIN K_MIN_PIN + #else + #define K_STOP_PIN K_MAX_PIN #endif #else #undef K_MIN_PIN From 35ad3b0d3b1a8bbf6b220f30f63fd0e32be8fe34 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 23 Sep 2021 11:09:43 -0500 Subject: [PATCH 0720/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20reset=5Fhotend?= =?UTF-8?q?=5Foffsets?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 397c2ac1d0..8ad7455aaf 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -124,7 +124,7 @@ xyze_pos_t destination; // {0} "Offsets for the first hotend must be 0.0." ); // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ] - HOTEND_LOOP() LOOP_LINEAR_AXES(a) hotend_offset[e][a] = tmp[a][e]; + HOTEND_LOOP() LOOP_ABC(a) hotend_offset[e][a] = tmp[a][e]; #if ENABLED(DUAL_X_CARRIAGE) hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS); #endif From e85f6225053de257ee6f2652f097d0939d0dbde7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 24 Sep 2021 01:01:22 +0000 Subject: [PATCH 0721/2168] [cron] Bump distribution date (2021-09-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 2284ab23c6..e23ab3a6b1 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-23" +//#define STRING_DISTRIBUTION_DATE "2021-09-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7d0b19c00c..28a545b589 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 "2021-09-23" + #define STRING_DISTRIBUTION_DATE "2021-09-24" #endif /** From 849b86afb68949ec0f67c49401bdf659d3eaac5c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 25 Sep 2021 00:59:33 +0000 Subject: [PATCH 0722/2168] [cron] Bump distribution date (2021-09-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e23ab3a6b1..d34f5ddd5a 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-24" +//#define STRING_DISTRIBUTION_DATE "2021-09-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 28a545b589..affbde748c 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 "2021-09-24" + #define STRING_DISTRIBUTION_DATE "2021-09-25" #endif /** From 86a6b9316ed16f4726096dfdf7495ee75dada7d4 Mon Sep 17 00:00:00 2001 From: Manuel McLure Date: Fri, 24 Sep 2021 19:08:07 -0700 Subject: [PATCH 0723/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M420=20/=20M851?= =?UTF-8?q?=20reports=20(#22829)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to 79c72ed821 --- Marlin/src/gcode/bedlevel/M420.cpp | 2 +- Marlin/src/gcode/probe/M851.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 1110ce7ccf..d76e08dee6 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -251,7 +251,7 @@ void GcodeSuite::M420_report(const bool forReplay/*=true*/) { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) #endif - , " ; Leveling " + , PSTR(" ; Leveling ") ); serialprintln_onoff(planner.leveling_active); } diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index 5518117946..7ec326730f 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -94,7 +94,7 @@ void GcodeSuite::M851_report(const bool forReplay/*=true*/) { PSTR(" M851 X0 Y0 Z") #endif , LINEAR_UNIT(probe.offset.z) - , " ;" + , PSTR(" ;") ); say_units(); } From e1ac3ede0d7bb9d77362040b593904006a26f873 Mon Sep 17 00:00:00 2001 From: Steve Wills Date: Fri, 24 Sep 2021 22:12:43 -0400 Subject: [PATCH 0724/2168] =?UTF-8?q?=F0=9F=90=9B=20Add=20'static'=20to=20?= =?UTF-8?q?fix=20'duplicates'=20(#22826)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index 9d928e7af3..45b54379db 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -64,8 +64,8 @@ #include -uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock; -volatile uint8_t *u8g_outData, *u8g_outClock; +static uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock; +static volatile uint8_t *u8g_outData, *u8g_outClock; static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) { u8g_outData = portOutputRegister(digitalPinToPort(dataPin)); From a7fdaabd54475e5f4dec3afad693b0c623bf7bf6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 02:27:07 -0500 Subject: [PATCH 0725/2168] =?UTF-8?q?=F0=9F=8E=A8=20Updated=20string=20mac?= =?UTF-8?q?ros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/multi_language.h | 2 +- Marlin/src/core/types.h | 6 +- Marlin/src/lcd/e3v2/common/dwin_api.h | 11 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 6 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 238 +++++++++--------- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 2 +- Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 1 - Marlin/src/lcd/e3v2/enhanced/dwinui.h | 24 +- Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h | 2 + Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 2 +- .../archim2-flash/flash_storage.cpp | 4 +- .../archim2-flash/flash_storage.h | 2 +- .../bioprinter/printing_dialog_box.cpp | 2 +- .../bioprinter/printing_dialog_box.h | 2 +- .../bioprinter/status_screen.cpp | 2 +- .../bioprinter/status_screen.h | 2 +- .../cocoa_press/preheat_screen.cpp | 2 +- .../cocoa_press/preheat_screen.h | 2 +- .../cocoa_press/status_screen.cpp | 2 +- .../cocoa_press/status_screen.h | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/compat.h | 2 +- .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 2 +- .../ftdi_eve_lib/basic/commands.cpp | 10 +- .../ftdi_eve_lib/basic/commands.h | 10 +- .../ftdi_eve_lib/extended/adjuster_widget.cpp | 4 +- .../ftdi_eve_lib/extended/adjuster_widget.h | 4 +- .../ftdi_eve_lib/extended/command_processor.h | 2 +- .../ftdi_eve_lib/extended/text_box.cpp | 2 +- .../ftdi_eve_lib/extended/text_box.h | 2 +- .../ftdi_eve_lib/extended/text_ellipsis.cpp | 2 +- .../ftdi_eve_lib/extended/text_ellipsis.h | 2 +- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 6 +- .../ftdi_eve_lib/extended/unicode/unicode.h | 6 +- .../generic/about_screen.cpp | 2 +- .../generic/alert_dialog_box.cpp | 4 +- .../base_numeric_adjustment_screen.cpp | 30 +-- .../generic/base_numeric_adjustment_screen.h | 24 +- .../generic/bed_mesh_view_screen.h | 2 +- .../generic/dialog_box_base_class.cpp | 4 +- .../generic/filament_runout_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/lock_screen.cpp | 2 +- .../generic/spinner_dialog_box.cpp | 6 +- .../generic/spinner_dialog_box.h | 6 +- .../generic/status_screen.cpp | 2 +- .../ftdi_eve_touch_ui/generic/status_screen.h | 2 +- .../generic/stress_test_screen.cpp | 2 +- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/game/brickout.cpp | 4 +- Marlin/src/lcd/menu/game/snake.cpp | 4 +- Marlin/src/lcd/menu/game/types.h | 2 +- Marlin/src/lcd/menu/menu.h | 2 +- 51 files changed, 237 insertions(+), 234 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 8a85f83dd4..2106f946ac 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -78,7 +78,7 @@ typedef const char Language_Str[]; #define GET_TEXT(MSG) GET_LANG(LCD_LANGUAGE)::MSG #define MAX_LANG_CHARSIZE LANG_CHARSIZE #endif -#define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG) +#define GET_TEXT_F(MSG) FPSTR(GET_TEXT(MSG)) #define GET_LANGUAGE_NAME(INDEX) GET_LANG(LCD_LANGUAGE_##INDEX)::LANGUAGE #define LANG_CHARSIZE GET_TEXT(CHARSIZE) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 372b4b1e66..e11a6cd03e 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -27,7 +27,11 @@ #include "../inc/MarlinConfigPre.h" class __FlashStringHelper; -typedef const __FlashStringHelper *progmem_str; +typedef const __FlashStringHelper* FSTR_P; +#ifndef FPSTR + #define FPSTR(S) (reinterpret_cast(S)) +#endif +#define FTOP(S) (reinterpret_cast(S)) // // Conditional type assignment magic. For example... diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index dd9560a60f..d4715acc41 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -21,10 +21,7 @@ */ #pragma once -#include -#include - -#include "../../../HAL/shared/Marduino.h" +#include "../../../inc/MarlinConfig.h" #ifndef DWIN_WIDTH #define DWIN_WIDTH 272 @@ -74,7 +71,7 @@ inline void DWIN_Text(size_t &i, const char * const string, uint16_t rlimit=0xFF i += len; } -inline void DWIN_Text(size_t &i, const __FlashStringHelper * string, uint16_t rlimit=0xFFFF) { +inline void DWIN_Text(size_t &i, FSTR_P string, uint16_t rlimit=0xFFFF) { if (!string) return; const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, _MIN(rlimit, strlen_P((PGM_P)string))); // cast to PGM_P (const char*) measure with strlen_P. if (len == 0) return; @@ -175,9 +172,9 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // rlimit: For draw less chars than string length use rlimit void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF); -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P title) { // Note that this won't work on AVR, only 32-bit systems! - DWIN_Draw_String(bShow, size, color, bColor, x, y, reinterpret_cast(title)); + DWIN_Draw_String(bShow, size, color, bColor, x, y, FTOP(title)); } // Draw a positive integer diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 05aa9f0ec3..0a52c9b965 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -363,7 +363,7 @@ void Draw_Title(const char * const title) { DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } -void Draw_Title(const __FlashStringHelper * title) { +void Draw_Title(FSTR_P title) { DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } @@ -439,7 +439,7 @@ void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } -void Draw_Menu_LineF(const uint8_t line, const uint8_t icon=0, const __FlashStringHelper *label=nullptr, bool more=false) { +void Draw_Menu_LineF(const uint8_t line, const uint8_t icon=0, FSTR_P label=nullptr, bool more=false) { Draw_Menu_Line(line, icon, (char*)label, more); } @@ -589,7 +589,7 @@ void say_steps_per_mm_en(const uint8_t row) { void DWIN_Draw_Label(const uint8_t row, char *string) { DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(row), string); } -void DWIN_Draw_Label(const uint8_t row, const __FlashStringHelper *title) { +void DWIN_Draw_Label(const uint8_t row, FSTR_P title) { DWIN_Draw_Label(row, (char*)title); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 80348e4418..b1b9dec719 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -3078,31 +3078,31 @@ void Draw_Prepare_Menu() { CurrentMenu = PrepareMenu; SetMenuTitle({133, 1, 28, 13}, {179, 0, 48, 14}, GET_TEXT_F(MSG_PREPARE)); DWINUI::MenuItemsPrepare(13); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); + ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); #endif - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_MOVE_AXIS), onDrawMoveSubMenu, Draw_Move_Menu); - ADDMENUITEM(ICON_LevBed, GET_TEXT(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); - ADDMENUITEM(ICON_CloseMotor, GET_TEXT(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); - ADDMENUITEM(ICON_Homing, GET_TEXT(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Draw_Move_Menu); + ADDMENUITEM(ICON_LevBed, GET_TEXT_F(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); + ADDMENUITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); + ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); #if ENABLED(MESH_BED_LEVELING) - ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); + ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); #endif #if HAS_ZOFFSET_ITEM #if EITHER(HAS_BED_PROBE, BABYSTEPPING) - ADDMENUITEM(ICON_SetZOffset, GET_TEXT(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); + ADDMENUITEM(ICON_SetZOffset, GET_TEXT_F(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); #else - ADDMENUITEM(ICON_SetHome, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); + ADDMENUITEM(ICON_SetHome, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); #endif #endif #if HAS_HOTEND - ADDMENUITEM(ICON_PLAPreheat, GET_TEXT(MSG_PREHEAT_1), onDrawPreheat1, SetPreheat0); + ADDMENUITEM(ICON_PLAPreheat, GET_TEXT_F(MSG_PREHEAT_1), onDrawPreheat1, SetPreheat0); ADDMENUITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, SetPreheat1); - ADDMENUITEM(ICON_CustomPreheat, GET_TEXT(MSG_PREHEAT_CUSTOM), onDrawMenuItem, SetPreheat2); + ADDMENUITEM(ICON_CustomPreheat, GET_TEXT_F(MSG_PREHEAT_CUSTOM), onDrawMenuItem, SetPreheat2); #endif #if HAS_PREHEAT - ADDMENUITEM(ICON_Cool, GET_TEXT(MSG_COOLDOWN), onDrawCooldown, SetCoolDown); + ADDMENUITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, SetCoolDown); #endif ADDMENUITEM(ICON_Language, PSTR("UI Language"), onDrawLanguage, SetLanguage); } @@ -3117,12 +3117,12 @@ void Draw_LevBedCorners_Menu() { CurrentMenu = LevBedMenu; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_FL), onDrawMenuItem, LevBedFL); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_FR), onDrawMenuItem, LevBedFR); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_BR), onDrawMenuItem, LevBedBR); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_BL), onDrawMenuItem, LevBedBL); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_LEVBED_C ), onDrawMenuItem, LevBedC ); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, LevBedFL); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, LevBedFR); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, LevBedBR); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, LevBedBL); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, LevBedC ); } CurrentMenu->draw(); } @@ -3134,17 +3134,17 @@ void Draw_Control_Menu() { CurrentMenu = ControlMenu; SetMenuTitle({103, 1, 28, 14}, {128, 2, 49, 11}, GET_TEXT_F(MSG_CONTROL)); DWINUI::MenuItemsPrepare(9); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); - ADDMENUITEM(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); - ADDMENUITEM(ICON_Motion, GET_TEXT(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + ADDMENUITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); + ADDMENUITEM(ICON_Motion, GET_TEXT_F(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); - ADDMENUITEM(ICON_ReadEEPROM, GET_TEXT(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); - ADDMENUITEM(ICON_ResumeEEPROM, GET_TEXT(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + ADDMENUITEM(ICON_ReadEEPROM, GET_TEXT_F(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); + ADDMENUITEM(ICON_ResumeEEPROM, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); #endif - ADDMENUITEM(ICON_Reboot, GET_TEXT(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); - ADDMENUITEM(ICON_AdvSet, GET_TEXT(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_Info, GET_TEXT(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_InfoMenu); + ADDMENUITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); + ADDMENUITEM(ICON_AdvSet, GET_TEXT_F(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_InfoMenu); } CurrentMenu->draw(); } @@ -3156,12 +3156,12 @@ void Draw_AdvancedSettings_Menu() { CurrentMenu = AdvancedSettings; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG DWINUI::MenuItemsPrepare(11); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOME_OFFSET - ADDMENUITEM(ICON_HomeOffset, GET_TEXT(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); + ADDMENUITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); #endif #if HAS_BED_PROBE - ADDMENUITEM(ICON_ProbeSet, GET_TEXT(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); + ADDMENUITEM(ICON_ProbeSet, GET_TEXT_F(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); #endif #if HAS_HOTEND ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu); @@ -3170,13 +3170,13 @@ void Draw_AdvancedSettings_Menu() { ADDMENUITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu); #endif #if HAS_FILAMENT_SENSOR - ADDMENUITEM(ICON_FilSet, GET_TEXT(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); + ADDMENUITEM(ICON_FilSet, GET_TEXT_F(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); #endif #if ENABLED(POWER_LOSS_RECOVERY) - ADDMENUITEM(ICON_Pwrlossr, F("Power-loss recovery"), onDrawPwrLossR, SetPwrLossr); + ADDMENUITEM(ICON_Pwrlossr, GET_TEXT_F(MSG_OUTAGE_RECOVERY), onDrawPwrLossR, SetPwrLossr); #endif #if HAS_LCD_BRIGHTNESS - ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); + ADDMENUITEM_P(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif ADDMENUITEM(ICON_Scolor, F("Select Colors"), onDrawSubMenu, Draw_SelectColors_Menu); #if ENABLED(SOUND_MENU_ITEM) @@ -3194,12 +3194,12 @@ void Draw_Move_Menu() { CurrentMenu = MoveMenu; SetMenuTitle({192, 1, 42, 14}, {231, 2, 35, 11}, GET_TEXT_F(MSG_MOVE_AXIS)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM_P(ICON_MoveX, GET_TEXT(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); - ADDMENUITEM_P(ICON_MoveY, GET_TEXT(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); - ADDMENUITEM_P(ICON_MoveZ, GET_TEXT(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM_P(ICON_MoveX, GET_TEXT_F(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); + ADDMENUITEM_P(ICON_MoveY, GET_TEXT_F(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); + ADDMENUITEM_P(ICON_MoveZ, GET_TEXT_F(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); #if HAS_HOTEND - ADDMENUITEM_P(ICON_Extruder, GET_TEXT(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); + ADDMENUITEM_P(ICON_Extruder, GET_TEXT_F(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); #endif } CurrentMenu->draw(); @@ -3214,10 +3214,10 @@ void Draw_Move_Menu() { CurrentMenu = HomeOffMenu; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG DWINUI::MenuItemsPrepare(4); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM_P(ICON_HomeOffsetX, GET_TEXT(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); - ADDMENUITEM_P(ICON_HomeOffsetY, GET_TEXT(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); - ADDMENUITEM_P(ICON_HomeOffsetZ, GET_TEXT(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM_P(ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); + ADDMENUITEM_P(ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); + ADDMENUITEM_P(ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); } CurrentMenu->draw(); } @@ -3231,11 +3231,11 @@ void Draw_Move_Menu() { CurrentMenu = ProbeSetMenu; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); - ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); - ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); - ADDMENUITEM(ICON_ProbeTest, GET_TEXT(MSG_M48_TEST), onDrawMenuItem, ProbeTest); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); + ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); + ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); + ADDMENUITEM(ICON_ProbeTest, GET_TEXT_F(MSG_M48_TEST), onDrawMenuItem, ProbeTest); } CurrentMenu->draw(); } @@ -3249,9 +3249,9 @@ void Draw_Move_Menu() { CurrentMenu = FilSetMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); #if HAS_FILAMENT_SENSOR - ADDMENUITEM(ICON_Runout, GET_TEXT(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); + ADDMENUITEM(ICON_Runout, GET_TEXT_F(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); #endif #if HAS_FILAMENT_RUNOUT_DISTANCE ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); @@ -3260,8 +3260,8 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM_P(ICON_FilLoad, GET_TEXT(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); - ADDMENUITEM_P(ICON_FilUnload, GET_TEXT(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); + ADDMENUITEM_P(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); + ADDMENUITEM_P(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); #endif } CurrentMenu->draw(); @@ -3275,8 +3275,8 @@ void Draw_SelectColors_Menu() { CurrentMenu = SelectColorMenu; SetMenuTitle({0}, {0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG DWINUI::MenuItemsPrepare(20); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_StockConfiguration, GET_TEXT(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); ADDMENUITEM_P(0, "Screen Background", onDrawSelColorItem, SelColor, &HMI_data.Background_Color); ADDMENUITEM_P(0, "Cursor", onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); ADDMENUITEM_P(0, "Title Background", onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); @@ -3306,8 +3306,8 @@ void Draw_GetColor_Menu() { CurrentMenu = GetColorMenu; SetMenuTitle({0}, {0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); - ADDMENUITEM(ICON_Cancel, GET_TEXT(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); + ADDMENUITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); ADDMENUITEM(0, "Red", onDrawGetColorItem, SetRGBColor); ADDMENUITEM(1, "Green", onDrawGetColorItem, SetRGBColor); ADDMENUITEM(2, "Blue", onDrawGetColorItem, SetRGBColor); @@ -3323,23 +3323,23 @@ void Draw_Tune_Menu() { CurrentMenu = TuneMenu; SetMenuTitle({73, 2, 28, 12}, {94, 2, 33, 11}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG DWINUI::MenuItemsPrepare(10); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); - ADDMENUITEM_P(ICON_Speed, GET_TEXT(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); + ADDMENUITEM_P(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); #if HAS_HOTEND - HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif - ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + ADDMENUITEM_P(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #endif ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); #if HAS_LCD_BRIGHTNESS @@ -3356,14 +3356,14 @@ void Draw_Motion_Menu() { CurrentMenu = MotionMenu; SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - ADDMENUITEM(ICON_MaxSpeed, GET_TEXT(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); - ADDMENUITEM(ICON_MaxAccelerated, GET_TEXT(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + ADDMENUITEM(ICON_MaxSpeed, GET_TEXT_F(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); + ADDMENUITEM(ICON_MaxAccelerated, GET_TEXT_F(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); #if HAS_CLASSIC_JERK - ADDMENUITEM(ICON_MaxJerk, GET_TEXT(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); + ADDMENUITEM(ICON_MaxJerk, GET_TEXT_F(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); #endif - ADDMENUITEM(ICON_Step, GET_TEXT(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); - ADDMENUITEM_P(ICON_Flow, GET_TEXT(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + ADDMENUITEM(ICON_Step, GET_TEXT_F(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); + ADDMENUITEM_P(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } CurrentMenu->draw(); } @@ -3376,12 +3376,12 @@ void Draw_Motion_Menu() { CurrentMenu = FilamentMenu; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Park, GET_TEXT(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); - ADDMENUITEM(ICON_FilMan, GET_TEXT(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Park, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); + ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - ADDMENUITEM(ICON_FilUnload, GET_TEXT(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); - ADDMENUITEM(ICON_FilLoad, GET_TEXT(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); + ADDMENUITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); + ADDMENUITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); #endif } CurrentMenu->draw(); @@ -3396,11 +3396,11 @@ void Draw_Motion_Menu() { CurrentMenu = ManualMesh; SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_ManualMesh, GET_TEXT(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); - MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); - ADDMENUITEM(ICON_Axis, GET_TEXT(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); - ADDMENUITEM(ICON_MeshSave, GET_TEXT(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); + MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); + ADDMENUITEM(ICON_MeshSave, GET_TEXT_F(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); } CurrentMenu->draw(); } @@ -3414,18 +3414,18 @@ void Draw_Motion_Menu() { CurrentMenu = PreheatMenu; SetMenuTitle(cn, en, text); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); #if HAS_HOTEND - ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); + ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); #endif #if HAS_HEATED_BED - ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); + ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); #endif #if HAS_FAN - ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); + ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3461,15 +3461,15 @@ void Draw_Temperature_Menu() { CurrentMenu = TemperatureMenu; SetMenuTitle({236, 2, 28, 12}, {56, 15, 85, 14}, GET_TEXT_F(MSG_TEMPERATURE)); DWINUI::MenuItemsPrepare(7); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOTEND - HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif #if HAS_HOTEND ADDMENUITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); @@ -3489,12 +3489,12 @@ void Draw_MaxSpeed_Menu() { CurrentMenu = MaxSpeedMenu; SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MAXSPEED)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT_F(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT_F(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT_F(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #endif } CurrentMenu->draw(); @@ -3507,12 +3507,12 @@ void Draw_MaxAccel_Menu() { CurrentMenu = MaxAccelMenu; SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_ACCELERATION)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - ADDMENUITEM_P(ICON_MaxAccY, GET_TEXT(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxAccZ, GET_TEXT(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT_F(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + ADDMENUITEM_P(ICON_MaxAccY, GET_TEXT_F(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxAccZ, GET_TEXT_F(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT_F(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3526,12 +3526,12 @@ void Draw_MaxAccel_Menu() { CurrentMenu = MaxJerkMenu; SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_JERK)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedJerkY, GET_TEXT(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedJerkZ, GET_TEXT(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT_F(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedJerkY, GET_TEXT_F(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedJerkZ, GET_TEXT_F(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT_F(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3545,12 +3545,12 @@ void Draw_Steps_Menu() { CurrentMenu = StepsMenu; SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_STEPS_PER_MM)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_StepX, GET_TEXT(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); - ADDMENUITEM_P(ICON_StepY, GET_TEXT(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); - ADDMENUITEM_P(ICON_StepZ, GET_TEXT(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + ADDMENUITEM_P(ICON_StepX, GET_TEXT_F(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); + ADDMENUITEM_P(ICON_StepY, GET_TEXT_F(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); + ADDMENUITEM_P(ICON_StepZ, GET_TEXT_F(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_StepE, GET_TEXT(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); + ADDMENUITEM_P(ICON_StepE, GET_TEXT_F(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3564,15 +3564,15 @@ void Draw_Steps_Menu() { CurrentMenu = HotendPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Hotend PID Settings")); DWINUI::MenuItemsPrepare(8); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); - ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); - ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + ADDMENUITEM_P(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); + ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3587,15 +3587,15 @@ void Draw_Steps_Menu() { CurrentMenu = BedPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Bed PID Settings")); DWINUI::MenuItemsPrepare(8); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); - ADDMENUITEM_P(ICON_Temperature, GET_TEXT(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); - ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + ADDMENUITEM_P(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); + ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3610,10 +3610,10 @@ void Draw_Steps_Menu() { CurrentMenu = ZOffsetWizMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_PROBE_WIZARD)); DWINUI::MenuItemsPrepare(4); - ADDMENUITEM(ICON_Back, GET_TEXT(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Homing, GET_TEXT(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); ADDMENUITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } CurrentMenu->draw(); if (!axis_is_trusted(Z_AXIS)) ui.set_status_P(PSTR("WARNING: Z position is unknow, move Z to home")); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h index f33879bb7e..c49f23af45 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -37,7 +37,7 @@ // str: multi-bit data void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, char *string); -inline void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, const __FlashStringHelper *title) { +inline void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, FSTR_P title) { DWIN_Draw_QR(QR_Pixel, x, y, (char *)title); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index 5c2cb3d1c1..6c46eb31f1 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -32,7 +32,6 @@ #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) #include "../../../inc/MarlinConfig.h" -#include "../../../core/macros.h" #include "dwin_lcd.h" #include "dwinui.h" diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index dd2fc74291..ce56c98e5b 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -124,9 +124,9 @@ public: rect_t frame = {0}; void draw(); void SetCaption(const char * const title); - inline void SetCaption(const __FlashStringHelper * title) { SetCaption((char *)title); } + inline void SetCaption(FSTR_P title) { SetCaption((char *)title); } void ShowCaption(const char * const title); - inline void ShowCaption(const __FlashStringHelper * title) { ShowCaption((char *)title); } + inline void ShowCaption(FSTR_P title) { ShowCaption((char *)title); } void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); void SetFrame(uint16_t x, uint16_t y, uint16_t w, uint16_t h); void FrameCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); @@ -146,7 +146,7 @@ public: void (*onClick)() = nullptr; MenuItemClass() {}; MenuItemClass(uint8_t cicon, const char * const text=nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); - MenuItemClass(uint8_t cicon, const __FlashStringHelper * text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) : MenuItemClass(cicon, (char*)text, ondraw, onclick){} + MenuItemClass(uint8_t cicon, FSTR_P text = nullptr, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr) : MenuItemClass(cicon, FTOP(text), ondraw, onclick){} MenuItemClass(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, void (*ondraw)(MenuItemClass* menuitem, int8_t line)=nullptr, void (*onclick)()=nullptr); void SetFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); virtual ~MenuItemClass(){}; @@ -158,7 +158,7 @@ public: void *value = nullptr; using MenuItemClass::MenuItemClass; MenuItemPtrClass(uint8_t cicon, const char * const text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val); - MenuItemPtrClass(uint8_t cicon, const __FlashStringHelper * text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemPtrClass(cicon, (char*)text, ondraw, onclick, val){} + MenuItemPtrClass(uint8_t cicon, FSTR_P text, void (*ondraw)(MenuItemClass* menuitem, int8_t line), void (*onclick)(), void* val) : MenuItemPtrClass(cicon, FTOP(text), ondraw, onclick, val){} }; class MenuClass { @@ -351,25 +351,25 @@ namespace DWINUI { inline void Draw_String(uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(false, font, textcolor, backcolor, x, y, string); } - inline void Draw_String(uint16_t x, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_String(uint16_t x, uint16_t y, FSTR_P title) { DWIN_Draw_String(false, font, textcolor, backcolor, x, y, (char *)title); } inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(false, font, color, backcolor, x, y, string); } - inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, FSTR_P title) { DWIN_Draw_String(false, font, color, backcolor, x, y, (char *)title); } inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(true, font, color, bgcolor, x, y, string); } - inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P title) { DWIN_Draw_String(true, font, color, bgcolor, x, y, (char *)title); } inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(true, size, color, bgcolor, x, y, string); } - inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P title) { DWIN_Draw_String(true, size, color, bgcolor, x, y, (char *)title); } @@ -381,7 +381,7 @@ namespace DWINUI { // y: Upper coordinate of the string // *string: The string void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string); - inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, FSTR_P title) { Draw_CenteredString(bShow, size, color, bColor, y, (char *)title); } inline void Draw_CenteredString(uint16_t color, uint16_t bcolor, uint16_t y, const char * const string) { @@ -390,19 +390,19 @@ namespace DWINUI { inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, const char * const string) { Draw_CenteredString(false, size, color, backcolor, y, string); } - inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, FSTR_P title) { Draw_CenteredString(false, size, color, backcolor, y, (char *)title); } inline void Draw_CenteredString(uint16_t color, uint16_t y, const char * const string) { Draw_CenteredString(false, font, color, backcolor, y, string); } - inline void Draw_CenteredString(uint16_t color, uint16_t y, const __FlashStringHelper *title) { + inline void Draw_CenteredString(uint16_t color, uint16_t y, FSTR_P title) { Draw_CenteredString(false, font, color, backcolor, y, (char *)title); } inline void Draw_CenteredString(uint16_t y, const char * const string) { Draw_CenteredString(false, font, textcolor, backcolor, y, string); } - inline void Draw_CenteredString(uint16_t y, const __FlashStringHelper *title) { + inline void Draw_CenteredString(uint16_t y, FSTR_P title) { Draw_CenteredString(false, font, textcolor, backcolor, y, (char *)title); } diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h index 753dcf47c2..65d9394a85 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h @@ -26,6 +26,8 @@ * @brief DWIN screen control functions ********************************************************************************/ +#include "../../../inc/MarlinConfigPre.h" + #if ENABLED(DWIN_MARLINUI_LANDSCAPE) #define DWIN_WIDTH 480 #define DWIN_HEIGHT 272 diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 9cdea13319..30af387bdc 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -65,7 +65,7 @@ class DWIN_String { static void set(uint8_t *string) { set(); add(string); } static void set(wchar_t character) { set(); add(character); } static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); } - static inline void set(const __FlashStringHelper *fstring) { set((uint8_t *)fstring); } + static inline void set(FSTR_P fstring) { set((uint8_t *)fstring); } static inline void set(const char *string) { set((uint8_t *)string); } static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } static inline void add(const char *string) { add((uint8_t *)string); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index ebe99a37d2..8b0c0f877c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -416,7 +416,7 @@ bool UIFlashStorage::is_present = false; /* Writes a media file from the SD card/USB flash drive into a slot on the SPI Flash. Media * files must be written sequentially following by a chip erase and it is not possible to * overwrite files. */ - UIFlashStorage::error_t UIFlashStorage::write_media_file(progmem_str filename, uint8_t slot) { + UIFlashStorage::error_t UIFlashStorage::write_media_file(FSTR_P filename, uint8_t slot) { #if ENABLED(SDSUPPORT) uint32_t addr; uint8_t buff[write_page_size]; @@ -543,7 +543,7 @@ bool UIFlashStorage::is_present = false; void UIFlashStorage::write_config_data(const void *, size_t) {} bool UIFlashStorage::verify_config_data(const void *, size_t) {return false;} bool UIFlashStorage::read_config_data(void *, size_t ) {return false;} - UIFlashStorage::error_t UIFlashStorage::write_media_file(progmem_str, uint8_t) {return FILE_NOT_FOUND;} + UIFlashStorage::error_t UIFlashStorage::write_media_file(FSTR_P, uint8_t) {return FILE_NOT_FOUND;} void UIFlashStorage::format_flash() {} bool UIFlashStorage::BootMediaReader::isAvailable(uint32_t) {return false;} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h index eef8cf8677..0ca269a628 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.h @@ -88,7 +88,7 @@ class UIFlashStorage : private SPIFlash { static void write_config_data (const void *data, size_t size); static bool verify_config_data (const void *data, size_t size); static bool read_config_data (void *data, size_t size); - static error_t write_media_file (progmem_str filename, uint8_t slot = 0); + static error_t write_media_file (FSTR_P filename, uint8_t slot = 0); class BootMediaReader; }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index 86c700f235..f0c0a59d36 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -105,7 +105,7 @@ bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) { return true; } -void BioPrintingDialogBox::setStatusMessage(progmem_str message) { +void BioPrintingDialogBox::setStatusMessage(FSTR_P message) { char buff[strlen_P((const char*)message)+1]; strcpy_P(buff, (const char*) message); setStatusMessage(buff); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h index aebbd16128..b55038bef2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h @@ -37,7 +37,7 @@ class BioPrintingDialogBox : public BaseScreen, public CachedScreen static void unlockMotors(); static void setStatusMessage(const char *); - static void setStatusMessage(progmem_str); + static void setStatusMessage(FSTR_P); static void onRedraw(draw_mode_t); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index 300878670e..c4e9d971f6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -81,7 +81,7 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { } } -void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, progmem_str label, float value, int16_t x, int16_t y, int16_t w, int16_t h) { +void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, FSTR_P label, float value, int16_t x, int16_t y, int16_t w, int16_t h) { #define SUB_COLS 9 #define SUB_ROWS 2 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h index 9b8e2620dc..87628c4cab 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h @@ -35,7 +35,7 @@ class PreheatTimerScreen : public BaseScreen, public CachedScreen static void unlockMotors(); static void setStatusMessage(const char *); - static void setStatusMessage(progmem_str); + static void setStatusMessage(FSTR_P); static void onRedraw(draw_mode_t); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h index dd25af1e74..3b63b0fd5b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h @@ -49,5 +49,5 @@ #endif class __FlashStringHelper; -typedef const __FlashStringHelper *progmem_str; +typedef const __FlashStringHelper *FSTR_P; extern const char G28_STR[]; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index c8e5721006..59833b06a0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -71,7 +71,7 @@ namespace ExtUI { } void onStatusChanged(const char *lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } - void onStatusChanged(progmem_str lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } + void onStatusChanged(FSTR_P lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } void onPrintTimerStarted() { InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_STARTED); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 40cddce7fd..8e788421ad 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -66,7 +66,7 @@ uint16_t CLCD::FontMetrics::get_text_width(const char *str, size_t n) const { return width; } -uint16_t CLCD::FontMetrics::get_text_width(progmem_str str, size_t n) const { +uint16_t CLCD::FontMetrics::get_text_width(FSTR_P str, size_t n) const { uint16_t width = 0; const uint8_t *p = (const uint8_t *) str; for (;;) { @@ -162,7 +162,7 @@ void CLCD::mem_write_bulk(uint32_t reg_address, const void *data, uint16_t len, } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM -void CLCD::mem_write_bulk(uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding) { +void CLCD::mem_write_bulk(uint32_t reg_address, FSTR_P str, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(str, len, padding); @@ -178,7 +178,7 @@ void CLCD::mem_write_pgm(uint32_t reg_address, const void *data, uint16_t len, u } // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM, reversing bytes (suitable for loading XBM images) -void CLCD::mem_write_xbm(uint32_t reg_address, progmem_str data, uint16_t len, uint8_t padding) { +void CLCD::mem_write_xbm(uint32_t reg_address, FSTR_P data, uint16_t len, uint8_t padding) { spi_ftdi_select(); spi_write_addr(reg_address); spi_write_bulk(data, len, padding); @@ -1048,7 +1048,7 @@ template bool CLCD::CommandFifo::write(T data, uint16_t len) { #endif // ... FTDI_API_LEVEL != 800 template bool CLCD::CommandFifo::write(const void*, uint16_t); -template bool CLCD::CommandFifo::write(progmem_str, uint16_t); +template bool CLCD::CommandFifo::write(FSTR_P, uint16_t); // CO_PROCESSOR COMMANDS @@ -1071,7 +1071,7 @@ void CLCD::CommandFifo::str(const char * data) { write(data, strlen(data)+1); } -void CLCD::CommandFifo::str(progmem_str data) { +void CLCD::CommandFifo::str(FSTR_P data) { write(data, strlen_P((const char*)data)+1); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index 9fc5195fd4..2e2657a83e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h @@ -93,7 +93,7 @@ #pragma once -typedef const __FlashStringHelper *progmem_str; +typedef const __FlashStringHelper *FSTR_P; class UIStorage; @@ -118,8 +118,8 @@ class CLCD { static void mem_write_fill (uint32_t reg_address, uint8_t w_data, uint16_t len); static void mem_write_bulk (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding = 0); static void mem_write_pgm (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding = 0); - static void mem_write_bulk (uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding = 0); - static void mem_write_xbm (uint32_t reg_address, progmem_str str, uint16_t len, uint8_t padding = 0); + static void mem_write_bulk (uint32_t reg_address, FSTR_P str, uint16_t len, uint8_t padding = 0); + static void mem_write_xbm (uint32_t reg_address, FSTR_P str, uint16_t len, uint8_t padding = 0); public: class CommandFifo; @@ -168,7 +168,7 @@ class CLCD::FontMetrics { // Returns width of string, up to a maximum of n characters. uint16_t get_text_width(const char *str, size_t n = SIZE_MAX) const; - uint16_t get_text_width(progmem_str str, size_t n = SIZE_MAX) const; + uint16_t get_text_width(FSTR_P str, size_t n = SIZE_MAX) const; }; /******************* FT800/810 Graphic Commands *********************************/ @@ -250,7 +250,7 @@ class CLCD::CommandFifo { // Sends the string portion of text, button, toggle and keys. void str (const char * data, size_t maxlen); void str (const char * data); - void str (progmem_str data); + void str (FSTR_P data); void memzero (uint32_t ptr, uint32_t size); void memset (uint32_t ptr, uint32_t value, uint32_t size); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp index 3ef71f573f..470d3806ee 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.cpp @@ -30,7 +30,7 @@ #define DEC_POS SUB_POS(8,1), SUB_SIZE(2,1) namespace FTDI { - void draw_adjuster_value(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, float value, progmem_str units, int8_t width, uint8_t precision) { + void draw_adjuster_value(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, float value, FSTR_P units, int8_t width, uint8_t precision) { char str[width + precision + 10 + (units ? strlen_P((const char*) units) : 0)]; if (isnan(value)) strcpy_P(str, PSTR("-")); @@ -45,7 +45,7 @@ namespace FTDI { cmd.tag(0).text(VAL_POS, str); } - void draw_adjuster(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t tag, float value, progmem_str units, int8_t width, uint8_t precision, draw_mode_t what) { + void draw_adjuster(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t tag, float value, FSTR_P units, int8_t width, uint8_t precision, draw_mode_t what) { if (what & BACKGROUND) cmd.tag(0).button(VAL_POS, F(""), FTDI::OPT_FLAT); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h index 71f7398694..fa5f8e46e6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/adjuster_widget.h @@ -25,7 +25,7 @@ namespace FTDI { void draw_adjuster_value( CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, - float value, progmem_str units = nullptr, + float value, FSTR_P units = nullptr, int8_t width = 5, uint8_t precision = 1 ); @@ -33,7 +33,7 @@ namespace FTDI { CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, uint8_t tag, - float value, progmem_str units = nullptr, + float value, FSTR_P units = nullptr, int8_t width = 5, uint8_t precision = 1, draw_mode_t what = BOTH ); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 7504a1387d..24e93982c2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -241,7 +241,7 @@ class CommandProcessor : public CLCD::CommandFifo { return *this; } - CommandProcessor& toggle2(int16_t x, int16_t y, int16_t w, int16_t h, progmem_str no, progmem_str yes, bool state, uint16_t options = FTDI::OPT_3D) { + CommandProcessor& toggle2(int16_t x, int16_t y, int16_t w, int16_t h, FSTR_P no, FSTR_P yes, bool state, uint16_t options = FTDI::OPT_3D) { char text[strlen_P((const char *)no) + strlen_P((const char *)yes) + 2]; strcpy_P(text, (const char *)no); strcat(text, "\xFF"); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 342b1e4d2b..b4d8156b39 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -135,7 +135,7 @@ namespace FTDI { } } - void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, progmem_str pstr, uint16_t options, uint8_t font) { + void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P pstr, uint16_t options, uint8_t font) { char str[strlen_P((const char*)pstr) + 1]; strcpy_P(str, (const char*)pstr); draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h index 3b14b020c0..cc702344ba 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h @@ -27,6 +27,6 @@ namespace FTDI { constexpr uint16_t OPT_BOTTOMY = 0x1000; // Non-standard - void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); + void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P str, uint16_t options = 0, uint8_t font = 31); void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index 463d5ad316..698bcdb150 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -80,7 +80,7 @@ namespace FTDI { _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); } - void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, progmem_str pstr, uint16_t options, uint8_t font) { + void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P pstr, uint16_t options, uint8_t font) { char tmp[strlen_P((const char*)pstr) + 3]; strcpy_P(tmp, (const char*)pstr); _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h index a2d8aa9443..0c6b202ae9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h @@ -26,6 +26,6 @@ * showing ellipsis if it does not fit. */ namespace FTDI { - void draw_text_with_ellipsis(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); + void draw_text_with_ellipsis(class CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P str, uint16_t options = 0, uint8_t font = 31); void draw_text_with_ellipsis(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 15e613cf69..ca25dea3ca 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -44,7 +44,7 @@ return false; } - bool FTDI::has_utf8_chars(progmem_str _str) { + bool FTDI::has_utf8_chars(FSTR_P _str) { const char *str = (const char *) _str; for (;;) { const char c = pgm_read_byte(str++); @@ -191,7 +191,7 @@ return render_utf8_text(nullptr, 0, 0, str, fs, maxlen); } - uint16_t FTDI::get_utf8_text_width(progmem_str pstr, font_size_t fs) { + uint16_t FTDI::get_utf8_text_width(FSTR_P pstr, font_size_t fs) { char str[strlen_P((const char*)pstr) + 1]; strcpy_P(str, (const char*)pstr); return get_utf8_text_width(str, fs); @@ -234,7 +234,7 @@ cmd.cmd(RESTORE_CONTEXT()); } - void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, progmem_str pstr, font_size_t fs, uint16_t options) { + void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, FSTR_P pstr, font_size_t fs, uint16_t options) { char str[strlen_P((const char*)pstr) + 1]; strcpy_P(str, (const char*)pstr); draw_utf8_text(cmd, x, y, (const char*) str, fs, options); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h index 391c8bf6cf..7818957fcc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h @@ -40,7 +40,7 @@ namespace FTDI { /* Returns true if the string has UTF8 string characters */ - bool has_utf8_chars(progmem_str str); + bool has_utf8_chars(FSTR_P str); bool has_utf8_chars(const char *str); /* Returns the next character in a UTF8 string and increments the @@ -66,10 +66,10 @@ namespace FTDI { void load_utf8_bitmaps(CommandProcessor& cmd); uint16_t get_utf8_char_width(utf8_char_t, font_size_t); - uint16_t get_utf8_text_width(progmem_str, font_size_t); + uint16_t get_utf8_text_width(FSTR_P, font_size_t); uint16_t get_utf8_text_width(const char *, font_size_t, size_t maxlen=SIZE_MAX); - void draw_utf8_text(CommandProcessor&, int x, int y, progmem_str, font_size_t, uint16_t options = 0); + void draw_utf8_text(CommandProcessor&, int x, int y, FSTR_P, font_size_t, uint16_t options = 0); void draw_utf8_text(CommandProcessor&, int x, int y, const char *, font_size_t, uint16_t options = 0, size_t maxlen=SIZE_MAX); // Similar to CLCD::FontMetrics, but can be used with UTF8 encoded strings. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index d2aec0baf7..6cb85e47c4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -83,7 +83,7 @@ void AboutScreen::onRedraw(draw_mode_t) { #ifdef TOUCH_UI_VERSION F(TOUCH_UI_VERSION) #else - progmem_str(getFirmwareName_str()) + FPSTR(getFirmwareName_str()) #endif , OPT_CENTER, font_medium); cmd.tag(0); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp index 0d309bff75..86b4eb175a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp @@ -64,8 +64,8 @@ void AlertDialogBox::hide() { } template void AlertDialogBox::show(const char *); -template void AlertDialogBox::show(progmem_str); +template void AlertDialogBox::show(FSTR_P); template void AlertDialogBox::showError(const char *); -template void AlertDialogBox::showError(progmem_str); +template void AlertDialogBox::showError(FSTR_P); #endif // FTDI_ALERT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index d0ba74721c..4415ed50fc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -109,7 +109,7 @@ void BaseNumericAdjustmentScreen::widgets_t::_button_style(CommandProcessor &cmd * Speed optimization for drawing buttons. Draw all unpressed buttons in the * background layer and draw only the pressed button in the foreground layer. */ -void BaseNumericAdjustmentScreen::widgets_t::_button(CommandProcessor &cmd, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, progmem_str text, bool enabled, bool highlight) { +void BaseNumericAdjustmentScreen::widgets_t::_button(CommandProcessor &cmd, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, FSTR_P text, bool enabled, bool highlight) { if (_what & BACKGROUND) enabled = true; if ((_what & BACKGROUND) || buttonIsPressed(tag) || highlight || !enabled) { _button_style(cmd, (!enabled) ? BTN_DISABLED : (highlight ? BTN_ACTION : BTN_NORMAL)); @@ -125,7 +125,7 @@ BaseNumericAdjustmentScreen::widgets_t &BaseNumericAdjustmentScreen::widgets_t:: return *this; } -void BaseNumericAdjustmentScreen::widgets_t::heading(progmem_str label) { +void BaseNumericAdjustmentScreen::widgets_t::heading(FSTR_P label) { if (_what & BACKGROUND) { CommandProcessor cmd; _button_style(cmd, TEXT_LABEL); @@ -176,13 +176,13 @@ void BaseNumericAdjustmentScreen::widgets_t::_draw_increment_btn(CommandProcesso switch (pos) { #if ENABLED(TOUCH_UI_PORTRAIT) - case 0: _button(cmd, tag, BTN_POS(5,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; - case 1: _button(cmd, tag, BTN_POS(7,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; - case 2: _button(cmd, tag, BTN_POS(9,_line), BTN_SIZE(2,1), progmem_str(label), true, highlight); break; + case 0: _button(cmd, tag, BTN_POS(5,_line), BTN_SIZE(2,1), FPSTR(label), true, highlight); break; + case 1: _button(cmd, tag, BTN_POS(7,_line), BTN_SIZE(2,1), FPSTR(label), true, highlight); break; + case 2: _button(cmd, tag, BTN_POS(9,_line), BTN_SIZE(2,1), FPSTR(label), true, highlight); break; #else - case 0: _button(cmd, tag, BTN_POS(15,2), BTN_SIZE(4,1), progmem_str(label), true, highlight); break; - case 1: _button(cmd, tag, BTN_POS(15,3), BTN_SIZE(4,1), progmem_str(label), true, highlight); break; - case 2: _button(cmd, tag, BTN_POS(15,4), BTN_SIZE(4,1), progmem_str(label), true, highlight); break; + case 0: _button(cmd, tag, BTN_POS(15,2), BTN_SIZE(4,1), FPSTR(label), true, highlight); break; + case 1: _button(cmd, tag, BTN_POS(15,3), BTN_SIZE(4,1), FPSTR(label), true, highlight); break; + case 2: _button(cmd, tag, BTN_POS(15,4), BTN_SIZE(4,1), FPSTR(label), true, highlight); break; #endif } } @@ -213,7 +213,7 @@ void BaseNumericAdjustmentScreen::widgets_t::increments() { #endif } -void BaseNumericAdjustmentScreen::widgets_t::adjuster_sram_val(uint8_t tag, progmem_str label, const char *value, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::adjuster_sram_val(uint8_t tag, FSTR_P label, const char *value, bool is_enabled) { CommandProcessor cmd; if (_what & BACKGROUND) { @@ -239,7 +239,7 @@ void BaseNumericAdjustmentScreen::widgets_t::adjuster_sram_val(uint8_t tag, prog _line++; } -void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, progmem_str label, const char *value, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, FSTR_P label, const char *value, bool is_enabled) { if (_what & BACKGROUND) { adjuster_sram_val(tag, label, nullptr); } @@ -251,7 +251,7 @@ void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, progmem_str l } } -void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, progmem_str label, float value, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, FSTR_P label, float value, bool is_enabled) { if (_what & BACKGROUND) { adjuster_sram_val(tag, label, nullptr); } @@ -265,7 +265,7 @@ void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, progmem_str l } } -void BaseNumericAdjustmentScreen::widgets_t::button(uint8_t tag, progmem_str label, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::button(uint8_t tag, FSTR_P label, bool is_enabled) { CommandProcessor cmd; cmd.font(LAYOUT_FONT); _button(cmd, tag, BTN_POS(5,_line), BTN_SIZE(9,1), label, is_enabled); @@ -273,7 +273,7 @@ void BaseNumericAdjustmentScreen::widgets_t::button(uint8_t tag, progmem_str lab _line++; } -void BaseNumericAdjustmentScreen::widgets_t::text_field(uint8_t tag, progmem_str label, const char *value, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::text_field(uint8_t tag, FSTR_P label, const char *value, bool is_enabled) { CommandProcessor cmd; if (_what & BACKGROUND) { @@ -295,7 +295,7 @@ void BaseNumericAdjustmentScreen::widgets_t::text_field(uint8_t tag, progmem_str _line++; } -void BaseNumericAdjustmentScreen::widgets_t::two_buttons(uint8_t tag1, progmem_str label1, uint8_t tag2, progmem_str label2, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::two_buttons(uint8_t tag1, FSTR_P label1, uint8_t tag2, FSTR_P label2, bool is_enabled) { CommandProcessor cmd; cmd.font(LAYOUT_FONT); _button(cmd, tag1, BTN_POS(5,_line), BTN_SIZE(4.5,1), label1, is_enabled); @@ -304,7 +304,7 @@ void BaseNumericAdjustmentScreen::widgets_t::two_buttons(uint8_t tag1, progmem_s _line++; } -void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, progmem_str label, bool value, bool is_enabled) { +void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, FSTR_P label, bool value, bool is_enabled) { CommandProcessor cmd; if (_what & BACKGROUND) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h index c097752674..fc0ef951bd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h @@ -44,7 +44,7 @@ class BaseNumericAdjustmentScreen : public BaseScreen { uint8_t _line; uint32_t _color; uint8_t _decimals; - progmem_str _units; + FSTR_P _units; enum style_t { BTN_NORMAL, BTN_ACTION, @@ -56,25 +56,25 @@ class BaseNumericAdjustmentScreen : public BaseScreen { protected: void _draw_increment_btn(CommandProcessor &, uint8_t line, const uint8_t tag); - void _button(CommandProcessor &, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, progmem_str, bool enabled = true, bool highlight = false); + void _button(CommandProcessor &, uint8_t tag, int16_t x, int16_t y, int16_t w, int16_t h, FSTR_P, bool enabled = true, bool highlight = false); void _button_style(CommandProcessor &cmd, style_t style); public: widgets_t(draw_mode_t); widgets_t &color(uint32_t color) {_color = color; return *this;} - widgets_t &units(progmem_str units) {_units = units; return *this;} + widgets_t &units(FSTR_P units) {_units = units; return *this;} widgets_t &draw_mode(draw_mode_t what) {_what = what; return *this;} widgets_t &precision(uint8_t decimals, precision_default_t = DEFAULT_HIGHEST); - void heading (progmem_str label); - void adjuster_sram_val (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void adjuster (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void adjuster (uint8_t tag, progmem_str label, float value=0, bool is_enabled = true); - void button (uint8_t tag, progmem_str label, bool is_enabled = true); - void text_field (uint8_t tag, progmem_str label, const char *value, bool is_enabled = true); - void two_buttons (uint8_t tag1, progmem_str label1, - uint8_t tag2, progmem_str label2, bool is_enabled = true); - void toggle (uint8_t tag, progmem_str label, bool value, bool is_enabled = true); + void heading (FSTR_P label); + void adjuster_sram_val (uint8_t tag, FSTR_P label, const char *value, bool is_enabled = true); + void adjuster (uint8_t tag, FSTR_P label, const char *value, bool is_enabled = true); + void adjuster (uint8_t tag, FSTR_P label, float value=0, bool is_enabled = true); + void button (uint8_t tag, FSTR_P label, bool is_enabled = true); + void text_field (uint8_t tag, FSTR_P label, const char *value, bool is_enabled = true); + void two_buttons (uint8_t tag1, FSTR_P label1, + uint8_t tag2, FSTR_P label2, bool is_enabled = true); + void toggle (uint8_t tag, FSTR_P label, bool value, bool is_enabled = true); void home_buttons (uint8_t tag); void increments (); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h index 90a90c233e..b9791fff7a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h @@ -25,7 +25,7 @@ #define FTDI_BED_MESH_VIEW_SCREEN_CLASS BedMeshViewScreen struct BedMeshViewScreenData { - progmem_str message; + FSTR_P message; uint8_t count; xy_uint8_t highlight; }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp index 1811779297..b6f69bc33e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp @@ -44,7 +44,7 @@ void DialogBoxBaseClass::drawMessage(T message, int16_t font) { } template void DialogBoxBaseClass::drawMessage(const char *, int16_t font); -template void DialogBoxBaseClass::drawMessage(progmem_str, int16_t font); +template void DialogBoxBaseClass::drawMessage(FSTR_P, int16_t font); void DialogBoxBaseClass::drawYesNoButtons(uint8_t default_btn) { CommandProcessor cmd; @@ -67,7 +67,7 @@ void DialogBoxBaseClass::drawButton(T label) { } template void DialogBoxBaseClass::drawButton(const char *); -template void DialogBoxBaseClass::drawButton(progmem_str); +template void DialogBoxBaseClass::drawButton(FSTR_P); bool DialogBoxBaseClass::onTouchEnd(uint8_t tag) { switch (tag) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp index 37ab70f7ac..68948b0c5e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp @@ -39,7 +39,7 @@ void FilamentRunoutScreen::onRedraw(draw_mode_t what) { w.units(GET_TEXT_F(MSG_UNITS_MM)); w.precision(0); w.color(e_axis); - w.adjuster( 10, progmem_str(NUL_STR), getFilamentRunoutDistance_mm(), getFilamentRunoutEnabled()); + w.adjuster( 10, FPSTR(NUL_STR), getFilamentRunoutDistance_mm(), getFilamentRunoutEnabled()); w.increments(); #endif } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp index 4e44f26d91..df8eabbe61 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/lock_screen.cpp @@ -63,7 +63,7 @@ void LockScreen::onRedraw(draw_mode_t what) { #define MARGIN_T 3 #define MARGIN_B 3 - progmem_str message; + FSTR_P message; switch (message_style()) { case 'w': message = GET_TEXT_F(MSG_PASSCODE_REJECTED); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 830a0238fe..9117bcee10 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -60,7 +60,7 @@ void SpinnerDialogBox::onRefresh() { void SpinnerDialogBox::onRedraw(draw_mode_t) { } -void SpinnerDialogBox::show(progmem_str message) { +void SpinnerDialogBox::show(FSTR_P message) { CommandProcessor cmd; if (AT_SCREEN(SpinnerDialogBox)) cmd.stop().execute(); cmd.cmd(CMD_DLSTART) @@ -86,13 +86,13 @@ void SpinnerDialogBox::hide() { GOTO_PREVIOUS(); } -void SpinnerDialogBox::enqueueAndWait(progmem_str message, progmem_str commands) { +void SpinnerDialogBox::enqueueAndWait(FSTR_P message, FSTR_P commands) { show(message); ExtUI::injectCommands_P((const char*)commands); mydata.auto_hide = true; } -void SpinnerDialogBox::enqueueAndWait(progmem_str message, char *commands) { +void SpinnerDialogBox::enqueueAndWait(FSTR_P message, char *commands) { show(message); ExtUI::injectCommands(commands); mydata.auto_hide = true; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h index 23e31d1a91..0f51d97653 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h @@ -37,12 +37,12 @@ class SpinnerDialogBox : public UIScreen { static void onRefresh(); static void onIdle(); - static void show(progmem_str); + static void show(FSTR_P); static void hide(); template static void enqueueAndWait(T commands) {enqueueAndWait(GET_TEXT_F(MSG_PLEASE_WAIT), commands);} - static void enqueueAndWait(progmem_str message, char *commands); - static void enqueueAndWait(progmem_str message, progmem_str commands); + static void enqueueAndWait(FSTR_P message, char *commands); + static void enqueueAndWait(FSTR_P message, FSTR_P commands); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index 23ac90107b..4e76450683 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -344,7 +344,7 @@ void StatusScreen::draw_status_message(draw_mode_t what, const char *message) { #undef GRID_COLS } -void StatusScreen::setStatusMessage(progmem_str message) { +void StatusScreen::setStatusMessage(FSTR_P message) { char buff[strlen_P((const char * const)message)+1]; strcpy_P(buff, (const char * const) message); setStatusMessage((const char *) buff); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h index 6033ba1ad9..62e632756a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h @@ -36,7 +36,7 @@ class StatusScreen : public BaseScreen, public CachedScreen= LCD_PIXEL_WIDTH - 10) { bx -= ball_dist * 2; bdat.ballh = -bdat.ballh; } bdat.ballx = BTOF(bx); diff --git a/Marlin/src/lcd/menu/game/snake.cpp b/Marlin/src/lcd/menu/game/snake.cpp index f8892a4e7a..c88893a6e6 100644 --- a/Marlin/src/lcd/menu/game/snake.cpp +++ b/Marlin/src/lcd/menu/game/snake.cpp @@ -63,7 +63,7 @@ #define SNAKE_SIZ SNAKE_BOX #endif -constexpr fixed_t snakev = FTOP(0.20); +constexpr fixed_t snakev = FTOF(0.20); snake_data_t &sdat = marlin_game_data.snake; @@ -125,7 +125,7 @@ void snake_reset() { // Init the head and velocity sdat.snakex = BTOF(1); sdat.snakey = BTOF(GAME_H / 2); - //snakev = FTOP(0.25); + //snakev = FTOF(0.25); // Init the tail with a cw turn sdat.snake_dir = 0; diff --git a/Marlin/src/lcd/menu/game/types.h b/Marlin/src/lcd/menu/game/types.h index f6e6c78aa0..6e0a2051d7 100644 --- a/Marlin/src/lcd/menu/game/types.h +++ b/Marlin/src/lcd/menu/game/types.h @@ -27,7 +27,7 @@ typedef struct { int8_t x, y; } pos_t; // Simple 8:8 fixed-point typedef int16_t fixed_t; -#define FTOP(F) fixed_t((F)*256.0f) +#define FTOF(F) fixed_t((F)*256.0f) #define PTOF(P) (float(P)*(1.0f/256.0f)) #define BTOF(X) (fixed_t(X)<<8) #define FTOB(X) int8_t(fixed_t(X)>>8) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 7b253ad0ee..ad2cf72000 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -114,7 +114,7 @@ class MenuItem_confirm : public MenuItemBase { static inline void select_screen( PGM_P const yes, PGM_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - PGM_P const pref, const progmem_str string, PGM_P const suff=nullptr + PGM_P const pref, FSTR_P const string, PGM_P const suff=nullptr ) { char str[strlen_P((PGM_P)string) + 1]; strcpy_P(str, (PGM_P)string); From 1ac7a56a823b5012250dd7259a9a7a46d3bfcde5 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Sat, 25 Sep 2021 05:59:43 -0500 Subject: [PATCH 0726/2168] =?UTF-8?q?=F0=9F=90=9B=20E3V2=20Brightness=20fo?= =?UTF-8?q?llowup=20(#22821)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/lcd/M250.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 25 ++++++++++++--------- Marlin/src/inc/Conditionals_post.h | 5 ----- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 9 +++----- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 9 +------- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 18 ++++++++------- Marlin/src/lcd/e3v2/common/dwin_api.h | 8 ++++--- Marlin/src/lcd/e3v2/creality/dwin.cpp | 4 ++++ Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 9 +++++--- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 8 +++++-- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 4 ++++ Marlin/src/lcd/marlinui.cpp | 15 +++++++++---- Marlin/src/lcd/marlinui.h | 16 +++++++------ Marlin/src/lcd/menu/menu_configuration.cpp | 5 ++++- Marlin/src/module/settings.cpp | 6 ++--- buildroot/tests/STM32F103RET6_creality | 2 +- 16 files changed, 82 insertions(+), 63 deletions(-) diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index 079315311a..083fb37f65 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -32,7 +32,7 @@ */ void GcodeSuite::M250() { if (parser.seenval('C')) - ui.set_contrast(parser.value_int()); + ui.set_contrast(parser.value_byte()); else M250_report(); } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 5feb3959f6..381a0827e1 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -500,6 +500,20 @@ #define HAS_DWIN_E3V2 1 #endif +// E3V2 extras +#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI + #define SERIAL_CATCHALL 0 + #ifndef LCD_SERIAL_PORT + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) + #define LCD_SERIAL_PORT 1 + #else + #define LCD_SERIAL_PORT 3 // Creality 4.x board + #endif + #endif + #define HAS_LCD_BRIGHTNESS 1 + #define LCD_BRIGHTNESS_MAX 250 +#endif + #if IS_ULTRA_LCD #define HAS_WIRED_LCD 1 #if ENABLED(DOGLCD) @@ -1111,17 +1125,6 @@ #define HAS_ETHERNET 1 #endif -#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #define SERIAL_CATCHALL 0 - #ifndef LCD_SERIAL_PORT - #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_E3_TURBO) - #define LCD_SERIAL_PORT 1 - #else - #define LCD_SERIAL_PORT 3 // Creality 4.x board - #endif - #endif -#endif - // Fallback Stepper Driver types that don't depend on Configuration_adv.h #ifndef X_DRIVER_TYPE #define X_DRIVER_TYPE A4988 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 6c1511282f..1db4208a1f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -423,11 +423,6 @@ #endif #endif -#if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #define HAS_LCD_BRIGHTNESS 1 - #define MAX_LCD_BRIGHTNESS 31 -#endif - /** * Override the SD_DETECT_STATE set in Configuration_adv.h * and enable sharing of onboard SD host drives (all platforms but AGCM4) diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 712e76e86f..9617b3775d 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -376,12 +376,9 @@ void MarlinUI::clear_lcd() { lcd.clear_buffer(); } -int16_t MarlinUI::contrast; // Initialized by settings.load() - -void MarlinUI::set_contrast(const int16_t value) { - contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); - lcd.setContrast(contrast); -} +#if HAS_LCD_CONTRAST + void MarlinUI::_set_contrast() { lcd.setContrast(contrast); } +#endif static void center_text_P(PGM_P pstart, uint8_t y) { uint8_t len = utf8_strlen_P(pstart); diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 33bb3e4b92..98173da8f3 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -93,14 +93,7 @@ U8G_CLASS u8g; #endif #if HAS_LCD_CONTRAST - - int16_t MarlinUI::contrast = DEFAULT_LCD_CONTRAST; - - void MarlinUI::set_contrast(const int16_t value) { - contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); - u8g.setContrast(contrast); - } - + void MarlinUI::_set_contrast() { u8g.setContrast(contrast); } #endif void MarlinUI::set_font(const MarlinFont font_nr) { diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 480b98d3fd..d89b22a7aa 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -78,14 +78,16 @@ bool DWIN_Handshake() { && databuf[3] == 'K' ); } -// Set the backlight brightness -// brightness: (0x00-0x1F) -void DWIN_LCD_Brightness(const uint8_t brightness) { - size_t i = 0; - DWIN_Byte(i, 0x30); - DWIN_Byte(i, _MAX(brightness, 0x1F)); - DWIN_Send(i); -} +#if HAS_LCD_BRIGHTNESS + // Set LCD backlight (from DWIN Enhanced) + // brightness: 0x00-0xFF + void DWIN_LCD_Brightness(const uint8_t brightness) { + size_t i = 0; + DWIN_Byte(i, 0x30); + DWIN_Byte(i, brightness); + DWIN_Send(i); + } +#endif // Set screen display direction // dir: 0=0°, 1=90°, 2=180°, 3=270° diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index d4715acc41..735907e4a4 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -87,9 +87,11 @@ bool DWIN_Handshake(); // DWIN startup void DWIN_Startup(); -// Set the backlight brightness -// brightness: (0x00-0xFF) -void DWIN_LCD_Brightness(const uint8_t brightness); +#if HAS_LCD_BRIGHTNESS + // Set the backlight brightness + // brightness: (0x00-0xFF) + void DWIN_LCD_Brightness(const uint8_t brightness); +#endif // Set screen display direction // dir: 0=0°, 1=90°, 2=180°, 3=270° diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 0a52c9b965..006ff5db26 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1816,6 +1816,10 @@ void HMI_SDCardInit() { card.cdroot(); } void MarlinUI::refresh() { /* Nothing to see here */ } +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + #if ENABLED(SCROLL_LONG_FILENAMES) char shift_name[LONG_FILENAME_LENGTH + 1]; diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index b1b9dec719..847073c52e 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -865,6 +865,10 @@ void HMI_SDCardInit() { card.cdroot(); } void MarlinUI::refresh() { /* Nothing to see here */ } +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + #define ICON_Folder ICON_More #if ENABLED(SCROLL_LONG_FILENAMES) @@ -2186,9 +2190,8 @@ void SetPID(celsius_t t, heater_id_t h) { #endif #if HAS_LCD_BRIGHTNESS - void ApplyBrightness() { ui.set_brightness(HMI_value.Value); } - void LiveBrightness() { DWIN_LCD_Brightness(HMI_value.Value); } - void SetBrightness() { SetIntOnClick(MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, ui.brightness, ApplyBrightness, LiveBrightness); } + void LiveBrightness() { ui.set_brightness(HMI_value.Value); } + void SetBrightness() { SetIntOnClick(LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, ui.brightness, nullptr, LiveBrightness); } #endif #if ENABLED(SOUND_MENU_ITEM) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 55aee49f82..eccbe8d141 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -2717,7 +2717,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Float(ui.brightness, row, false, 1); } else - Modify_Value(ui.brightness, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, 1, ui.refresh_brightness); + Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); break; case VISUAL_TIME_FORMAT: if (draw) { @@ -3879,7 +3879,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Float(ui.brightness, row, false, 1); } else - Modify_Value(ui.brightness, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS, 1, ui.refresh_brightness); + Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); break; } break; @@ -4800,6 +4800,10 @@ void CrealityDWINClass::Update() { void MarlinUI::update() { CrealityDWIN.Update(); } +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + void CrealityDWINClass::State_Update() { if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { if (!printing) Start_Print(card.isFileOpen() || TERN0(POWER_LOSS_RECOVERY, recovery.valid())); diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 45c1fa3122..09458401be 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -254,6 +254,10 @@ void MarlinUI::draw_status_message(const bool blink) { #endif } +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + #if HAS_LCD_MENU #include "../../menu/menu.h" diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 2a6a320889..5fcbff870e 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -95,16 +95,23 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif +#if HAS_LCD_CONTRAST + uint8_t MarlinUI::contrast; // Initialized by settings.load() + + void MarlinUI::set_contrast(const uint8_t value) { + contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); + _set_contrast(); + } +#endif + #if HAS_LCD_BRIGHTNESS uint8_t MarlinUI::brightness = DEFAULT_LCD_BRIGHTNESS; bool MarlinUI::backlight = true; void MarlinUI::set_brightness(const uint8_t value) { backlight = !!value; - if (backlight) brightness = constrain(value, MIN_LCD_BRIGHTNESS, MAX_LCD_BRIGHTNESS); - // Set brightness on enabled LCD here - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_LCD_Brightness(brightness)); - TERN_(DWIN_CREALITY_LCD_JYERSUI, DWIN_LCD_Brightness(backlight ? brightness : 0)); + if (backlight) brightness = constrain(value, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX); + _set_brightness(); } #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 49ecd89957..270ee3afce 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -247,17 +247,18 @@ public: #endif #if HAS_LCD_BRIGHTNESS - #ifndef MIN_LCD_BRIGHTNESS - #define MIN_LCD_BRIGHTNESS 1 + #ifndef LCD_BRIGHTNESS_MIN + #define LCD_BRIGHTNESS_MIN 1 #endif - #ifndef MAX_LCD_BRIGHTNESS - #define MAX_LCD_BRIGHTNESS 255 + #ifndef LCD_BRIGHTNESS_MAX + #define LCD_BRIGHTNESS_MAX 255 #endif #ifndef DEFAULT_LCD_BRIGHTNESS - #define DEFAULT_LCD_BRIGHTNESS MAX_LCD_BRIGHTNESS + #define DEFAULT_LCD_BRIGHTNESS LCD_BRIGHTNESS_MAX #endif static uint8_t brightness; static bool backlight; + static void _set_brightness(); // Implementation-specific static void set_brightness(const uint8_t value); FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } #endif @@ -425,8 +426,9 @@ public: static uint8_t lcd_status_update_delay; #if HAS_LCD_CONTRAST - static int16_t contrast; - static void set_contrast(const int16_t value); + static uint8_t contrast; + static void _set_contrast(); // Implementation-specific + static void set_contrast(const uint8_t value); FORCE_INLINE static void refresh_contrast() { set_contrast(contrast); } #endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 44c99dd0a9..c9227724ab 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -528,8 +528,11 @@ void menu_configuration() { #endif #endif + #if HAS_LCD_BRIGHTNESS + EDIT_ITEM_FAST(uint8, MSG_BRIGHTNESS, &ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, ui.refresh_brightness, true); + #endif #if HAS_LCD_CONTRAST - EDIT_ITEM(int3, MSG_CONTRAST, &ui.contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, ui.refresh_contrast, true); + EDIT_ITEM_FAST(uint8, MSG_CONTRAST, &ui.contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, ui.refresh_contrast, true); #endif #if ENABLED(FWRETRACT) SUBMENU(MSG_RETRACT, menu_config_retract); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index d8d9f20276..7d73f2ec4b 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -352,7 +352,7 @@ typedef struct SettingsDataStruct { // // HAS_LCD_CONTRAST // - int16_t lcd_contrast; // M250 C + uint8_t lcd_contrast; // M250 C // // HAS_LCD_BRIGHTNESS @@ -1017,7 +1017,7 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(lcd_contrast); - const int16_t lcd_contrast = TERN(HAS_LCD_CONTRAST, ui.contrast, 127); + const uint8_t lcd_contrast = TERN(HAS_LCD_CONTRAST, ui.contrast, 127); EEPROM_WRITE(lcd_contrast); } @@ -1884,7 +1884,7 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(lcd_contrast); - int16_t lcd_contrast; + uint8_t lcd_contrast; EEPROM_READ(lcd_contrast); if (!validating) { TERN_(HAS_LCD_CONTRAST, ui.set_contrast(lcd_contrast)); diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index 8ce4f57cf8..d530f7b851 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -24,7 +24,7 @@ opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY exec_test $1 $2 "Ender 3 v2 with JyersUI" "$3" use_example_configs "Creality/Ender-3 V2/MarlinUI" -opt_add SDCARD_EEPROM_EMULATION NOZZLE_AS_PROBE AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING +opt_add SDCARD_EEPROM_EMULATION AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" restore_configs From 031fec7a0233d5b1199e2e3a61a5ea98ecc3bf84 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 26 Sep 2021 01:02:25 +0000 Subject: [PATCH 0727/2168] [cron] Bump distribution date (2021-09-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d34f5ddd5a..bfb8eb2346 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-25" +//#define STRING_DISTRIBUTION_DATE "2021-09-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index affbde748c..afef568919 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 "2021-09-25" + #define STRING_DISTRIBUTION_DATE "2021-09-26" #endif /** From 8fd5a4037a27c7c4009e9272770957a4931bcaad Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sun, 26 Sep 2021 04:59:29 +0200 Subject: [PATCH 0728/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20M412=5Freport=20?= =?UTF-8?q?formatting=20(#22834)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/runout/M412.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index bed08294ba..9cbfbade66 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -68,7 +68,7 @@ void GcodeSuite::M412() { void GcodeSuite::M412_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); - SERIAL_ECHOLNPGM( + SERIAL_ECHOPGM( " M412 S", runout.enabled #if HAS_FILAMENT_RUNOUT_DISTANCE , " D", LINEAR_UNIT(runout.runout_distance()) From 3329e07bd9cfc148a7ca78c121778e2255ac8a72 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 27 Sep 2021 01:00:10 +0000 Subject: [PATCH 0729/2168] [cron] Bump distribution date (2021-09-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index bfb8eb2346..195d40f6ce 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-26" +//#define STRING_DISTRIBUTION_DATE "2021-09-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index afef568919..d39f82525a 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 "2021-09-26" + #define STRING_DISTRIBUTION_DATE "2021-09-27" #endif /** From 942b76082c5704558957731828e0fd023ad09bae Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 28 Sep 2021 04:17:00 +1300 Subject: [PATCH 0730/2168] =?UTF-8?q?=F0=9F=94=A7=20Sanity-check=20BLTOUCH?= =?UTF-8?q?=5FSET=5F5V=5FMODE=20on=205V=20pins=20(#22840)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/inc/SanityCheck.h | 28 ++++++++++++++++++++++++++-- 1 file changed, 26 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 5408f25f38..58c02e7ebd 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1529,10 +1529,34 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if ENABLED(BLTOUCH) + + // BLTouch can't run in 5V mode with a 3.3V probe pin + #if ENABLED(BLTOUCH_SET_5V_MODE) + #define _5V(P,A,B) WITHIN(P,A,B) + #ifdef STM32F1 // STM32F103 5V-tolerant pins + #define _IS_5V_TOLERANT(P) (_5V(P,PA8,PA15) || _5V(P,PB2,PB15) || _5V(P,PC6,PC12) || _5V(P,PD0,PD15) || _5V(P,PE0,PE15) || _5V(P,PF0,PF5) || _5V(P,PF11,PF15)) + #elif defined(ARDUINO_ARCH_SAM) + #define _IS_5V_TOLERANT(P) 0 // Assume no 5V tolerance + #else + #define _IS_5V_TOLERANT(P) 1 // Assume 5V tolerance + #endif + #if USES_Z_MIN_PROBE_PIN && !_IS_5V_TOLERANT(Z_MIN_PROBE_PIN) + #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PROBE_PIN." + #elif !_IS_5V_TOLERANT(Z_MIN_PIN) + #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PIN." + #endif + #undef _IS_5V_TOLERANT + #undef _5V + #elif NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN, ENDSTOPPULLUP_ZMIN_PROBE) + #if USES_Z_MIN_PROBE_PIN + #error "BLTOUCH on Z_MIN_PROBE_PIN requires ENDSTOPPULLUP_ZMIN_PROBE, ENDSTOPPULLUPS, or BLTOUCH_SET_5V_MODE." + #else + #error "BLTOUCH on Z_MIN_PIN requires ENDSTOPPULLUP_ZMIN, ENDSTOPPULLUPS, or BLTOUCH_SET_5V_MODE." + #endif + #endif + #if BLTOUCH_DELAY < 200 #error "BLTOUCH_DELAY less than 200 is unsafe and is not supported." - #elif DISABLED(BLTOUCH_SET_5V_MODE) && NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN, ENDSTOPPULLUP_ZMIN_PROBE) - #error "BLTOUCH without BLTOUCH_SET_5V_MODE requires ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN or ENDSTOPPULLUP_ZMIN_PROBE." #endif #endif From f73175d8263033d1feb1045af67e7230c844aab0 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Mon, 27 Sep 2021 21:01:47 +0200 Subject: [PATCH 0731/2168] =?UTF-8?q?=F0=9F=9A=B8=20TFT=20backlight=20PWM?= =?UTF-8?q?=20/=20brightness=20(#22841)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 9 +++++++++ Marlin/src/lcd/language/language_fr.h | 1 + Marlin/src/lcd/tft/touch.cpp | 4 +++- Marlin/src/lcd/tft/ui_common.cpp | 9 +++++++++ Marlin/src/lcd/tft_io/tft_io.cpp | 10 +++++++++- Marlin/src/lcd/touch/touch_buttons.cpp | 4 +++- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 6 ++++++ 7 files changed, 40 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 98173da8f3..f1c5eebbb5 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -338,6 +338,15 @@ void MarlinUI::draw_kill_screen() { void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { + #if PIN_EXISTS(TFT_BACKLIGHT) + if (PWM_PIN(TFT_BACKLIGHT_PIN)) + analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness); + #endif + } +#endif + #if HAS_LCD_MENU #include "../menu/menu.h" diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index be8daaa3dc..a99659bf18 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -336,6 +336,7 @@ namespace Language_fr { LSTR MSG_FILAMENT_LOAD = _UxGT("Charger mm"); LSTR MSG_ADVANCE_K = _UxGT("Avance K"); LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); + LSTR MSG_BRIGHTNESS = _UxGT("Luminosité LCD"); LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); LSTR MSG_STORE_EEPROM = _UxGT("Enregistrer config."); LSTR MSG_LOAD_EEPROM = _UxGT("Charger config."); diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 7262536e77..dc1f2ecb6c 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -294,7 +294,9 @@ bool Touch::get_point(int16_t *x, int16_t *y) { } void Touch::wakeUp() { if (isSleeping()) { - #if PIN_EXISTS(TFT_BACKLIGHT) + #if HAS_LCD_BRIGHTNESS + ui._set_brightness(); + #elif PIN_EXISTS(TFT_BACKLIGHT) WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index a5f41874b0..41862b5ad8 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -210,6 +210,15 @@ void MarlinUI::clear_lcd() { cursor.set(0, 0); } +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { + #if PIN_EXISTS(TFT_BACKLIGHT) + if (PWM_PIN(TFT_BACKLIGHT_PIN)) + analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness); + #endif + } +#endif + #if ENABLED(TOUCH_SCREEN_CALIBRATION) void MarlinUI::touch_calibration_screen() { diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index 707232b4bb..6ec3bedcdf 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -49,6 +49,10 @@ #include "ili9341.h" #include "ili9328.h" +#if HAS_LCD_BRIGHTNESS + #include "../marlinui.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_GRAPHICAL_TFT) #include "../../core/debug_out.h" @@ -72,6 +76,9 @@ if (lcd_id != 0xFFFFFFFF) return; #if PIN_EXISTS(TFT_BACKLIGHT) WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); + #if HAS_LCD_BRIGHTNESS && DISABLED(DELAYED_BACKLIGHT_INIT) + ui._set_brightness(); + #endif #endif // io.Init(); @@ -141,11 +148,12 @@ if (lcd_id != 0xFFFFFFFF) return; lcd_id = 0; } #else - #error Unsupported TFT driver + #error "Unsupported TFT driver" #endif #if PIN_EXISTS(TFT_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) WRITE(TFT_BACKLIGHT_PIN, HIGH); + TERN_(HAS_LCD_BRIGHTNESS, ui._set_brightness()); #endif } diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 9d9d6efeb2..feaba8483b 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -122,7 +122,9 @@ uint8_t TouchButtons::read_buttons() { } void TouchButtons::wakeUp() { if (isSleeping()) { - #if PIN_EXISTS(TFT_BACKLIGHT) + #if HAS_LCD_BRIGHTNESS + ui._set_brightness(); + #elif PIN_EXISTS(TFT_BACKLIGHT) WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index b25badca56..34fbdaf02f 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -135,6 +135,7 @@ #define TFT_RESET_PIN PC4 // pin 33 #define TFT_BACKLIGHT_PIN PD12 // pin 59 + #define TFT_BACKLIGHT_PWM 150 // Brightness with alt. TIM4 chan 1 (1-255) #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h #define DOGLCD_SCK -1 @@ -143,6 +144,11 @@ #define TFT_BUFFER_SIZE 3200 #endif +#if defined(TFT_BACKLIGHT_PWM) && !defined(MAPLE_STM32F1) + #define HAS_LCD_BRIGHTNESS 1 + #define DEFAULT_LCD_BRIGHTNESS TFT_BACKLIGHT_PWM +#endif + #if ENABLED(SDIO_SUPPORT) #define SD_SS_PIN -1 // else SDSS set to PA4 in M43 (spi_pins.h) #endif From 228eb9c404fcbcebb507bbfe781ebe3ca0a1ccdf Mon Sep 17 00:00:00 2001 From: espr14 Date: Mon, 27 Sep 2021 21:05:52 +0200 Subject: [PATCH 0732/2168] =?UTF-8?q?=F0=9F=8E=A8=20steps=5Fto=5Fmm=20=3D>?= =?UTF-8?q?=20mm=5Fper=5Fstep=20(#22847)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/encoder_i2c.cpp | 2 +- Marlin/src/feature/runout.h | 2 +- Marlin/src/gcode/config/M92.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 8 +-- Marlin/src/lcd/menu/menu.cpp | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_tune.cpp | 6 +-- Marlin/src/lcd/tft/ui_1024x600.cpp | 2 +- Marlin/src/lcd/tft/ui_320x240.cpp | 2 +- Marlin/src/lcd/tft/ui_480x320.cpp | 2 +- Marlin/src/module/motion.cpp | 6 +-- Marlin/src/module/planner.cpp | 72 +++++++++++++-------------- Marlin/src/module/planner.h | 4 +- Marlin/src/module/settings.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- 15 files changed, 58 insertions(+), 58 deletions(-) diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index e6b127e03c..bed24f0525 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -173,7 +173,7 @@ void I2CPositionEncoder::update() { LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); SERIAL_CHAR(axis_codes[encoderAxis]); - SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm"); + SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.mm_per_step[encoderAxis], "mm"); babystep.add_steps(encoderAxis, -LROUND(errorP)); errPrstIdx = 0; } diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index d88e81d9d9..918e65bb22 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -373,7 +373,7 @@ class FilamentSensorBase { // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. const uint8_t e = b->extruder; const int32_t steps = b->steps.e; - runout_mm_countdown[e] -= (TEST(b->direction_bits, E_AXIS) ? -steps : steps) * planner.steps_to_mm[E_AXIS_N(e)]; + runout_mm_countdown[e] -= (TEST(b->direction_bits, E_AXIS) ? -steps : steps) * planner.mm_per_step[E_AXIS_N(e)]; } } }; diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index ecc5e63a3c..ef11533114 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -76,7 +76,7 @@ void GcodeSuite::M92() { if (parser.seen('H') || wanted) { const uint16_t argH = parser.ushortval('H'), micro_steps = argH ?: Z_MICROSTEPS; - const float z_full_step_mm = micro_steps * planner.steps_to_mm[Z_AXIS]; + const float z_full_step_mm = micro_steps * planner.mm_per_step[Z_AXIS]; SERIAL_ECHO_START(); SERIAL_ECHOPGM("{ micro_steps:", micro_steps, ", z_full_step_mm:", z_full_step_mm); if (wanted) { diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 97b1ab885b..d37b277110 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -755,7 +755,7 @@ namespace ExtUI { * what nozzle is printing. */ void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles) { - const float mm = steps * planner.steps_to_mm[axis]; + const float mm = steps * planner.mm_per_step[axis]; UNUSED(mm); if (!babystepAxis_steps(steps, axis)) return; @@ -791,12 +791,12 @@ namespace ExtUI { * steps that is at least mm long. */ int16_t mmToWholeSteps(const_float_t mm, const axis_t axis) { - const float steps = mm / planner.steps_to_mm[axis]; + const float steps = mm / planner.mm_per_step[axis]; return steps > 0 ? CEIL(steps) : FLOOR(steps); } float mmFromWholeSteps(int16_t steps, const axis_t axis) { - return steps * planner.steps_to_mm[axis]; + return steps * planner.mm_per_step[axis]; } #endif // BABYSTEPPING @@ -806,7 +806,7 @@ namespace ExtUI { #if HAS_BED_PROBE + probe.offset.z #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) - + planner.steps_to_mm[Z_AXIS] * babystep.axis_total[BS_AXIS_IND(Z_AXIS)] + + planner.mm_per_step[Z_AXIS] * babystep.axis_total[BS_AXIS_IND(Z_AXIS)] #endif ); } diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index a177f32932..76cdd51cd5 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -315,7 +315,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { const int16_t babystep_increment = int16_t(ui.encoderPosition) * (BABYSTEP_SIZE_Z); ui.encoderPosition = 0; - const float diff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + const float diff = planner.mm_per_step[Z_AXIS] * babystep_increment, new_probe_offset = probe.offset.z + diff, new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - diff diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index cfb7e5fc70..8d87a876b9 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -532,7 +532,7 @@ void menu_advanced_steps_per_mm() { if (e == active_extruder) planner.refresh_positioning(); else - planner.steps_to_mm[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; + planner.mm_per_step[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; }); #elif E_STEPPERS EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 3a0d0c81ca..37ffb679e9 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -65,8 +65,8 @@ babystep.add_steps(axis, steps); } if (ui.should_draw()) { - const float spm = planner.steps_to_mm[axis]; - MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(spm * babystep.accum)); + const float mps = planner.mm_per_step[axis]; + MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(mps * babystep.accum)); #if ENABLED(BABYSTEP_DISPLAY_TOTAL) const bool in_view = TERN1(HAS_MARLINUI_U8GLIB, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); if (in_view) { @@ -81,7 +81,7 @@ lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); #endif - lcd_put_u8str(BABYSTEP_TO_STR(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); + lcd_put_u8str(BABYSTEP_TO_STR(mps * babystep.axis_total[BS_TOTAL_IND(axis)])); } #endif } diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index db75c36ef9..456bd32758 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -667,7 +667,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; - const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + const float bsDiff = planner.mm_per_step[Z_AXIS] * babystep_increment, new_probe_offset = probe.offset.z + bsDiff, new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index deffbae94c..15d477c485 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -652,7 +652,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; - const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + const float bsDiff = planner.mm_per_step[Z_AXIS] * babystep_increment, new_probe_offset = probe.offset.z + bsDiff, new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index c8333f7e4b..424f29a182 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -654,7 +654,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; - const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + const float bsDiff = planner.mm_per_step[Z_AXIS] * babystep_increment, new_probe_offset = probe.offset.z + bsDiff, new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 8ad7455aaf..a56831c214 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1682,7 +1682,7 @@ void prepare_line_to_destination() { int16_t phaseDelta = (home_phase[axis] - phaseCurrent) * stepperBackoutDir; // Check if home distance within endstop assumed repeatability noise of .05mm and warn. - if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) + if (ABS(phaseDelta) * planner.mm_per_step[axis] / phasePerUStep < 0.05f) SERIAL_ECHOLNPGM("Selected home phase ", home_phase[axis], " too close to endstop trigger phase ", phaseCurrent, ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); @@ -1691,7 +1691,7 @@ void prepare_line_to_destination() { if (phaseDelta < 0) phaseDelta += 1024; // Convert TMC µsteps(phase) to whole Marlin µsteps to effector backout direction to mm - const float mmDelta = int16_t(phaseDelta / phasePerUStep) * effectorBackoutDir * planner.steps_to_mm[axis]; + const float mmDelta = int16_t(phaseDelta / phasePerUStep) * effectorBackoutDir * planner.mm_per_step[axis]; // Optional debug messages if (DEBUGGING(LEVELING)) { @@ -1999,7 +1999,7 @@ void prepare_line_to_destination() { // Delta homing treats the axes as normal linear axes. const float adjDistance = delta_endstop_adj[axis], - minDistance = (MIN_STEPS_PER_SEGMENT) * planner.steps_to_mm[axis]; + minDistance = (MIN_STEPS_PER_SEGMENT) * planner.mm_per_step[axis]; // Retrace by the amount specified in delta_endstop_adj if more than min steps. if (adjDistance * (Z_HOME_DIR) < 0 && ABS(adjDistance) > minDistance) { // away from endstop, more than min distance diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 511c3b3f43..f22a99316f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -138,7 +138,7 @@ planner_settings_t Planner::settings; // Initialized by settings.load( uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 -float Planner::steps_to_mm[DISTINCT_AXES]; // (mm) Millimeters per step +float Planner::mm_per_step[DISTINCT_AXES]; // (mm) Millimeters per step #if HAS_JUNCTION_DEVIATION float Planner::junction_deviation_mm; // (mm) M205 J @@ -1702,7 +1702,7 @@ void Planner::endstop_triggered(const AxisEnum axis) { } float Planner::triggered_position_mm(const AxisEnum axis) { - return stepper.triggered_position(axis) * steps_to_mm[axis]; + return stepper.triggered_position(axis) * mm_per_step[axis]; } void Planner::finish_and_disable() { @@ -1759,7 +1759,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { #endif - return axis_steps * steps_to_mm[axis]; + return axis_steps * mm_per_step[axis]; } /** @@ -2015,51 +2015,51 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } steps_dist_mm; #if IS_CORE #if CORE_IS_XY - steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; - steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; - steps_dist_mm.z = dc * steps_to_mm[Z_AXIS]; - steps_dist_mm.a = (da + db) * steps_to_mm[A_AXIS]; - steps_dist_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.z = dc * mm_per_step[Z_AXIS]; + steps_dist_mm.a = (da + db) * mm_per_step[A_AXIS]; + steps_dist_mm.b = CORESIGN(da - db) * mm_per_step[B_AXIS]; #elif CORE_IS_XZ - steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; - steps_dist_mm.y = db * steps_to_mm[Y_AXIS]; - steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; - steps_dist_mm.a = (da + dc) * steps_to_mm[A_AXIS]; - steps_dist_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.y = db * mm_per_step[Y_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.a = (da + dc) * mm_per_step[A_AXIS]; + steps_dist_mm.c = CORESIGN(da - dc) * mm_per_step[C_AXIS]; #elif CORE_IS_YZ - steps_dist_mm.x = da * steps_to_mm[X_AXIS]; - steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; - steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; - steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; - steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.x = da * mm_per_step[X_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.b = (db + dc) * mm_per_step[B_AXIS]; + steps_dist_mm.c = CORESIGN(db - dc) * mm_per_step[C_AXIS]; #endif #if LINEAR_AXES >= 4 - steps_dist_mm.i = di * steps_to_mm[I_AXIS]; + steps_dist_mm.i = di * mm_per_step[I_AXIS]; #endif #if LINEAR_AXES >= 5 - steps_dist_mm.j = dj * steps_to_mm[J_AXIS]; + steps_dist_mm.j = dj * mm_per_step[J_AXIS]; #endif #if LINEAR_AXES >= 6 - steps_dist_mm.k = dk * steps_to_mm[K_AXIS]; + steps_dist_mm.k = dk * mm_per_step[K_AXIS]; #endif #elif ENABLED(MARKFORGED_XY) - steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; - steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; - steps_dist_mm.z = dc * steps_to_mm[Z_AXIS]; - steps_dist_mm.a = (da - db) * steps_to_mm[A_AXIS]; - steps_dist_mm.b = db * steps_to_mm[B_AXIS]; + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.z = dc * mm_per_step[Z_AXIS]; + steps_dist_mm.a = (da - db) * mm_per_step[A_AXIS]; + steps_dist_mm.b = db * mm_per_step[B_AXIS]; #else LINEAR_AXIS_CODE( - steps_dist_mm.a = da * steps_to_mm[A_AXIS], - steps_dist_mm.b = db * steps_to_mm[B_AXIS], - steps_dist_mm.c = dc * steps_to_mm[C_AXIS], - steps_dist_mm.i = di * steps_to_mm[I_AXIS], - steps_dist_mm.j = dj * steps_to_mm[J_AXIS], - steps_dist_mm.k = dk * steps_to_mm[K_AXIS] + steps_dist_mm.a = da * mm_per_step[A_AXIS], + steps_dist_mm.b = db * mm_per_step[B_AXIS], + steps_dist_mm.c = dc * mm_per_step[C_AXIS], + steps_dist_mm.i = di * mm_per_step[I_AXIS], + steps_dist_mm.j = dj * mm_per_step[J_AXIS], + steps_dist_mm.k = dk * mm_per_step[K_AXIS] ); #endif - TERN_(HAS_EXTRUDERS, steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]); + TERN_(HAS_EXTRUDERS, steps_dist_mm.e = esteps_float * mm_per_step[E_AXIS_N(extruder)]); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); @@ -2889,7 +2889,7 @@ bool Planner::buffer_segment(const abce_pos_t &abce // When changing extruders recalculate steps corresponding to the E position #if ENABLED(DISTINCT_E_FACTORS) if (last_extruder != extruder && settings.axis_steps_per_mm[E_AXIS_N(extruder)] != settings.axis_steps_per_mm[E_AXIS_N(last_extruder)]) { - position.e = LROUND(position.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)] * steps_to_mm[E_AXIS_N(last_extruder)]); + position.e = LROUND(position.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)] * mm_per_step[E_AXIS_N(last_extruder)]); last_extruder = extruder; } #endif @@ -3168,11 +3168,11 @@ void Planner::reset_acceleration_rates() { } /** - * Recalculate 'position' and 'steps_to_mm'. + * Recalculate 'position' and 'mm_per_step'. * Must be called whenever settings.axis_steps_per_mm changes! */ void Planner::refresh_positioning() { - LOOP_DISTINCT_AXES(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i]; + LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i]; set_position_mm(current_position); reset_acceleration_rates(); } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 15744c3f9a..16d136be45 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -374,7 +374,7 @@ class Planner { #endif static uint32_t max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2 - static float steps_to_mm[DISTINCT_AXES]; // Millimeters per step + static float mm_per_step[DISTINCT_AXES]; // Millimeters per step #if HAS_JUNCTION_DEVIATION static float junction_deviation_mm; // (mm) M205 J @@ -489,7 +489,7 @@ class Planner { static void reset_acceleration_rates(); /** - * Recalculate 'position' and 'steps_to_mm'. + * Recalculate 'position' and 'mm_per_step'. * Must be called whenever settings.axis_steps_per_mm changes! */ static void refresh_positioning(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 7d73f2ec4b..921b25dad7 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -557,7 +557,7 @@ void MarlinSettings::postprocess() { TERN_(EXTENSIBLE_UI, ExtUI::onPostprocessSettings()); - // Refresh steps_to_mm with the reciprocal of axis_steps_per_mm + // Refresh mm_per_step with the reciprocal of axis_steps_per_mm // and init stepper.count[], planner.position[] with current_position planner.refresh_positioning(); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 6be98e90d4..d59ebe5695 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1102,7 +1102,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { lpq[lpq_ptr] = 0; if (++lpq_ptr >= lpq_len) lpq_ptr = 0; - work_pid[ee].Kc = (lpq[lpq_ptr] * planner.steps_to_mm[E_AXIS]) * PID_PARAM(Kc, ee); + work_pid[ee].Kc = (lpq[lpq_ptr] * planner.mm_per_step[E_AXIS]) * PID_PARAM(Kc, ee); pid_output += work_pid[ee].Kc; } #endif // PID_EXTRUSION_SCALING From 5dce8d0a84aa8ee3e2b63c880dd2eadc18a64f1b Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Tue, 28 Sep 2021 03:08:29 +0800 Subject: [PATCH 0733/2168] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20MKS=20LVGL=20UI?= =?UTF-8?q?=20temperature=20set=20interface=20(#22848)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 14 +++++--------- Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp | 1 + 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index 1d804c3b2a..eb8799f1c4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -124,24 +124,20 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { else if (uiCfg.extruderIndex == 0) { uiCfg.curTempType = TERN(HAS_HEATED_BED, 1, 0); } + lv_obj_del(btn_pla); + lv_obj_del(btn_abs); } else if (uiCfg.curTempType == 1) { uiCfg.extruderIndex = 0; uiCfg.curTempType = 0; + lv_obj_del(buttonAdd); + lv_obj_del(buttonDec); disp_add_dec(); disp_ext_heart(); } + disp_temp_type(); break; - case ID_P_STEP: - switch (uiCfg.stepHeat) { - case 1: uiCfg.stepHeat = 5; break; - case 5: uiCfg.stepHeat = 10; break; - case 10: uiCfg.stepHeat = 1; break; - default: break; - } - disp_step_heat(); - break; case ID_P_OFF: if (uiCfg.curTempType == 0) { thermalManager.setTargetHotend(0, uiCfg.extruderIndex); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index a8d8b29ac0..1596944bd8 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -98,6 +98,7 @@ void disp_det_ok() { lv_obj_set_style(det_info, &det_style); lv_label_set_text(det_info, "det:ok"); } + void disp_det_error() { det_style.text.color.full = 0xF800; lv_obj_set_style(det_info, &det_style); From 8f9e56afb97ca6a40265b24fe90ac7b672050df9 Mon Sep 17 00:00:00 2001 From: Malderin <52313714+Malderin@users.noreply.github.com> Date: Mon, 27 Sep 2021 22:13:38 +0300 Subject: [PATCH 0734/2168] =?UTF-8?q?=F0=9F=9A=B8=20MKS=20UI=20LVGL=20bed?= =?UTF-8?q?=20preheat=20presets=20(#22842)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index eb8799f1c4..6e9c88b60b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -132,8 +132,6 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { uiCfg.curTempType = 0; lv_obj_del(buttonAdd); lv_obj_del(buttonDec); - disp_add_dec(); - disp_ext_heart(); } disp_temp_type(); @@ -156,10 +154,16 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { draw_return_ui(); break; case ID_P_ABS: - thermalManager.setTargetHotend(PREHEAT_2_TEMP_HOTEND, 0); + if (uiCfg.curTempType == 0) + thermalManager.setTargetHotend(PREHEAT_2_TEMP_HOTEND, 0); + else if (uiCfg.curTempType == 1) + thermalManager.setTargetBed(PREHEAT_2_TEMP_BED); break; case ID_P_PLA: - thermalManager.setTargetHotend(PREHEAT_1_TEMP_HOTEND, 0); + if (uiCfg.curTempType == 0) + thermalManager.setTargetHotend(PREHEAT_1_TEMP_HOTEND, 0); + else if (uiCfg.curTempType == 1) + thermalManager.setTargetBed(PREHEAT_1_TEMP_BED); break; } } @@ -180,6 +184,7 @@ void lv_draw_preHeat() { buttonStep = lv_imgbtn_create(scr, nullptr, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight, event_handler, ID_P_STEP); if (uiCfg.curTempType == 0) disp_ext_heart(); + if (uiCfg.curTempType == 1) disp_ext_heart(); #if HAS_ROTARY_ENCODER if (gCfgItems.encoder_enable) { From 8ab02df63a2360b2dac86048b38311bbdfa42b3c Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Mon, 27 Sep 2021 14:47:47 -0500 Subject: [PATCH 0735/2168] =?UTF-8?q?=E2=9C=A8=20E3V2=20(Enhanced)=20Mesh?= =?UTF-8?q?=20Viewer=20(#22844)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 23 +++++- Marlin/src/lcd/e3v2/enhanced/dwin.h | 3 + Marlin/src/lcd/e3v2/enhanced/dwinui.h | 1 + Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp | 75 +++++++++++++++++++ Marlin/src/lcd/e3v2/enhanced/meshviewer.h | 28 +++++++ Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 8 +- .../cocoa_press/leveling_menu.cpp | 2 +- .../generic/leveling_menu.cpp | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 2 +- Marlin/src/lcd/language/language_en.h | 1 + 10 files changed, 136 insertions(+), 9 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/meshviewer.h diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 847073c52e..6edfc81c60 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -62,7 +62,7 @@ #include "../../../feature/host_actions.h" #endif -#if HAS_ONESTEP_LEVELING +#if HAS_MESH || HAS_ONESTEP_LEVELING #include "../../../feature/bedlevel/bedlevel.h" #endif @@ -78,6 +78,10 @@ #include "../../../feature/powerloss.h" #endif +#if HAS_MESH + #include "meshviewer.h" +#endif + #include #include #include @@ -1661,7 +1665,7 @@ void DWIN_MeshLevelingStart() { #endif } -void DWIN_CompletedLeveling() { HMI_ReturnScreen(); } +void DWIN_CompletedLeveling() { DWIN_MeshViewer(); } #if HAS_MESH void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { @@ -1921,6 +1925,17 @@ void DWIN_Redraw_screen() { #endif // ADVANCED_PAUSE_FEATURE +#if HAS_MESH + void DWIN_MeshViewer() { + if (!leveling_is_valid()) + DWIN_Popup_Continue(ICON_BLTouch, "Mesh viewer", "No valid mesh"); + else { + HMI_SaveProcessID(WaitResponse); + MeshViewer.Draw(); + } + } +#endif + void HMI_LockScreen() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -3185,6 +3200,9 @@ void Draw_AdvancedSettings_Menu() { #if ENABLED(SOUND_MENU_ITEM) ADDMENUITEM(ICON_Sound, F("Enable Sound"), onDrawEnableSound, SetEnableSound); #endif + #if HAS_MESH + ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); + #endif ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); } CurrentMenu->draw(); @@ -3403,6 +3421,7 @@ void Draw_Motion_Menu() { ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); + ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); ADDMENUITEM(ICON_MeshSave, GET_TEXT_F(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); } CurrentMenu->draw(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 8d138df7f7..6b131592a8 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -222,6 +222,9 @@ void DWIN_RebootScreen(); // Utility and extensions void HMI_LockScreen(); void DWIN_LockScreen(const bool flag = true); +#if HAS_MESH + void DWIN_MeshViewer(); +#endif // HMI user control functions void HMI_Menu(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index ce56c98e5b..8cbb66fdf0 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -50,6 +50,7 @@ #define ICON_ManualMesh ICON_HotendTemp #define ICON_MeshNext ICON_Axis #define ICON_MeshSave ICON_WriteEEPROM +#define ICON_MeshViewer ICON_HotendTemp #define ICON_MoveZ0 ICON_HotendTemp #define ICON_Park ICON_Motion #define ICON_PIDcycles ICON_ResumeEEPROM diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp new file mode 100644 index 0000000000..6efc96f21b --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp @@ -0,0 +1,75 @@ +/** + * DWIN Mesh Viewer + * Author: Miguel A. Risco-Castillo + * version: 2.5 + * Date: 2021/09/27 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(DWIN_CREALITY_LCD_ENHANCED, HAS_MESH) + +#include "meshviewer.h" + +#include "../../../core/types.h" +#include "../../marlinui.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin.h" +#include "../../../feature/bedlevel/bedlevel.h" + +MeshViewerClass MeshViewer; + +void MeshViewerClass::Draw() { + const int8_t mx = 30, my = 30; // Margins + const int16_t stx = (DWIN_WIDTH - 2 * mx) / (GRID_MAX_POINTS_X - 1), // Steps + sty = (DWIN_WIDTH - 2 * my) / (GRID_MAX_POINTS_Y - 1); + int8_t zmesh[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], maxz =-127, minz = 127; + #define px(xp) (mx + (xp) * stx) + #define py(yp) (30 + DWIN_WIDTH - my - (yp) * sty) + #define rm(z) ((((z) - minz) * 10 / _MAX(1, (maxz - minz))) + 10) + #define DrawMeshValue(xp, yp, zv) DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(xp) - 12, py(yp) - 6, zv) + #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) + #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(GRID_MAX_POINTS_Y - 1), DWIN_WIDTH - 2 * my) + GRID_LOOP(x, y) { + const float v = Z_VALUES(x,y) * 100; + zmesh[x][y] = v; + NOLESS(maxz, v); + NOMORE(minz, v); + } + Title.ShowCaption(F("Mesh viewer")); + DWINUI::ClearMenuArea(); + DWINUI::Draw_Icon(ICON_Continue_E, 86, 305); + DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(GRID_MAX_POINTS_X - 1), py(GRID_MAX_POINTS_Y - 1)); + LOOP_S_L_N(x, 1, GRID_MAX_POINTS_X - 1) DrawMeshVLine(x); + LOOP_S_L_N(y, 1, GRID_MAX_POINTS_Y - 1) DrawMeshHLine(y); + LOOP_L_N(y, GRID_MAX_POINTS_Y) { + watchdog_refresh(); + LOOP_L_N(x, GRID_MAX_POINTS_X) { + uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); + DWINUI::Draw_FillCircle(color, px(x), py(y), rm(zmesh[x][y])); + DrawMeshValue(x, y, Z_VALUES(x,y)); + } + } + char str_1[6], str_2[6] = ""; + ui.status_printf_P(0, PSTR("Mesh minZ: %s, maxZ: %s"), + dtostrf((float)minz / 100, 1, 2, str_1), + dtostrf((float)maxz / 100, 1, 2, str_2) + ); +} + +#endif // DWIN_CREALITY_LCD_ENHANCED && HAS_MESH diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.h b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h new file mode 100644 index 0000000000..4f7a6ae1d2 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h @@ -0,0 +1,28 @@ +/** + * DWIN Mesh Viewer + * Author: Miguel A. Risco-Castillo + * version: 2.5 + * Date: 2021/09/27 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser 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 Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +class MeshViewerClass { +public: + void Draw(); +}; + +extern MeshViewerClass MeshViewer; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index eccbe8d141..a48987e68d 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -3246,7 +3246,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW: if (draw) - Draw_Menu_Item(row, ICON_Mesh, "Mesh Viewer", nullptr, true); + Draw_Menu_Item(row, ICON_Mesh, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); else { #if ENABLED(AUTO_BED_LEVELING_UBL) if (ubl.storage_slot < 0) { @@ -3319,7 +3319,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW_MESH: if (draw) - Draw_Menu_Item(row, ICON_PrintSize, "Mesh Viewer", nullptr, true); + Draw_Menu_Item(row, ICON_PrintSize, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); else Draw_Menu(MeshViewer); break; @@ -4070,9 +4070,9 @@ const char * CrealityDWINClass::Get_Menu_Title(uint8_t menu) { case InfoMain: return "Info"; #if HAS_MESH case Leveling: return "Leveling"; - case LevelView: return "Mesh View"; + case LevelView: return GET_TEXT_F(MSG_MESH_VIEW); case LevelSettings: return "Leveling Settings"; - case MeshViewer: return "Mesh Viewer"; + case MeshViewer: return GET_TEXT_F(MSG_MESH_VIEW); case LevelManual: return "Manual Tuning"; #endif #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index 2e3472987e..3636b5da6c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -61,7 +61,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .font(font_medium).colors(normal_btn) .tag(2).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) .enabled(ENABLED(HAS_MESH)) - .tag(3).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) + .tag(3).button(SHOW_MESH_POS, GET_TEXT_F(MSG_MESH_VIEW)) .enabled(ENABLED(HAS_MESH)) .tag(4).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) #undef GRID_COLS diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 9bc2f56ab9..05845a9755 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -86,7 +86,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .enabled(ENABLED(HAS_BED_PROBE)) .tag(3).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) .enabled(ENABLED(HAS_MESH)) - .tag(4).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) + .tag(4).button(SHOW_MESH_POS, GET_TEXT_F(MSG_MESH_VIEW)) .enabled(ENABLED(HAS_MESH)) .tag(5).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) .enabled(ENABLED(G26_MESH_VALIDATION)) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 0d883d8d02..2e2597aec4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -145,7 +145,7 @@ namespace Language_en { PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; PROGMEM Language_Str MSG_AXIS_LEVELING = u8"Axis Leveling"; PROGMEM Language_Str MSG_PROBE_BED = u8"Probe Mesh"; - PROGMEM Language_Str MSG_SHOW_MESH = u8"View Mesh"; + PROGMEM Language_Str MSG_MESH_VIEW = u8"View Mesh"; PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test (PLA)"; PROGMEM Language_Str MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index b23d0bfa00..8c7a78cd46 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -157,6 +157,7 @@ namespace Language_en { LSTR MSG_NEXT_CORNER = _UxGT("Next Corner"); LSTR MSG_MESH_EDITOR = _UxGT("Mesh Editor"); LSTR MSG_EDIT_MESH = _UxGT("Edit Mesh"); + LSTR MSG_MESH_VIEW = _UxGT("View Mesh"); LSTR MSG_EDITING_STOPPED = _UxGT("Mesh Editing Stopped"); LSTR MSG_PROBING_POINT = _UxGT("Probing Point"); LSTR MSG_MESH_X = _UxGT("Index X"); From eda8e9c8dddfb93950409092832311a60635c054 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 28 Sep 2021 01:01:32 +0000 Subject: [PATCH 0736/2168] [cron] Bump distribution date (2021-09-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 195d40f6ce..3cfe8510ad 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-27" +//#define STRING_DISTRIBUTION_DATE "2021-09-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d39f82525a..67cfb5d82b 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 "2021-09-27" + #define STRING_DISTRIBUTION_DATE "2021-09-28" #endif /** From 33e0855e2c173680865aaa6c6aa93047d63fc469 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Sep 2021 01:07:51 -0500 Subject: [PATCH 0737/2168] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Handle=20shared?= =?UTF-8?q?=20enable=20pins=20(#22824)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 80 ++----- Marlin/src/MarlinCore.h | 9 - Marlin/src/feature/controllerfan.cpp | 27 +-- Marlin/src/feature/fwretract.cpp | 4 +- Marlin/src/feature/fwretract.h | 2 +- Marlin/src/feature/mmu/mmu.cpp | 3 +- Marlin/src/feature/mmu/mmu2.cpp | 36 +-- Marlin/src/feature/pause.cpp | 4 +- Marlin/src/feature/power.cpp | 22 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/gcode/config/M301.cpp | 7 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 222 +++++++++++++++--- .../src/gcode/feature/fwretract/G10_G11.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/inc/Conditionals_LCD.h | 10 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 3 +- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 3 +- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 7 +- .../lcd/extui/dgus_reloaded/DGUSTxHandler.cpp | 10 +- .../generic/stress_test_screen.cpp | 2 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 3 +- Marlin/src/module/planner.cpp | 70 +++--- Marlin/src/module/probe.cpp | 10 +- Marlin/src/module/settings.cpp | 2 +- Marlin/src/module/stepper.cpp | 131 +++++++++-- Marlin/src/module/stepper.h | 102 ++++++++ 26 files changed, 523 insertions(+), 252 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 280c619ad2..1b9c8885b1 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -81,10 +81,6 @@ #endif #endif -#if ENABLED(EXTENSIBLE_UI) - #include "lcd/extui/ui_api.h" -#endif - #if HAS_ETHERNET #include "feature/ethernet.h" #endif @@ -312,48 +308,6 @@ bool pin_is_protected(const pin_t pin) { #pragma GCC diagnostic pop -void enable_e_steppers() { - #define _ENA_E(N) ENABLE_AXIS_E##N(); - REPEAT(E_STEPPERS, _ENA_E) -} - -void enable_all_steppers() { - TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); - ENABLE_AXIS_X(); - ENABLE_AXIS_Y(); - ENABLE_AXIS_Z(); - ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki) - ENABLE_AXIS_J(); - ENABLE_AXIS_K(); - enable_e_steppers(); - - TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled()); -} - -void disable_e_steppers() { - #define _DIS_E(N) DISABLE_AXIS_E##N(); - REPEAT(E_STEPPERS, _DIS_E) -} - -void disable_e_stepper(const uint8_t e) { - #define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break; - switch (e) { - REPEAT(E_STEPPERS, _CASE_DIS_E) - } -} - -void disable_all_steppers() { - DISABLE_AXIS_X(); - DISABLE_AXIS_Y(); - DISABLE_AXIS_Z(); - DISABLE_AXIS_I(); - DISABLE_AXIS_J(); - DISABLE_AXIS_K(); - disable_e_steppers(); - - TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); -} - /** * A Print Job exists when the timer is running or SD is printing */ @@ -464,13 +418,13 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this // Individual axes will be disabled if configured - 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_I)) DISABLE_AXIS_I(); - if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J(); - if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K(); - if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); + TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS)); + TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS)); + TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS)); + TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS)); + TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS)); + TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS)); + TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers()); TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); } @@ -689,13 +643,13 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(SWITCHING_EXTRUDER) bool oldstatus; switch (active_extruder) { - default: oldstatus = E0_ENABLE_READ(); ENABLE_AXIS_E0(); break; + default: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 0); stepper.ENABLE_EXTRUDER(0); break; #if E_STEPPERS > 1 - case 2: case 3: oldstatus = E1_ENABLE_READ(); ENABLE_AXIS_E1(); break; + case 2: case 3: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 1); stepper.ENABLE_EXTRUDER(1); break; #if E_STEPPERS > 2 - case 4: case 5: oldstatus = E2_ENABLE_READ(); ENABLE_AXIS_E2(); break; + case 4: case 5: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 2); stepper.ENABLE_EXTRUDER(2); break; #if E_STEPPERS > 3 - case 6: case 7: oldstatus = E3_ENABLE_READ(); ENABLE_AXIS_E3(); break; + case 6: case 7: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 3); stepper.ENABLE_EXTRUDER(3); break; #endif // E_STEPPERS > 3 #endif // E_STEPPERS > 2 #endif // E_STEPPERS > 1 @@ -704,7 +658,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { bool oldstatus; switch (active_extruder) { default: - #define _CASE_EN(N) case N: oldstatus = E##N##_ENABLE_READ(); ENABLE_AXIS_E##N(); break; + #define _CASE_EN(N) case N: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, N); stepper.ENABLE_EXTRUDER(N); break; REPEAT(E_STEPPERS, _CASE_EN); } #endif @@ -718,17 +672,17 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(SWITCHING_EXTRUDER) switch (active_extruder) { - default: oldstatus = E0_ENABLE_WRITE(oldstatus); break; + default: if (oldstatus) stepper.ENABLE_EXTRUDER(0); else stepper.DISABLE_EXTRUDER(0); break; #if E_STEPPERS > 1 - case 2: case 3: oldstatus = E1_ENABLE_WRITE(oldstatus); break; + case 2: case 3: if (oldstatus) stepper.ENABLE_EXTRUDER(1); else stepper.DISABLE_EXTRUDER(1); break; #if E_STEPPERS > 2 - case 4: case 5: oldstatus = E2_ENABLE_WRITE(oldstatus); break; + case 4: case 5: if (oldstatus) stepper.ENABLE_EXTRUDER(2); else stepper.DISABLE_EXTRUDER(2); break; #endif // E_STEPPERS > 2 #endif // E_STEPPERS > 1 } #else // !SWITCHING_EXTRUDER switch (active_extruder) { - #define _CASE_RESTORE(N) case N: E##N##_ENABLE_WRITE(oldstatus); break; + #define _CASE_RESTORE(N) case N: if (oldstatus) stepper.ENABLE_EXTRUDER(N); else stepper.DISABLE_EXTRUDER(N); break; REPEAT(E_STEPPERS, _CASE_RESTORE); } #endif // !SWITCHING_EXTRUDER @@ -940,7 +894,7 @@ void minkill(const bool steppers_off/*=false*/) { TERN_(HAS_CUTTER, cutter.kill()); // Reiterate cutter shutdown // Power off all steppers (for M112) or just the E steppers - steppers_off ? disable_all_steppers() : disable_e_steppers(); + steppers_off ? stepper.disable_all_steppers() : stepper.disable_e_steppers(); TERN_(PSU_CONTROL, powerManager.power_off()); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 6428b77398..c3698d616d 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -38,15 +38,6 @@ inline void idle_no_sleep() { idle(true); } extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed #endif -/** - * The axis order in all axis related arrays is X, Y, Z, E - */ -void enable_e_steppers(); -void enable_all_steppers(); -void disable_e_stepper(const uint8_t e); -void disable_e_steppers(); -void disable_all_steppers(); - void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false); void minkill(const bool steppers_off=false); diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 35f567fa8f..5efddbb111 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -25,7 +25,7 @@ #if ENABLED(USE_CONTROLLER_FAN) #include "controllerfan.h" -#include "../module/stepper/indirection.h" +#include "../module/stepper.h" #include "../module/temperature.h" ControllerFan controllerFan; @@ -54,33 +54,12 @@ void ControllerFan::update() { if (ELAPSED(ms, nextMotorCheck)) { nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s - #define MOTOR_IS_ON(A,B) (A##_ENABLE_READ() == bool(B##_ENABLE_ON)) - #define _OR_ENABLED_E(N) || MOTOR_IS_ON(E##N,E) - - const bool motor_on = ( - ( DISABLED(CONTROLLER_FAN_IGNORE_Z) && - ( MOTOR_IS_ON(Z,Z) - || TERN0(HAS_Z2_ENABLE, MOTOR_IS_ON(Z2,Z)) - || TERN0(HAS_Z3_ENABLE, MOTOR_IS_ON(Z3,Z)) - || TERN0(HAS_Z4_ENABLE, MOTOR_IS_ON(Z4,Z)) - ) - ) || ( - DISABLED(CONTROLLER_FAN_USE_Z_ONLY) && - ( MOTOR_IS_ON(X,X) || MOTOR_IS_ON(Y,Y) - || TERN0(HAS_X2_ENABLE, MOTOR_IS_ON(X2,X)) - || TERN0(HAS_Y2_ENABLE, MOTOR_IS_ON(Y2,Y)) - #if E_STEPPERS - REPEAT(E_STEPPERS, _OR_ENABLED_E) - #endif - ) - ) - ); - // If any triggers for the controller fan are true... // - At least one stepper driver is enabled // - The heated bed is enabled // - TEMP_SENSOR_BOARD is reporting >= CONTROLLER_FAN_MIN_BOARD_TEMP - if ( motor_on + const ena_mask_t axis_mask = TERN(CONTROLLER_FAN_USE_Z_ONLY, _BV(Z_AXIS), ~TERN0(CONTROLLER_FAN_IGNORE_Z, _BV(Z_AXIS))); + if ( (stepper.axis_enabled.bits & axis_mask) || TERN0(HAS_HEATED_BED, thermalManager.temp_bed.soft_pwm_amount > 0) || TERN0(HAS_CONTROLLER_FAN_MIN_BOARD_TEMP, thermalManager.wholeDegBoard() >= CONTROLLER_FAN_MIN_BOARD_TEMP) ) lastMotorOn = ms; //... set time to NOW so the fan will turn on diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 26817b9ed2..4077d8d1c2 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -75,7 +75,7 @@ void FWRetract::reset() { LOOP_L_N(i, EXTRUDERS) { retracted[i] = false; - TERN_(HAS_MULTI_EXTRUDER, retracted_swap[i] = false); + E_TERN_(retracted_swap[i] = false); current_retract[i] = 0.0; } } @@ -91,7 +91,7 @@ void FWRetract::reset() { * Note: Auto-retract will apply the set Z hop in addition to any Z hop * included in the G-code. Use M207 Z0 to to prevent double hop. */ -void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping/*=false*/)) { +void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) { // Prevent two retracts or recovers in a row if (retracted[active_extruder] == retracting) return; diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index 9b0ff19c8b..d6d0432e3a 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -74,7 +74,7 @@ public: #endif } - static void retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping = false)); + static void retract(const bool retracting E_OPTARG(bool swapping=false)); static void M207_report(); static void M207(); diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp index 7189723138..6340f3c301 100644 --- a/Marlin/src/feature/mmu/mmu.cpp +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -26,6 +26,7 @@ #include "../MarlinCore.h" #include "../module/planner.h" +#include "../module/stepper.h" void mmu_init() { SET_OUTPUT(E_MUX0_PIN); @@ -35,7 +36,7 @@ void mmu_init() { void select_multiplexed_stepper(const uint8_t e) { planner.synchronize(); - disable_e_steppers(); + stepper.disable_e_steppers(); WRITE(E_MUX0_PIN, TEST(e, 0) ? HIGH : LOW); WRITE(E_MUX1_PIN, TEST(e, 1) ? HIGH : LOW); WRITE(E_MUX2_PIN, TEST(e, 2) ? HIGH : LOW); diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index cf03eaf7f6..3727c8c86d 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -35,7 +35,7 @@ MMU2 mmu2; #include "../../libs/nozzle.h" #include "../../module/temperature.h" #include "../../module/planner.h" -#include "../../module/stepper/indirection.h" +#include "../../module/stepper.h" #include "../../MarlinCore.h" #if ENABLED(HOST_PROMPT_SUPPORT) @@ -486,7 +486,7 @@ static void mmu2_not_responding() { if (index != extruder) { - DISABLE_AXIS_E0(); + stepper.disable_extruder(); ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); command(MMU_CMD_T0 + index); @@ -495,7 +495,7 @@ static void mmu2_not_responding() { if (load_to_gears()) { extruder = index; // filament change is finished active_extruder = 0; - ENABLE_AXIS_E0(); + stepper.enable_extruder(); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); } ui.reset_status(); @@ -531,13 +531,13 @@ static void mmu2_not_responding() { #if ENABLED(MMU2_MENUS) planner.synchronize(); const uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); + stepper.disable_extruder(); command(MMU_CMD_T0 + index); manage_response(true, true); if (load_to_gears()) { mmu_loop(); - ENABLE_AXIS_E0(); + stepper.enable_extruder(); extruder = index; active_extruder = 0; } @@ -566,7 +566,7 @@ static void mmu2_not_responding() { set_runout_valid(false); if (index != extruder) { - DISABLE_AXIS_E0(); + stepper.disable_extruder(); if (FILAMENT_PRESENT()) { DEBUG_ECHOLNPGM("Unloading\n"); mmu_loading_flag = false; @@ -582,7 +582,7 @@ static void mmu2_not_responding() { extruder = index; active_extruder = 0; - ENABLE_AXIS_E0(); + stepper.enable_extruder(); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); ui.reset_status(); @@ -620,14 +620,14 @@ static void mmu2_not_responding() { #if ENABLED(MMU2_MENUS) planner.synchronize(); uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); + stepper.disable_extruder(); command(MMU_CMD_T0 + index); manage_response(true, true); mmu_continue_loading(); command(MMU_CMD_C0); mmu_loop(); - ENABLE_AXIS_E0(); + stepper.enable_extruder(); extruder = index; active_extruder = 0; #else @@ -670,14 +670,14 @@ static void mmu2_not_responding() { set_runout_valid(false); if (index != extruder) { - DISABLE_AXIS_E0(); + stepper.disable_extruder(); ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); command(MMU_CMD_T0 + index); manage_response(true, true); command(MMU_CMD_C0); extruder = index; //filament change is finished active_extruder = 0; - ENABLE_AXIS_E0(); + stepper.enable_extruder(); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder); ui.reset_status(); } @@ -714,13 +714,13 @@ static void mmu2_not_responding() { #if ENABLED(MMU2_MENUS) planner.synchronize(); uint8_t index = mmu2_choose_filament(); - DISABLE_AXIS_E0(); + stepper.disable_extruder(); command(MMU_CMD_T0 + index); manage_response(true, true); command(MMU_CMD_C0); mmu_loop(); - ENABLE_AXIS_E0(); + stepper.enable_extruder(); extruder = index; active_extruder = 0; #else @@ -912,7 +912,7 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { return false; } - DISABLE_AXIS_E0(); + stepper.disable_extruder(); command(MMU_CMD_T0 + index); manage_response(true, true); @@ -950,7 +950,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { LCD_MESSAGEPGM(MSG_MMU2_EJECTING_FILAMENT); - ENABLE_AXIS_E0(); + stepper.enable_extruder(); current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; line_to_current_position(MMM_TO_MMS(2500)); planner.synchronize(); @@ -979,7 +979,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { BUZZ(200, 404); - DISABLE_AXIS_E0(); + stepper.disable_extruder(); return true; } @@ -1016,7 +1016,7 @@ bool MMU2::unload() { void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { planner.synchronize(); - ENABLE_AXIS_E0(); + stepper.enable_extruder(); const E_Step* step = sequence; @@ -1034,7 +1034,7 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { step++; } - DISABLE_AXIS_E0(); + stepper.disable_extruder(); } #endif // HAS_PRUSA_MMU2 diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 24cd52e548..d54326116e 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -302,8 +302,8 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load * send current back to their board, potentially frying it. */ inline void disable_active_extruder() { - #if HAS_E_STEPPER_ENABLE - disable_e_stepper(active_extruder); + #if HAS_EXTRUDERS + stepper.DISABLE_EXTRUDER(active_extruder); safe_delay(100); #endif } diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index b86249fbc0..8116bd2e44 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -27,7 +27,7 @@ #include "../inc/MarlinConfig.h" #include "power.h" -#include "../module/stepper/indirection.h" +#include "../module/stepper.h" #include "../MarlinCore.h" #if ENABLED(PS_OFF_SOUND) @@ -120,6 +120,9 @@ void Power::power_off() { */ bool Power::is_power_needed() { + // If any of the stepper drivers are enabled... + if (stepper.axis_enabled.bits) return true; + if (printJobOngoing() || printingIsPaused()) return true; #if ENABLED(AUTO_POWER_FANS) @@ -140,23 +143,6 @@ void Power::power_off() { if (TERN0(AUTO_POWER_COOLER_FAN, thermalManager.coolerfan_speed)) return true; - // If any of the drivers or the bed are enabled... - if (X_ENABLE_READ() == X_ENABLE_ON || Y_ENABLE_READ() == Y_ENABLE_ON || Z_ENABLE_READ() == Z_ENABLE_ON - #if HAS_X2_ENABLE - || X2_ENABLE_READ() == X_ENABLE_ON - #endif - #if HAS_Y2_ENABLE - || Y2_ENABLE_READ() == Y_ENABLE_ON - #endif - #if HAS_Z2_ENABLE - || Z2_ENABLE_READ() == Z_ENABLE_ON - #endif - #if E_STEPPERS - #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == E_ENABLE_ON - REPEAT(E_STEPPERS, _OR_ENABLED_E) - #endif - ) return true; - #if HAS_HOTEND HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 159121ba45..8db31daa40 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -186,7 +186,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat); TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); - TERN_(HAS_MULTI_EXTRUDER, info.active_extruder = active_extruder); + E_TERN_(info.active_extruder = active_extruder); #if DISABLED(NO_VOLUMETRICS) info.flag.volumetric_enabled = parser.volumetric_enabled; diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp index 19b438309c..db882b3b65 100644 --- a/Marlin/src/gcode/config/M301.cpp +++ b/Marlin/src/gcode/config/M301.cpp @@ -48,10 +48,10 @@ void GcodeSuite::M301() { // multi-extruder PID patch: M301 updates or prints a single extruder's PID values // default behavior (omitting E parameter) is to update for extruder 0 only - int8_t e = parser.byteval('E', -1); // extruder being updated + int8_t e = E_TERN0(parser.byteval('E', -1)); // extruder being updated if (!parser.seen("PID" TERN_(PID_EXTRUSION_SCALING, "CL") TERN_(PID_FAN_SCALING, "F"))) - return M301_report(true, e); + return M301_report(true E_OPTARG(e)); if (e == -1) e = 0; @@ -78,8 +78,9 @@ void GcodeSuite::M301() { SERIAL_ERROR_MSG(STR_INVALID_EXTRUDER); } -void GcodeSuite::M301_report(const bool forReplay/*=true*/, const int8_t eindex/*=-1*/) { +void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t eindex/*=-1*/)) { report_heading(forReplay, PSTR(STR_HOTEND_PID)); + IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr int8_t eindex = -1); HOTEND_LOOP() { if (e == eindex || eindex == -1) { report_echo_start(forReplay); diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index e6e0f033ec..82df20ac45 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -29,29 +29,186 @@ #include "../../feature/bedlevel/bedlevel.h" #endif -/** - * M17: Enable stepper motors - */ -void GcodeSuite::M17() { - if (parser.seen_axis()) { - LOGICAL_AXIS_CODE( - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), - if (parser.seen_test('X')) ENABLE_AXIS_X(), - if (parser.seen_test('Y')) ENABLE_AXIS_Y(), - if (parser.seen_test('Z')) ENABLE_AXIS_Z(), - if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(), - if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(), - if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K() - ); +#define DEBUG_OUT ENABLED(MARLIN_DEV_MODE) +#include "../../core/debug_out.h" +#include "../../libs/hex_print.h" + +inline axis_flags_t selected_axis_bits() { + axis_flags_t selected{0}; + #if HAS_EXTRUDERS + if (parser.seen('E')) { + if (E_TERN0(parser.has_value())) { + const uint8_t e = parser.value_int(); + if (e < EXTRUDERS) + selected.bits = _BV(INDEX_OF_AXIS(E_AXIS, e)); + } + else + selected.bits = selected.e_bits(); + } + #endif + selected.bits |= LINEAR_AXIS_GANG( + (parser.seen_test('X') << X_AXIS), + | (parser.seen_test('Y') << Y_AXIS), + | (parser.seen_test('Z') << Z_AXIS), + | (parser.seen_test(AXIS4_NAME) << I_AXIS), + | (parser.seen_test(AXIS5_NAME) << J_AXIS), + | (parser.seen_test(AXIS6_NAME) << K_AXIS) + ); + return selected; +} + +// Enable specified axes and warn about other affected axes +void do_enable(const axis_flags_t to_enable) { + const ena_mask_t was_enabled = stepper.axis_enabled.bits, + shall_enable = to_enable.bits & ~was_enabled; + + DEBUG_ECHOLNPGM("Now Enabled: ", hex_word(stepper.axis_enabled.bits), " Enabling: ", hex_word(to_enable.bits), " | ", shall_enable); + + if (!shall_enable) return; // All specified axes already enabled? + + ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap + + // Enable all flagged axes + LOOP_LINEAR_AXES(a) { + if (TEST(shall_enable, a)) { + stepper.enable_axis(AxisEnum(a)); // Mark and enable the requested axis + DEBUG_ECHOLNPGM("Enabled ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits)); + also_enabled |= enable_overlap[a]; + } } - else { - LCD_MESSAGEPGM(MSG_NO_MOVE); - enable_all_steppers(); + #if HAS_EXTRUDERS + LOOP_L_N(e, EXTRUDERS) { + const uint8_t a = INDEX_OF_AXIS(E_AXIS, e); + if (TEST(shall_enable, a)) { + stepper.ENABLE_EXTRUDER(e); + DEBUG_ECHOLNPGM("Enabled E", AS_DIGIT(e), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... ", hex_word(stepper.axis_enabled.bits)); + also_enabled |= enable_overlap[a]; + } + } + #endif + + if ((also_enabled &= ~(shall_enable | was_enabled))) { + SERIAL_CHAR('('); + LOOP_LINEAR_AXES(a) if (TEST(also_enabled, a)) SERIAL_CHAR(axis_codes[a], ' '); + #if HAS_EXTRUDERS + #define _EN_ALSO(N) if (TEST(also_enabled, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR('E', '0' + N, ' '); + REPEAT(EXTRUDERS, _EN_ALSO) + #endif + SERIAL_ECHOLNPGM("also enabled)"); } + + DEBUG_ECHOLNPGM("Enabled Now: ", hex_word(stepper.axis_enabled.bits)); } /** - * M18, M84: Disable stepper motors + * M17: Enable stepper motor power for one or more axes. + * Print warnings for axes that share an ENABLE_PIN. + * + * Examples: + * + * M17 XZ ; Enable X and Z axes + * M17 E ; Enable all E steppers + * M17 E1 ; Enable just the E1 stepper + */ +void GcodeSuite::M17() { + if (parser.seen_axis()) { + if (any_enable_overlap()) + do_enable(selected_axis_bits()); + else { + #if HAS_EXTRUDERS + if (parser.seen('E')) { + if (parser.has_value()) { + const uint8_t e = parser.value_int(); + if (e < EXTRUDERS) stepper.ENABLE_EXTRUDER(e); + } + else + stepper.enable_e_steppers(); + } + #endif + LINEAR_AXIS_CODE( + if (parser.seen_test('X')) stepper.enable_axis(X_AXIS), + if (parser.seen_test('Y')) stepper.enable_axis(Y_AXIS), + if (parser.seen_test('Z')) stepper.enable_axis(Z_AXIS), + if (parser.seen_test(AXIS4_NAME)) stepper.enable_axis(I_AXIS), + if (parser.seen_test(AXIS5_NAME)) stepper.enable_axis(J_AXIS), + if (parser.seen_test(AXIS6_NAME)) stepper.enable_axis(K_AXIS) + ); + } + } + else { + LCD_MESSAGEPGM(MSG_NO_MOVE); + stepper.enable_all_steppers(); + } +} + +void try_to_disable(const axis_flags_t to_disable) { + ena_mask_t still_enabled = to_disable.bits & stepper.axis_enabled.bits; + + DEBUG_ECHOLNPGM("Enabled: ", hex_word(stepper.axis_enabled.bits), " To Disable: ", hex_word(to_disable.bits), " | ", hex_word(still_enabled)); + + if (!still_enabled) return; + + // Attempt to disable all flagged axes + LOOP_LINEAR_AXES(a) + if (TEST(to_disable.bits, a)) { + DEBUG_ECHOPGM("Try to disable ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... "); + if (stepper.disable_axis(AxisEnum(a))) { // Mark the requested axis and request to disable + DEBUG_ECHOPGM("OK"); + still_enabled &= ~(_BV(a) | enable_overlap[a]); // If actually disabled, clear one or more tracked bits + } + else + DEBUG_ECHOPGM("OVERLAP"); + DEBUG_ECHOLNPGM(" ... still_enabled=", hex_word(still_enabled)); + } + #if HAS_EXTRUDERS + LOOP_L_N(e, EXTRUDERS) { + const uint8_t a = INDEX_OF_AXIS(E_AXIS, e); + if (TEST(to_disable.bits, a)) { + DEBUG_ECHOPGM("Try to disable E", AS_DIGIT(e), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... "); + if (stepper.DISABLE_EXTRUDER(e)) { + DEBUG_ECHOPGM("OK"); + still_enabled &= ~(_BV(a) | enable_overlap[a]); + } + else + DEBUG_ECHOPGM("OVERLAP"); + DEBUG_ECHOLNPGM(" ... still_enabled=", hex_word(still_enabled)); + } + } + #endif + + auto overlap_warning = [](const ena_mask_t axis_bits) { + SERIAL_ECHOPGM(" not disabled. Shared with"); + LOOP_LINEAR_AXES(a) if (TEST(axis_bits, a)) SERIAL_CHAR(' ', axis_codes[a]); + #if HAS_EXTRUDERS + #define _EN_STILLON(N) if (TEST(axis_bits, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR(' ', 'E', '0' + N); + REPEAT(EXTRUDERS, _EN_STILLON) + #endif + SERIAL_ECHOLNPGM("."); + }; + + // If any of the requested axes are still enabled, give a warning + LOOP_LINEAR_AXES(a) { + if (TEST(still_enabled, a)) { + SERIAL_CHAR(axis_codes[a]); + overlap_warning(stepper.axis_enabled.bits & enable_overlap[a]); + } + } + #if HAS_EXTRUDERS + LOOP_L_N(e, EXTRUDERS) { + const uint8_t a = INDEX_OF_AXIS(E_AXIS, e); + if (TEST(still_enabled, a)) { + SERIAL_CHAR('E', '0' + e); + overlap_warning(stepper.axis_enabled.bits & enable_overlap[a]); + } + } + #endif + + DEBUG_ECHOLNPGM("Enabled Now: ", hex_word(stepper.axis_enabled.bits)); +} + +/** + * M18, M84: Disable stepper motor power for one or more axes. + * Print warnings for axes that share an ENABLE_PIN. */ void GcodeSuite::M18_M84() { if (parser.seenval('S')) { @@ -61,15 +218,26 @@ void GcodeSuite::M18_M84() { else { if (parser.seen_axis()) { planner.synchronize(); - LOGICAL_AXIS_CODE( - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), - if (parser.seen_test('X')) DISABLE_AXIS_X(), - if (parser.seen_test('Y')) DISABLE_AXIS_Y(), - if (parser.seen_test('Z')) DISABLE_AXIS_Z(), - if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(), - if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(), - if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K() - ); + if (any_enable_overlap()) + try_to_disable(selected_axis_bits()); + else { + #if HAS_EXTRUDERS + if (parser.seen('E')) { + if (E_TERN0(parser.has_value())) + stepper.DISABLE_EXTRUDER(parser.value_int()); + else + stepper.disable_e_steppers(); + } + #endif + LINEAR_AXIS_CODE( + if (parser.seen_test('X')) stepper.disable_axis(X_AXIS), + if (parser.seen_test('Y')) stepper.disable_axis(Y_AXIS), + if (parser.seen_test('Z')) stepper.disable_axis(Z_AXIS), + if (parser.seen_test(AXIS4_NAME)) stepper.disable_axis(I_AXIS), + if (parser.seen_test(AXIS5_NAME)) stepper.disable_axis(J_AXIS), + if (parser.seen_test(AXIS6_NAME)) stepper.disable_axis(K_AXIS) + ); + } } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp index 35330fe0ac..1889f83d62 100644 --- a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp +++ b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp @@ -32,7 +32,7 @@ * G10 - Retract filament according to settings of M207 * TODO: Handle 'G10 P' for tool settings and 'G10 L' for workspace settings */ -void GcodeSuite::G10() { fwretract.retract(true OPTARG(HAS_MULTI_EXTRUDER, parser.boolval('S'))); } +void GcodeSuite::G10() { fwretract.retract(true E_OPTARG(parser.boolval('S'))); } /** * G11 - Recover filament according to settings of M208 diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index a7fc7ff990..4a3c865a4f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -879,7 +879,7 @@ private: #if ENABLED(PIDTEMP) static void M301(); - static void M301_report(const bool forReplay=true, const int8_t eindex=-1); + static void M301_report(const bool forReplay=true E_OPTARG(const int8_t eindex=-1)); #endif #if ENABLED(PREVENT_COLD_EXTRUSION) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 381a0827e1..99b360f9f0 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -587,6 +587,8 @@ * HOTENDS - Number of hotends, whether connected or separate * E_STEPPERS - Number of actual E stepper motors * E_MANUAL - Number of E steppers for LCD move options + * + * These defines must be simple constants for use in REPEAT, etc. */ #if EXTRUDERS #define HAS_EXTRUDERS 1 @@ -605,9 +607,14 @@ #undef DISABLE_E #endif +#define E_OPTARG(N) OPTARG(HAS_MULTI_EXTRUDER, N) +#define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) +#define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) + #if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 #define E_STEPPERS 2 + #define E_MANUAL 1 #elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS @@ -637,7 +644,8 @@ #elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 - #define E_STEPPERS 1 + #define E_STEPPERS 1 + #define E_MANUAL 1 #endif diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 42364f2890..1b572367f2 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -37,6 +37,7 @@ #include "FileNavigator.h" #include "../../../gcode/queue.h" +#include "../../../module/stepper.h" #include "../../../sd/cardreader.h" #include "../../../libs/numtostr.h" #include "../../../MarlinCore.h" @@ -665,7 +666,7 @@ void ChironTFT::PanelAction(uint8_t req) { case 19: // A19 Motors off if (!isPrinting()) { - disable_all_steppers(); // from marlincore.h + stepper.disable_all_steppers(); SendtoTFTLN(AC_msg_ready); } break; diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 4f51e04c21..e07e377dfc 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -27,6 +27,7 @@ #include "../ui_api.h" #include "../../../libs/numtostr.h" +#include "../../../module/stepper.h" // for disable_all_steppers #include "../../../module/motion.h" // for quickstop_stepper, A20 read printing speed, feedrate_percentage #include "../../../MarlinCore.h" // for disable_steppers #include "../../../inc/MarlinConfig.h" @@ -738,7 +739,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { case 19: // A19 stop stepper drivers - sent on stop extrude command and on turn motors off command if (!isPrinting()) { quickstop_stepper(); - disable_all_steppers(); + stepper.disable_all_steppers(); } SENDLINE_PGM(""); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 42731cd866..8567e5c0e7 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -33,6 +33,7 @@ #include "../../../core/language.h" #include "../../../module/temperature.h" #include "../../../module/printcounter.h" +#include "../../../module/stepper.h" #include "../../../gcode/queue.h" #if ENABLED(ADVANCED_PAUSE_FEATURE) #include "../../../feature/pause.h" @@ -375,10 +376,10 @@ void DGUSRxHandler::Steppers(DGUS_VP &vp, void *data_ptr) { switch (control) { case DGUS_Data::Control::ENABLE: - enable_all_steppers(); + stepper.enable_all_steppers(); break; case DGUS_Data::Control::DISABLE: - disable_all_steppers(); + stepper.disable_all_steppers(); break; } @@ -553,7 +554,7 @@ void DGUSRxHandler::FilamentSelect(DGUS_VP &vp, void *data_ptr) { default: return; case DGUS_Data::Extruder::CURRENT: case DGUS_Data::Extruder::E0: - TERN_(HAS_MULTI_EXTRUDER, case DGUS_Data::Extruder::E1:) + E_TERN_(case DGUS_Data::Extruder::E1:) dgus_screen_handler.filament_extruder = extruder; break; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index b419428fbc..6c14745904 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -286,14 +286,8 @@ void DGUSTxHandler::TempMax(DGUS_VP &vp) { } void DGUSTxHandler::StepperStatus(DGUS_VP &vp) { - if (X_ENABLE_READ() == X_ENABLE_ON - && Y_ENABLE_READ() == Y_ENABLE_ON - && Z_ENABLE_READ() == Z_ENABLE_ON) { - dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::ENABLED)); - } - else { - dgus_display.Write((uint16_t)vp.addr, Swap16((uint16_t)DGUS_Data::Status::DISABLED)); - } + const bool motor_on = stepper.axis_enabled.bits & (_BV(LINEAR_AXES) - 1); + dgus_display.Write((uint16_t)vp.addr, Swap16(uint16_t(motor_on ? DGUS_Data::Status::ENABLED : DGUS_Data::Status::DISABLED))); } void DGUSTxHandler::StepIcons(DGUS_VP &vp) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp index 6f32bf06d7..ab1f96a399 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp @@ -125,7 +125,7 @@ void StressTestScreen::onIdle() { injectCommands_P(PSTR( "G0 X100 Y100 Z100 F6000\n" "T0\nG4 S1" - TERN_(HAS_MULTI_EXTRUDER, "\nT1\nG4 S1") + E_TERN_("\nT1\nG4 S1") "\nG0 X150 Y150 Z150" )); } diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 50423db4fd..c4e0e66a39 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -33,6 +33,7 @@ #include "../../../MarlinCore.h" #include "../../../feature/pause.h" +#include "../../../module/stepper.h" #include "../../../gcode/queue.h" #include "../../../libs/numtostr.h" #include "../../../sd/cardreader.h" @@ -536,7 +537,7 @@ void NextionTFT::PanelAction(uint8_t req) { case 57: // Disable Motors if (!isPrinting()) { - disable_all_steppers(); // from marlincore.h + stepper.disable_all_steppers(); SEND_TXT("tmppage.M117", "Motors disabled"); } break; diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index f22a99316f..c6edfb835e 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1375,13 +1375,13 @@ void Planner::check_axes_activity() { // Disable inactive axes // LOGICAL_AXIS_CODE( - if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(), - if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(), - if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(), - if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(), - if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(), - if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(), - if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K() + if (TERN0(DISABLE_E, !axis_active.e)) stepper.disable_e_steppers(), + if (TERN0(DISABLE_X, !axis_active.x)) stepper.disable_axis(X_AXIS), + if (TERN0(DISABLE_Y, !axis_active.y)) stepper.disable_axis(Y_AXIS), + if (TERN0(DISABLE_Z, !axis_active.z)) stepper.disable_axis(Z_AXIS), + if (TERN0(DISABLE_I, !axis_active.i)) stepper.disable_axis(I_AXIS), + if (TERN0(DISABLE_J, !axis_active.j)) stepper.disable_axis(J_AXIS), + if (TERN0(DISABLE_K, !axis_active.k)) stepper.disable_axis(K_AXIS) ); // @@ -1707,7 +1707,7 @@ float Planner::triggered_position_mm(const AxisEnum axis) { void Planner::finish_and_disable() { while (has_blocks_queued() || cleaning_buffer_counter) idle(); - disable_all_steppers(); + stepper.disable_all_steppers(); } /** @@ -2144,7 +2144,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->e_to_p_pressure = baricuda_e_to_p_pressure; #endif - TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); + E_TERN_(block->extruder = extruder); #if ENABLED(AUTO_POWER_CONTROL) if (LINEAR_AXIS_GANG( @@ -2160,43 +2160,43 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Enable active axes #if EITHER(CORE_IS_XY, MARKFORGED_XY) if (block->steps.a || block->steps.b) { - ENABLE_AXIS_X(); - ENABLE_AXIS_Y(); + stepper.enable_axis(X_AXIS); + stepper.enable_axis(Y_AXIS); } #if DISABLED(Z_LATE_ENABLE) - if (block->steps.z) ENABLE_AXIS_Z(); + if (block->steps.z) stepper.enable_axis(Z_AXIS); #endif #elif CORE_IS_XZ if (block->steps.a || block->steps.c) { - ENABLE_AXIS_X(); - ENABLE_AXIS_Z(); + stepper.enable_axis(X_AXIS); + stepper.enable_axis(Z_AXIS); } - if (block->steps.y) ENABLE_AXIS_Y(); + if (block->steps.y) stepper.enable_axis(Y_AXIS); #elif CORE_IS_YZ if (block->steps.b || block->steps.c) { - ENABLE_AXIS_Y(); - ENABLE_AXIS_Z(); + stepper.enable_axis(Y_AXIS); + stepper.enable_axis(Z_AXIS); } - if (block->steps.x) ENABLE_AXIS_X(); + if (block->steps.x) stepper.enable_axis(X_AXIS); #else LINEAR_AXIS_CODE( - if (block->steps.x) ENABLE_AXIS_X(), - if (block->steps.y) ENABLE_AXIS_Y(), - if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(), - if (block->steps.i) ENABLE_AXIS_I(), - if (block->steps.j) ENABLE_AXIS_J(), - if (block->steps.k) ENABLE_AXIS_K() + if (block->steps.x) stepper.enable_axis(X_AXIS), + if (block->steps.y) stepper.enable_axis(Y_AXIS), + if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) stepper.enable_axis(Z_AXIS), + if (block->steps.i) stepper.enable_axis(I_AXIS), + if (block->steps.j) stepper.enable_axis(J_AXIS), + if (block->steps.k) stepper.enable_axis(K_AXIS) ); #endif #if EITHER(IS_CORE, MARKFORGED_XY) #if LINEAR_AXES >= 4 - if (block->steps.i) ENABLE_AXIS_I(); + if (block->steps.i) stepper.enable_axis(I_AXIS); #endif #if LINEAR_AXES >= 5 - if (block->steps.j) ENABLE_AXIS_J(); + if (block->steps.j) stepper.enable_axis(J_AXIS); #endif #if LINEAR_AXES >= 6 - if (block->steps.k) ENABLE_AXIS_K(); + if (block->steps.k) stepper.enable_axis(K_AXIS); #endif #endif @@ -2214,27 +2214,27 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #define ENABLE_ONE_E(N) do{ \ if (E_STEPPER_INDEX(extruder) == N) { \ - ENABLE_AXIS_E##N(); \ + stepper.ENABLE_EXTRUDER(N); \ g_uc_extruder_last_move[N] = (BLOCK_BUFFER_SIZE) * 2; \ if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ - ENABLE_AXIS_E1(); \ + stepper.ENABLE_EXTRUDER(1); \ } \ else if (!g_uc_extruder_last_move[N]) { \ - DISABLE_AXIS_E##N(); \ + stepper.DISABLE_EXTRUDER(N); \ if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ - DISABLE_AXIS_E1(); \ + stepper.DISABLE_EXTRUDER(1); \ } \ }while(0); #else - #define ENABLE_ONE_E(N) ENABLE_AXIS_E##N(); + #define ENABLE_ONE_E(N) stepper.ENABLE_EXTRUDER(N); #endif REPEAT(E_STEPPERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) } - #endif // EXTRUDERS + #endif // HAS_EXTRUDERS if (esteps) NOLESS(fr_mm_s, settings.min_feedrate_mm_s); @@ -3049,7 +3049,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif - TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); + E_TERN_(block->extruder = extruder); block->page_idx = page_idx; @@ -3085,7 +3085,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons // Move buffer head block_buffer_head = next_buffer_head; - enable_all_steppers(); + stepper.enable_all_steppers(); stepper.wake_up(); } diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 3aca68845d..638bb6be81 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -251,17 +251,17 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() void Probe::set_probing_paused(const bool dopause) { TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); - TERN_(PROBING_ESTEPPERS_OFF, if (dopause) disable_e_steppers()); + TERN_(PROBING_ESTEPPERS_OFF, if (dopause) stepper.disable_e_steppers()); #if ENABLED(PROBING_STEPPERS_OFF) && DISABLED(DELTA) static uint8_t old_trusted; if (dopause) { old_trusted = axis_trusted; - DISABLE_AXIS_X(); - DISABLE_AXIS_Y(); + stepper.disable_axis(X_AXIS); + stepper.disable_axis(Y_AXIS); } else { - if (TEST(old_trusted, X_AXIS)) ENABLE_AXIS_X(); - if (TEST(old_trusted, Y_AXIS)) ENABLE_AXIS_Y(); + if (TEST(old_trusted, X_AXIS)) stepper.enable_axis(X_AXIS); + if (TEST(old_trusted, Y_AXIS)) stepper.enable_axis(Y_AXIS); axis_trusted = old_trusted; } #endif diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 921b25dad7..a4b8bb19e6 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3278,7 +3278,7 @@ void MarlinSettings::reset() { // // Tool-changing Parameters // - TERN_(HAS_MULTI_EXTRUDER, gcode.M217_report(forReplay)); + E_TERN_(gcode.M217_report(forReplay)); // // Backlash Compensation diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index aa68ccd4ec..3a1ee39c52 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -123,6 +123,10 @@ Stepper stepper; // Singleton bool L64XX_OK_to_power_up = false; // flag to keep L64xx steppers powered down after a reset or power up #endif +#if ENABLED(AUTO_POWER_CONTROL) + #include "../feature/power.h" +#endif + #if ENABLED(POWER_LOSS_RECOVERY) #include "../feature/powerloss.h" #endif @@ -131,6 +135,10 @@ Stepper stepper; // Singleton #include "../feature/spindle_laser.h" #endif +#if ENABLED(EXTENSIBLE_UI) + #include "../lcd/extui/ui_api.h" +#endif + // public: #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) @@ -145,6 +153,8 @@ Stepper stepper; // Singleton #endif #endif +axis_flags_t Stepper::axis_enabled; // {0} + // private: block_t* Stepper::current_block; // (= nullptr) A pointer to the block currently being traced @@ -473,6 +483,89 @@ xyze_int8_t Stepper::count_direction{0}; #define DIR_WAIT_AFTER() #endif +void Stepper::enable_axis(const AxisEnum axis) { + #define _CASE_ENABLE(N) case N##_AXIS: ENABLE_AXIS_##N(); break; + switch (axis) { + LINEAR_AXIS_CODE( + _CASE_ENABLE(X), _CASE_ENABLE(Y), _CASE_ENABLE(Z), + _CASE_ENABLE(I), _CASE_ENABLE(J), _CASE_ENABLE(K) + ); + default: break; + } + mark_axis_enabled(axis); +} + +bool Stepper::disable_axis(const AxisEnum axis) { + mark_axis_disabled(axis); + // If all the axes that share the enabled bit are disabled + const bool can_disable = can_axis_disable(axis); + if (can_disable) { + #define _CASE_DISABLE(N) case N##_AXIS: DISABLE_AXIS_##N(); break; + switch (axis) { + LINEAR_AXIS_CODE( + _CASE_DISABLE(X), _CASE_DISABLE(Y), _CASE_DISABLE(Z), + _CASE_DISABLE(I), _CASE_DISABLE(J), _CASE_DISABLE(K) + ); + default: break; + } + } + return can_disable; +} + +#if HAS_EXTRUDERS + + void Stepper::enable_extruder(E_TERN_(const uint8_t eindex)) { + IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr uint8_t eindex = 0); + #define _CASE_ENA_E(N) case N: ENABLE_AXIS_E##N(); mark_axis_enabled(E_AXIS E_OPTARG(eindex)); break; + switch (eindex) { + REPEAT(E_STEPPERS, _CASE_ENA_E) + } + } + + bool Stepper::disable_extruder(E_TERN_(const uint8_t eindex)) { + IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr uint8_t eindex = 0); + mark_axis_disabled(E_AXIS E_OPTARG(eindex)); + const bool can_disable = can_axis_disable(E_AXIS E_OPTARG(eindex)); + if (can_disable) { + #define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break; + switch (eindex) { REPEAT(E_STEPPERS, _CASE_DIS_E) } + } + return can_disable; + } + + void Stepper::enable_e_steppers() { + #define _ENA_E(N) ENABLE_EXTRUDER(N); + REPEAT(EXTRUDERS, _ENA_E) + } + + void Stepper::disable_e_steppers() { + #define _DIS_E(N) DISABLE_EXTRUDER(N); + REPEAT(EXTRUDERS, _DIS_E) + } + +#endif + +void Stepper::enable_all_steppers() { + TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); + LINEAR_AXIS_CODE( + enable_axis(X_AXIS), enable_axis(Y_AXIS), enable_axis(Z_AXIS), + enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS) + ); + enable_e_steppers(); + + TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled()); +} + +void Stepper::disable_all_steppers() { + LINEAR_AXIS_CODE( + disable_axis(X_AXIS), disable_axis(Y_AXIS), disable_axis(Z_AXIS), + disable_axis(I_AXIS), disable_axis(J_AXIS), disable_axis(K_AXIS) + ); + disable_e_steppers(); + + TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); +} + /** * Set the stepper direction of each axis * @@ -494,24 +587,12 @@ void Stepper::set_directions() { count_direction[_AXIS(A)] = 1; \ } - #if HAS_X_DIR - SET_STEP_DIR(X); // A - #endif - #if HAS_Y_DIR - SET_STEP_DIR(Y); // B - #endif - #if HAS_Z_DIR - SET_STEP_DIR(Z); // C - #endif - #if HAS_I_DIR - SET_STEP_DIR(I); - #endif - #if HAS_J_DIR - SET_STEP_DIR(J); - #endif - #if HAS_K_DIR - SET_STEP_DIR(K); - #endif + TERN_(HAS_X_DIR, SET_STEP_DIR(X)); // A + TERN_(HAS_Y_DIR, SET_STEP_DIR(Y)); // B + TERN_(HAS_Z_DIR, SET_STEP_DIR(Z)); // C + TERN_(HAS_I_DIR, SET_STEP_DIR(I)); + TERN_(HAS_J_DIR, SET_STEP_DIR(J)); + TERN_(HAS_K_DIR, SET_STEP_DIR(K)); #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -2204,7 +2285,7 @@ uint32_t Stepper::block_phase_isr() { TERN_(MIXING_EXTRUDER, mixer.stepper_setup(current_block->b_color)); - TERN_(HAS_MULTI_EXTRUDER, stepper_extruder = current_block->extruder); + E_TERN_(stepper_extruder = current_block->extruder); // Initialize the trapezoid generator from the current block. #if ENABLED(LIN_ADVANCE) @@ -2227,7 +2308,7 @@ uint32_t Stepper::block_phase_isr() { || current_block->direction_bits != last_direction_bits || TERN(MIXING_EXTRUDER, false, stepper_extruder != last_moved_extruder) ) { - TERN_(HAS_MULTI_EXTRUDER, last_moved_extruder = stepper_extruder); + E_TERN_(last_moved_extruder = stepper_extruder); TERN_(HAS_L64XX, L64XX_OK_to_power_up = true); set_directions(current_block->direction_bits); } @@ -2276,7 +2357,7 @@ uint32_t Stepper::block_phase_isr() { // If delayed Z enable, enable it now. This option will severely interfere with // timing between pulses when chaining motion between blocks, and it could lead // to lost steps in both X and Y axis, so avoid using it unless strictly necessary!! - if (current_block->steps.z) ENABLE_AXIS_Z(); + if (current_block->steps.z) enable_axis(Z_AXIS); #endif // Mark the time_nominal as not calculated yet @@ -2872,7 +2953,7 @@ void Stepper::report_positions() { #if ENABLED(BABYSTEPPING) - #define _ENABLE_AXIS(AXIS) ENABLE_AXIS_## AXIS() + #define _ENABLE_AXIS(A) enable_axis(_AXIS(A)) #define _READ_DIR(AXIS) AXIS ##_DIR_READ() #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true) @@ -3000,8 +3081,10 @@ void Stepper::report_positions() { const bool z_direction = direction ^ BABYSTEP_INVERT_Z; - ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); - ENABLE_AXIS_I(); ENABLE_AXIS_J(); ENABLE_AXIS_K(); + LINEAR_AXIS_CODE( + enable_axis(X_AXIS), enable_axis(Y_AXIS), enable_axis(Z_AXIS), + enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS) + ); DIR_WAIT_BEFORE(); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index ca88d6b6b1..0bfb418d40 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -236,6 +236,71 @@ // Perhaps DISABLE_MULTI_STEPPING should be required with ADAPTIVE_STEP_SMOOTHING. #define MIN_STEP_ISR_FREQUENCY (MAX_STEP_ISR_FREQUENCY_1X / 2) +#define ENABLE_COUNT (LINEAR_AXES + E_STEPPERS) +typedef IF<(ENABLE_COUNT > 8), uint16_t, uint8_t>::type ena_mask_t; + +// Axis flags type, for enabled state or other simple state +typedef struct { + union { + ena_mask_t bits; + struct { + bool LINEAR_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1); + #if HAS_EXTRUDERS + bool LIST_N(EXTRUDERS, E0:1, E1:1, E2:1, E3:1, E4:1, E5:1, E6:1, E7:1); + #endif + }; + }; + constexpr ena_mask_t linear_bits() { return _BV(LINEAR_AXES) - 1; } + constexpr ena_mask_t e_bits() { return (_BV(EXTRUDERS) - 1) << LINEAR_AXES; } +} axis_flags_t; + +// All the stepper enable pins +constexpr pin_t ena_pins[] = { + LINEAR_AXIS_LIST(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN), + LIST_N(E_STEPPERS, E0_ENABLE_PIN, E1_ENABLE_PIN, E2_ENABLE_PIN, E3_ENABLE_PIN, E4_ENABLE_PIN, E5_ENABLE_PIN, E6_ENABLE_PIN, E7_ENABLE_PIN) +}; + +// Index of the axis or extruder element in a combined array +constexpr uint8_t index_of_axis(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + return uint8_t(axis) + (E_TERN0(axis < LINEAR_AXES ? 0 : eindex)); +} +//#define __IAX_N(N,V...) _IAX_##N(V) +//#define _IAX_N(N,V...) __IAX_N(N,V) +//#define _IAX_1(A) index_of_axis(A) +//#define _IAX_2(A,B) index_of_axis(A E_OPTARG(B)) +//#define INDEX_OF_AXIS(V...) _IAX_N(TWO_ARGS(V),V) + +#define INDEX_OF_AXIS(A,V...) index_of_axis(A E_OPTARG(V+0)) + +// Bit mask for a matching enable pin, or 0 +constexpr ena_mask_t ena_same(const uint8_t a, const uint8_t b) { + return ena_pins[a] == ena_pins[b] ? _BV(b) : 0; +} + +// Recursively get the enable overlaps mask for a given linear axis or extruder +constexpr ena_mask_t ena_overlap(const uint8_t a=0, const uint8_t b=0) { + return b >= ENABLE_COUNT ? 0 : (a == b ? 0 : ena_same(a, b)) | ena_overlap(a, b + 1); +} + +// Recursively get whether there's any overlap at all +constexpr bool any_enable_overlap(const uint8_t a=0) { + return a >= ENABLE_COUNT ? false : ena_overlap(a) || any_enable_overlap(a + 1); +} + +// Array of axes that overlap with each +// TODO: Consider cases where >=2 steppers are used by a linear axis or extruder +// (e.g., CoreXY, Dual XYZ, or E with multiple steppers, etc.). +constexpr ena_mask_t enable_overlap[] = { + #define _OVERLAP(N) ena_overlap(INDEX_OF_AXIS(AxisEnum(N))), + REPEAT(LINEAR_AXES, _OVERLAP) + #if HAS_EXTRUDERS + #define _E_OVERLAP(N) ena_overlap(INDEX_OF_AXIS(E_AXIS, N)), + REPEAT(E_STEPPERS, _E_OVERLAP) + #endif +}; + +//static_assert(!any_enable_overlap(), "There is some overlap."); + // // Stepper class definition // @@ -519,6 +584,43 @@ class Stepper { static void refresh_motor_power(); #endif + static axis_flags_t axis_enabled; // Axis stepper(s) ENABLED states + + static inline bool axis_is_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + return TEST(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); + } + static inline void mark_axis_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + SBI(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); + } + static inline void mark_axis_disabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + CBI(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); + } + static inline bool can_axis_disable(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + return !any_enable_overlap() || !(axis_enabled.bits & enable_overlap[INDEX_OF_AXIS(axis, eindex)]); + } + + static void enable_axis(const AxisEnum axis); + static bool disable_axis(const AxisEnum axis); + + #if HAS_EXTRUDERS + static void enable_extruder(E_TERN_(const uint8_t eindex=0)); + static bool disable_extruder(E_TERN_(const uint8_t eindex=0)); + static void enable_e_steppers(); + static void disable_e_steppers(); + #else + static inline void enable_extruder() {} + static inline bool disable_extruder() {} + static inline void enable_e_steppers() {} + static inline void disable_e_steppers() {} + #endif + + #define ENABLE_EXTRUDER(N) enable_extruder(E_TERN_(N)) + #define DISABLE_EXTRUDER(N) disable_extruder(E_TERN_(N)) + #define AXIS_IS_ENABLED(N,V...) axis_is_enabled(N E_OPTARG(#V)) + + static void enable_all_steppers(); + static void disable_all_steppers(); + // Update direction states for all steppers static void set_directions(); From f2ba845dad67c57a6cf1ce5a75bc4f526681ca2d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Sep 2021 02:39:11 -0500 Subject: [PATCH 0738/2168] =?UTF-8?q?=F0=9F=8E=A8=20Condense=20reverse-pro?= =?UTF-8?q?tection=20code?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/stepper_driver_safety.cpp | 142 ++++++------------- 1 file changed, 44 insertions(+), 98 deletions(-) diff --git a/Marlin/src/feature/stepper_driver_safety.cpp b/Marlin/src/feature/stepper_driver_safety.cpp index 991f5a5906..c7da5d2ff7 100644 --- a/Marlin/src/feature/stepper_driver_safety.cpp +++ b/Marlin/src/feature/stepper_driver_safety.cpp @@ -39,7 +39,7 @@ void stepper_driver_backward_check() { OUT_WRITE(SAFE_POWER_PIN, LOW); - #define TEST_BACKWARD(AXIS, BIT) do { \ + #define _TEST_BACKWARD(AXIS, BIT) do { \ SET_INPUT(AXIS##_ENABLE_PIN); \ OUT_WRITE(AXIS##_STEP_PIN, false); \ delay(20); \ @@ -49,57 +49,31 @@ void stepper_driver_backward_check() { } \ }while(0) - #if HAS_X_ENABLE - TEST_BACKWARD(X, 0); - #endif - #if HAS_X2_ENABLE - TEST_BACKWARD(X2, 1); - #endif + #define TEST_BACKWARD(AXIS, BIT) TERN_(HAS_##AXIS##_ENABLE, _TEST_BACKWARD(AXIS, BIT)) - #if HAS_Y_ENABLE - TEST_BACKWARD(Y, 2); - #endif - #if HAS_Y2_ENABLE - TEST_BACKWARD(Y2, 3); - #endif + TEST_BACKWARD(X, 0); + TEST_BACKWARD(X2, 1); - #if HAS_Z_ENABLE - TEST_BACKWARD(Z, 4); - #endif - #if HAS_Z2_ENABLE - TEST_BACKWARD(Z2, 5); - #endif - #if HAS_Z3_ENABLE - TEST_BACKWARD(Z3, 6); - #endif - #if HAS_Z4_ENABLE - TEST_BACKWARD(Z4, 7); - #endif + TEST_BACKWARD(Y, 2); + TEST_BACKWARD(Y2, 3); - #if HAS_E0_ENABLE - TEST_BACKWARD(E0, 8); - #endif - #if HAS_E1_ENABLE - TEST_BACKWARD(E1, 9); - #endif - #if HAS_E2_ENABLE - TEST_BACKWARD(E2, 10); - #endif - #if HAS_E3_ENABLE - TEST_BACKWARD(E3, 11); - #endif - #if HAS_E4_ENABLE - TEST_BACKWARD(E4, 12); - #endif - #if HAS_E5_ENABLE - TEST_BACKWARD(E5, 13); - #endif - #if HAS_E6_ENABLE - TEST_BACKWARD(E6, 14); - #endif - #if HAS_E7_ENABLE - TEST_BACKWARD(E7, 15); - #endif + TEST_BACKWARD(Z, 4); + TEST_BACKWARD(Z2, 5); + TEST_BACKWARD(Z3, 6); + TEST_BACKWARD(Z4, 7); + + TEST_BACKWARD(I, 8); + TEST_BACKWARD(J, 9); + TEST_BACKWARD(K, 10); + + TEST_BACKWARD(E0, 11); + TEST_BACKWARD(E1, 12); + TEST_BACKWARD(E2, 13); + TEST_BACKWARD(E3, 14); + TEST_BACKWARD(E4, 15); + TEST_BACKWARD(E5, 16); + TEST_BACKWARD(E6, 17); + TEST_BACKWARD(E7, 18); if (!axis_plug_backward) WRITE(SAFE_POWER_PIN, HIGH); @@ -113,59 +87,31 @@ void stepper_driver_backward_report() { stepper_driver_backward_error(axis); }; - #define REPORT_BACKWARD(axis, bit) _report_if_backward(PSTR(STRINGIFY(axis)), bit) + #define REPORT_BACKWARD(axis, bit) TERN_(HAS_##axis##_ENABLE, _report_if_backward(PSTR(STRINGIFY(axis)), bit)) - #if HAS_X_ENABLE - REPORT_BACKWARD(X, 0); - #endif - #if HAS_X2_ENABLE - REPORT_BACKWARD(X2, 1); - #endif + REPORT_BACKWARD(X, 0); + REPORT_BACKWARD(X2, 1); - #if HAS_Y_ENABLE - REPORT_BACKWARD(Y, 2); - #endif - #if HAS_Y2_ENABLE - REPORT_BACKWARD(Y2, 3); - #endif + REPORT_BACKWARD(Y, 2); + REPORT_BACKWARD(Y2, 3); - #if HAS_Z_ENABLE - REPORT_BACKWARD(Z, 4); - #endif - #if HAS_Z2_ENABLE - REPORT_BACKWARD(Z2, 5); - #endif - #if HAS_Z3_ENABLE - REPORT_BACKWARD(Z3, 6); - #endif - #if HAS_Z4_ENABLE - REPORT_BACKWARD(Z4, 7); - #endif + REPORT_BACKWARD(Z, 4); + REPORT_BACKWARD(Z2, 5); + REPORT_BACKWARD(Z3, 6); + REPORT_BACKWARD(Z4, 7); - #if HAS_E0_ENABLE - REPORT_BACKWARD(E0, 8); - #endif - #if HAS_E1_ENABLE - REPORT_BACKWARD(E1, 9); - #endif - #if HAS_E2_ENABLE - REPORT_BACKWARD(E2, 10); - #endif - #if HAS_E3_ENABLE - REPORT_BACKWARD(E3, 11); - #endif - #if HAS_E4_ENABLE - REPORT_BACKWARD(E4, 12); - #endif - #if HAS_E5_ENABLE - REPORT_BACKWARD(E5, 13); - #endif - #if HAS_E6_ENABLE - REPORT_BACKWARD(E6, 14); - #endif - #if HAS_E7_ENABLE - REPORT_BACKWARD(E7, 15); - #endif + REPORT_BACKWARD(I, 8); + REPORT_BACKWARD(J, 9); + REPORT_BACKWARD(K, 10); + + REPORT_BACKWARD(E0, 11); + REPORT_BACKWARD(E1, 12); + REPORT_BACKWARD(E2, 13); + REPORT_BACKWARD(E3, 14); + REPORT_BACKWARD(E4, 15); + REPORT_BACKWARD(E5, 16); + REPORT_BACKWARD(E6, 17); + REPORT_BACKWARD(E7, 18); } #endif // HAS_DRIVER_SAFE_POWER_PROTECT From 90b0e16ec0c80ec128b70d20b0b47af8a3281c88 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 29 Sep 2021 00:58:41 +0000 Subject: [PATCH 0739/2168] [cron] Bump distribution date (2021-09-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 3cfe8510ad..412a094b5d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-28" +//#define STRING_DISTRIBUTION_DATE "2021-09-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 67cfb5d82b..bff44d06fe 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 "2021-09-28" + #define STRING_DISTRIBUTION_DATE "2021-09-29" #endif /** From 732e59b412a29c52f5d6ad492743b86fa4cb20e6 Mon Sep 17 00:00:00 2001 From: Malderin <52313714+Malderin@users.noreply.github.com> Date: Wed, 29 Sep 2021 04:20:03 +0300 Subject: [PATCH 0740/2168] =?UTF-8?q?=F0=9F=90=9B=20E3V2=20Mesh=20Viewer?= =?UTF-8?q?=20followup=20(#22850)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index 6e9c88b60b..4d657f2394 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -124,18 +124,22 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { else if (uiCfg.extruderIndex == 0) { uiCfg.curTempType = TERN(HAS_HEATED_BED, 1, 0); } - lv_obj_del(btn_pla); - lv_obj_del(btn_abs); } else if (uiCfg.curTempType == 1) { uiCfg.extruderIndex = 0; uiCfg.curTempType = 0; - lv_obj_del(buttonAdd); - lv_obj_del(buttonDec); } - disp_temp_type(); break; + case ID_P_STEP: + switch (uiCfg.stepHeat) { + case 1: uiCfg.stepHeat = 5; break; + case 5: uiCfg.stepHeat = 10; break; + case 10: uiCfg.stepHeat = 1; break; + default: break; + } + disp_step_heat(); + break; case ID_P_OFF: if (uiCfg.curTempType == 0) { thermalManager.setTargetHotend(0, uiCfg.extruderIndex); From c6ceac9067b21a705f40fbcfc90bbc922945f82e Mon Sep 17 00:00:00 2001 From: Steven Haigh Date: Thu, 30 Sep 2021 02:22:46 +1000 Subject: [PATCH 0741/2168] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Fix=20DWIN=5F?= =?UTF-8?q?CompletedLeveling=20(#22851)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 6edfc81c60..8bb5a155ee 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -1665,7 +1665,7 @@ void DWIN_MeshLevelingStart() { #endif } -void DWIN_CompletedLeveling() { DWIN_MeshViewer(); } +void DWIN_CompletedLeveling() { TERN_(HAS_MESH, DWIN_MeshViewer()); } #if HAS_MESH void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index a48987e68d..6d4f8b0a3a 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -3246,7 +3246,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW: if (draw) - Draw_Menu_Item(row, ICON_Mesh, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); + Draw_Menu_Item(row, ICON_Mesh, GET_TEXT(MSG_MESH_VIEW), nullptr, true); else { #if ENABLED(AUTO_BED_LEVELING_UBL) if (ubl.storage_slot < 0) { @@ -3319,7 +3319,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW_MESH: if (draw) - Draw_Menu_Item(row, ICON_PrintSize, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); + Draw_Menu_Item(row, ICON_PrintSize, GET_TEXT(MSG_MESH_VIEW), nullptr, true); else Draw_Menu(MeshViewer); break; @@ -4070,9 +4070,9 @@ const char * CrealityDWINClass::Get_Menu_Title(uint8_t menu) { case InfoMain: return "Info"; #if HAS_MESH case Leveling: return "Leveling"; - case LevelView: return GET_TEXT_F(MSG_MESH_VIEW); + case LevelView: return GET_TEXT(MSG_MESH_VIEW); case LevelSettings: return "Leveling Settings"; - case MeshViewer: return GET_TEXT_F(MSG_MESH_VIEW); + case MeshViewer: return GET_TEXT(MSG_MESH_VIEW); case LevelManual: return "Manual Tuning"; #endif #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE From d3ed21b10eed717bdeeb210502082655d50488bf Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 30 Sep 2021 01:05:47 +0000 Subject: [PATCH 0742/2168] [cron] Bump distribution date (2021-09-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 412a094b5d..e087e4f8bc 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-29" +//#define STRING_DISTRIBUTION_DATE "2021-09-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bff44d06fe..b1ffde547e 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 "2021-09-29" + #define STRING_DISTRIBUTION_DATE "2021-09-30" #endif /** From ea0169f2bcd3de2fe3b99bceb0f9dd34d85f3322 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 1 Oct 2021 01:05:30 +0000 Subject: [PATCH 0743/2168] [cron] Bump distribution date (2021-10-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e087e4f8bc..6aeb8bb443 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-09-30" +//#define STRING_DISTRIBUTION_DATE "2021-10-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b1ffde547e..796be9d41b 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 "2021-09-30" + #define STRING_DISTRIBUTION_DATE "2021-10-01" #endif /** From e27b1e5d58113dc1bad900701762ec147e573703 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 2 Oct 2021 01:00:08 +0000 Subject: [PATCH 0744/2168] [cron] Bump distribution date (2021-10-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6aeb8bb443..b86aa71eff 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-01" +//#define STRING_DISTRIBUTION_DATE "2021-10-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 796be9d41b..7530399dd6 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 "2021-10-01" + #define STRING_DISTRIBUTION_DATE "2021-10-02" #endif /** From e4d8290be3765b0ee9d780b346c852e3c142bca1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 3 Oct 2021 01:06:58 +0000 Subject: [PATCH 0745/2168] [cron] Bump distribution date (2021-10-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b86aa71eff..2a8161bea6 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-02" +//#define STRING_DISTRIBUTION_DATE "2021-10-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7530399dd6..fbcf0f23d1 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 "2021-10-02" + #define STRING_DISTRIBUTION_DATE "2021-10-03" #endif /** From 9bb562f40a5570a63430bbf9392da0fdb85c5c8c Mon Sep 17 00:00:00 2001 From: VragVideo <91742261+VragVideo@users.noreply.github.com> Date: Sun, 3 Oct 2021 06:12:51 +0300 Subject: [PATCH 0746/2168] =?UTF-8?q?=E2=9C=A8=20WYH=20L12864=20LCD=20(Alf?= =?UTF-8?q?awise=20Ex8)=20(#22863)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 5 ++ Marlin/Configuration_adv.h | 2 +- .../dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp | 4 +- .../HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp | 4 +- .../u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp | 4 +- .../u8g/u8g_com_HAL_LPC1768_sw_spi.cpp | 4 +- .../NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp | 4 +- .../src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp | 4 +- Marlin/src/inc/Conditionals_LCD.h | 79 ++++++++++--------- Marlin/src/inc/Conditionals_post.h | 2 + Marlin/src/inc/SanityCheck.h | 3 +- Marlin/src/lcd/dogm/marlinui_DOGM.h | 6 +- .../lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp | 5 +- .../dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp | 4 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 35 +++++++- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/mega/pins_SILVER_GATE.h | 2 +- Marlin/src/pins/pins.h | 2 +- Marlin/src/pins/pins_postprocess.h | 2 +- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 2 +- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 2 +- Marlin/src/pins/rambo/pins_MINIRAMBO.h | 2 +- Marlin/src/pins/rambo/pins_RAMBO.h | 2 +- Marlin/src/pins/ramps/pins_3DRAG.h | 2 +- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 2 +- Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 2 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 2 +- Marlin/src/pins/sanguino/pins_MELZI.h | 2 +- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 2 +- Marlin/src/pins/sanguino/pins_MELZI_V2.h | 2 +- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 2 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 2 +- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 2 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 2 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 2 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 2 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 2 +- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 35 +++++++- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 2 +- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 2 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 2 +- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 2 +- 56 files changed, 180 insertions(+), 100 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c50af25e63..ab1565d343 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2376,6 +2376,11 @@ //#define VIKI2 //#define miniVIKI +// +// Alfawise Ex8 printer LCD marked as WYH L12864 COG +// +//#define WYH_L12864 + // // MakerLab Mini Panel with graphic // controller and SD support - https://reprap.org/wiki/Mini_panel diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6e44f009ed..8e1f673c87 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1603,7 +1603,7 @@ * Set STATUS_EXPIRE_SECONDS to zero to never clear the status. * This will prevent position updates from being displayed. */ - #if ENABLED(U8GLIB_ST7920) + #if IS_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 diff --git a/Marlin/src/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 index 65bfd4f4e2..8268cf307e 100644 --- a/Marlin/src/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 @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #include "../../../inc/MarlinConfig.h" #include "../../shared/Delay.h" @@ -182,5 +182,5 @@ uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va } #endif // LIGHTWEIGHT_UI -#endif // U8GLIB_ST7920 +#endif // IS_U8GLIB_ST7920 #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp index 2b13c182d0..68e3e74a45 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) +#if HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #include "u8g_com_HAL_DUE_sw_spi_shared.h" @@ -141,5 +141,5 @@ uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void return 1; } -#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 +#endif // HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/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 index 039fa6769b..e159ebaa0c 100644 --- a/Marlin/src/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 @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #include #include @@ -143,5 +143,5 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar return 1; } -#endif // U8GLIB_ST7920 +#endif // IS_U8GLIB_ST7920 #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index 3308d03e79..f116a9b80a 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) +#if HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #include #include "../../shared/HAL_SPI.h" @@ -205,5 +205,5 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, return 1; } -#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 +#endif // HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp index c77c3d30f0..c384cdd751 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #include #include "../../shared/Delay.h" @@ -167,5 +167,5 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void } #endif -#endif // U8GLIB_ST7920 +#endif // IS_U8GLIB_ST7920 #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 085954803c..7fd335d62e 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) +#if HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #undef SPI_SPEED #define SPI_SPEED 2 // About 2 MHz @@ -211,5 +211,5 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt #elif !ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB #include uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {return 0;} -#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 +#endif // HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 #endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 99b360f9f0..46b969a478 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -39,17 +39,17 @@ /** * General Flags that may be set below by specific LCDs * - * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) - * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs - * IS_ULTRA_LCD : Ultra LCD, not necessarily Ultipanel. - * IS_RRD_SC : Common RRD Smart Controller digital interface pins - * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins - * U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. - * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib - * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib - * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib - * U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib - * U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib + * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) + * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs + * IS_ULTRA_LCD : Ultra LCD, not necessarily Ultipanel. + * IS_RRD_SC : Common RRD Smart Controller digital interface pins + * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins + * IS_U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. + * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib + * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib (U8GLIB_SSD1306) + * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib (HAS_U8GLIB_I2C_OLED, IS_ULTRA_LCD, DOGLCD) + * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib + * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib */ #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) @@ -85,7 +85,7 @@ #elif ENABLED(ZONESTAR_12864LCD) #define DOGLCD #define IS_RRD_SC 1 - #define U8GLIB_ST7920 + #define IS_U8GLIB_ST7920 1 #elif ENABLED(ZONESTAR_12864OLED) #define IS_RRD_SC 1 @@ -99,19 +99,24 @@ #define IS_ULTIPANEL 1 #define ENCODER_PULSES_PER_STEP 2 -#elif ANY(miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864) +#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864) + + #define IS_DOGM_12864 1 #define DOGLCD #define IS_ULTIPANEL 1 #if ENABLED(miniVIKI) - #define U8GLIB_ST7565_64128N + #define IS_U8GLIB_ST7565_64128N 1 #elif ENABLED(VIKI2) - #define U8GLIB_ST7565_64128N + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(WYH_L12864) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_XOFFSET 0x04 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define U8GLIB_LM6059_AF + #define IS_U8GLIB_LM6059_AF 1 #elif ENABLED(AZSMZ_12864) - #define U8GLIB_ST7565_64128N + #define IS_U8GLIB_ST7565_64128N 1 #endif #elif ENABLED(OLED_PANEL_TINYBOY2) @@ -128,7 +133,7 @@ #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define DOGLCD - #define U8GLIB_ST7920 + #define IS_U8GLIB_ST7920 1 #define IS_ULTIPANEL 1 #elif ENABLED(MKS_12864OLED) @@ -144,7 +149,7 @@ #elif ENABLED(SAV_3DGLCD) #ifdef U8GLIB_SSD1306 - #define IS_U8GLIB_SSD1306 + #define IS_U8GLIB_SSD1306 // Allow for U8GLIB_SSD1306 + SAV_3DGLCD #endif #define IS_NEWPANEL 1 @@ -266,7 +271,7 @@ // ST7920-based graphical displays #if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) #define DOGLCD - #define U8GLIB_ST7920 + #define IS_U8GLIB_ST7920 1 #define IS_RRD_SC 1 #endif @@ -275,7 +280,7 @@ #define IS_ULTIPANEL 1 #define DOGLCD #if ENABLED(MAKRPANEL) - #define U8GLIB_ST7565_64128N + #define IS_U8GLIB_ST7565_64128N 1 #endif #endif @@ -373,25 +378,28 @@ * I2C Panels */ -#if EITHER(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) +#if ANY(IS_RRD_SC, IS_DOGM_12864, OLED_PANEL_TINYBOY2, LCD_I2C_PANELOLU2) - #define LCD_I2C_TYPE_PCF8575 - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + + #if ENABLED(LCD_I2C_PANELOLU2) // PANELOLU2 LCD with status LEDs, separate encoder and click inputs + #define LCD_I2C_TYPE_MCP23017 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) + #define IS_ULTIPANEL 1 + #endif + +#elif EITHER(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) + + #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander #if ENABLED(LCD_SAINSMART_I2C_2004) #define LCD_WIDTH 20 #define LCD_HEIGHT 4 #endif -#elif ENABLED(LCD_I2C_PANELOLU2) - - // PANELOLU2 LCD with status LEDs, separate encoder and click inputs - - #define LCD_I2C_TYPE_MCP23017 - #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) - #define IS_ULTIPANEL 1 - #elif ENABLED(LCD_I2C_VIKI) /** @@ -417,11 +425,6 @@ #define STD_ENCODER_PULSES_PER_STEP 2 #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#elif ANY(IS_RRD_SC, miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, OLED_PANEL_TINYBOY2, BQ_LCD_SMART_CONTROLLER, LCD_I2C_PANELOLU2) - - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #endif #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 1db4208a1f..9dfc7b187a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -358,6 +358,8 @@ #define _LCD_CONTRAST_MAX 115 #elif ENABLED(VIKI2) #define _LCD_CONTRAST_INIT 140 +#elif ENABLED(WYH_L12864) + #define _LCD_CONTRAST_INIT 190 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #define _LCD_CONTRAST_MIN 90 #define _LCD_CONTRAST_INIT 110 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 58c02e7ebd..8417292934 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -833,7 +833,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * LCD Lightweight Screen Style */ -#if ENABLED(LIGHTWEIGHT_UI) && DISABLED(U8GLIB_ST7920) +#if ENABLED(LIGHTWEIGHT_UI) && !IS_U8GLIB_ST7920 #error "LIGHTWEIGHT_UI requires a U8GLIB_ST7920-based display." #endif @@ -2672,6 +2672,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(MKS_TS35_V2_0, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35, MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R, ANET_ET4_TFT28, ANET_ET5_TFT35) \ + COUNT_ENABLED(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) \ + COUNT_ENABLED(VIKI2, miniVIKI) \ + + ENABLED(WYH_L12864) \ + COUNT_ENABLED(ZONESTAR_12864LCD, ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) \ + COUNT_ENABLED(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) \ + ENABLED(AZSMZ_12864) \ diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.h b/Marlin/src/lcd/dogm/marlinui_DOGM.h index 328b69b93b..050f147d62 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.h +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.h @@ -43,7 +43,7 @@ #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS #endif -#elif ENABLED(U8GLIB_ST7920) +#elif IS_U8GLIB_ST7920 // RepRap Discount Full Graphics Smart Controller // and other variant LCDs using ST7920 @@ -72,7 +72,7 @@ #define U8G_CLASS U8GLIB_DOGM128_2X // 4 stripes (HW-SPI) #endif -#elif ENABLED(U8GLIB_LM6059_AF) +#elif IS_U8GLIB_LM6059_AF // Based on the Adafruit ST7565 (https://www.adafruit.com/products/250) @@ -82,7 +82,7 @@ #define U8G_CLASS U8GLIB_LM6059_2X // 4 stripes (HW-SPI) #endif -#elif ENABLED(U8GLIB_ST7565_64128N) +#elif IS_U8GLIB_ST7565_64128N // MaKrPanel, Mini Viki, Viki 2.0, AZSMZ 12864 ST7565 controller diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp index fda090338c..bfd44d08df 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -63,6 +63,9 @@ #define WIDTH 128 #define HEIGHT 64 #define PAGE_HEIGHT 8 +#ifndef ST7565_XOFFSET + #define ST7565_XOFFSET 0x00 +#endif #define ST7565_ADC_REVERSE(N) ((N) ? 0xA1 : 0xA0) #define ST7565_BIAS_MODE(N) ((N) ? 0xA3 : 0xA2) @@ -123,7 +126,7 @@ static const uint8_t u8g_dev_st7565_64128n_HAL_init_seq[] PROGMEM = { static const uint8_t u8g_dev_st7565_64128n_HAL_data_start[] PROGMEM = { U8G_ESC_ADR(0), // instruction mode U8G_ESC_CS(1), // enable chip - ST7565_COLUMN_ADR(0x00), // high 4 bits to 0, low 4 bits to 0. Changed for DisplayTech 64128N + ST7565_COLUMN_ADR(ST7565_XOFFSET), // high 4 bits to 0, low 4 bits to 0. Changed for DisplayTech 64128N U8G_ESC_END // end of sequence }; diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp index 9367ed75a9..e844eee251 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -29,7 +29,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #include "ultralcd_st7920_u8glib_rrd_AVR.h" @@ -192,5 +192,5 @@ u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = { u8g_dev_rrd_st7920_128x64_fn, &u8 void ST7920_write_byte(const uint8_t val) { ST7920_WRITE_BYTE(val); } #endif -#endif // U8GLIB_ST7920 +#endif // IS_U8GLIB_ST7920 #endif // !U8G_HAL_LINKS && (__AVR__ || ARDUINO_ARCH_STM32 || ARDUINO_ARCH_ESP32) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index dc52a7c36d..ec8f31b854 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -220,12 +220,13 @@ #error "ANET_FULL_GRAPHICS_LCD_ALT_WIRING only applies to the ANET 1.0 board." #elif ENABLED(ANET_FULL_GRAPHICS_LCD) + #error "CAUTION! ANET_FULL_GRAPHICS_LCD requires wiring modifications. See 'pins_BTT_SKR_V1_3.h' for details. Comment out this line to continue." /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. (This is the critical part!) - * 3. Rewire the CLK Signal (LCD Pin9) to LCD Pin7. (LCD Pin9 remains open because this pin is open drain.) + * 3. Rewire the CLK Signal (LCD Pin9) to LCD Pin7. (LCD Pin9 remains open because it is open drain.) * 4. A wire is needed to connect the Reset switch at J3 (LCD Pin7) to EXP2 (Pin3) on the board. * * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! @@ -252,6 +253,38 @@ #define LCD_PINS_ENABLE EXP1_05_PIN #define LCD_PINS_D4 EXP1_07_PIN + #elif ENABLED(WYH_L12864) + + #error "CAUTION! WYH_L12864 requires wiring modifications. Comment out this line to continue." + + /** + * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. + * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. (This is the critical part!) + * 3. Swap the LCD's MOSI (Pin9) and empty (Pin10) wires because Pin9 is open drain. + * + * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! + * + * The WYH_L12864 connector plug: + * + * BEFORE AFTER + * ______ ______ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * SCK | 7 8 | BTN_ENC SCK | 7 8 | BTN_ENC + * MOSI | 9 10 | open | 9 10 | MOSI + * ------ ------ + * LCD LCD + */ + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_08_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_07_PIN + #define DOGLCD_MOSI EXP1_10_PIN + #define LCD_BACKLIGHT_PIN -1 + #elif ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS EXP1_04_PIN 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 17daf176da..dc82a2857f 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -321,7 +321,7 @@ /** * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. (This is the critical part!) - * 3. Rewire the CLK Signal (LCD Pin9) to LCD Pin7. (LCD Pin9 remains open because this pin is open drain.) + * 3. Rewire the CLK Signal (LCD Pin9) to LCD Pin7. (LCD Pin9 remains open because it is open drain.) * 4. A wire is needed to connect the Reset switch at J3 (LCD Pin7) to EXP2 (Pin3) on the board. * * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 7b4f53a764..c2ca5b3103 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -73,7 +73,7 @@ #define TEMP_BED_PIN 6 #if HAS_WIRED_LCD - #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 + #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 #define LCD_PINS_RS 30 #define LCD_PINS_ENABLE 20 #define LCD_PINS_D4 25 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 0293da1dba..367432b1a9 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -49,7 +49,7 @@ #define IS_RAMPS_SF #endif -#if !(BOTH(IS_ULTRA_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) +#if !(BOTH(IS_ULTRA_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) #define HAS_FREE_AUX2_PINS 1 #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 4860e2d800..827e07e3f5 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -1366,7 +1366,7 @@ // // Default DOGLCD SPI delays // -#if DISABLED(U8GLIB_ST7920) +#if !IS_U8GLIB_ST7920 #undef ST7920_DELAY_1 #undef ST7920_DELAY_2 #undef ST7920_DELAY_3 diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 25decbf035..a7d1a62820 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -205,7 +205,7 @@ #endif // IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #endif // HAS_WIRED_LCD -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 48c68d55f9..45c09ae33e 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -201,7 +201,7 @@ #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index c496878908..ab25e2e692 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -193,7 +193,7 @@ #endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 8153103a38..41e59c1b22 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -270,7 +270,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 0 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 5bd1667356..4ff6e2d7e5 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -166,7 +166,7 @@ #endif // IS_ULTRA_LCD && IS_NEWPANEL -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 188 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 7715eca7eb..64d881866b 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -106,7 +106,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 0 #define BOARD_ST7920_DELAY_3 189 diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index 4bebd6ded6..ced66d80b8 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -40,7 +40,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 250 diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 94c4551fc2..f15c89e4f8 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -199,7 +199,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 200 #define BOARD_ST7920_DELAY_2 200 #define BOARD_ST7920_DELAY_3 200 diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index 31583fd109..852ad5a34b 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -32,7 +32,7 @@ #define IS_MELZI 1 // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 0 #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 3c6dd901c0..36e26980f4 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -36,7 +36,7 @@ #define BOARD_INFO_NAME "Melzi (Creality)" // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 8abed5c30c..81bd78b7a0 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "Melzi (Tronxy)" // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index c3133432e0..a3ab5ff61b 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "Melzi V2" // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 400 #define BOARD_ST7920_DELAY_3 0 diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 8dd6171b92..02f4a6e985 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -165,7 +165,7 @@ #define KILL_PIN 10 #define BEEPER_PIN 27 - #elif ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI #define LCD_PINS_RS 30 // CS chip select /SS chip slave select diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 650357ee9e..a6cc5ffa60 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -202,7 +202,7 @@ #endif // !FYSETC_MINI_12864 // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 77eb6aaf14..f8e3e76ada 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -155,7 +155,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 3f02d7082f..e4c741eae7 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -179,7 +179,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index b3da8d884e..520764a503 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -158,7 +158,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 3650ffde5c..cb5200bc27 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -166,7 +166,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 56dda2b143..88aa35f2c0 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -163,7 +163,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index c9a20fd66e..12a6d5b84d 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -168,7 +168,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 489da08393..dd1008ee3a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -221,7 +221,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 125 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 6388e1723c..3767748e53 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -113,7 +113,7 @@ #endif // !MKS_MINI_12864 // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index d19343386e..3df6727d03 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -365,7 +365,7 @@ #endif - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index fdee796692..69fdd1da89 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -300,7 +300,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index daacd0c124..ca6510c7d9 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -332,7 +332,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 125 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index e0b2f6adfc..817ad71752 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -305,7 +305,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 200 // Tclk_fall <200ns #define BOARD_ST7920_DELAY_2 250 // Tdata_width >200ns #define BOARD_ST7920_DELAY_3 200 // Tclk_rise <200ns diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 86851a7840..d054e354f7 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -285,7 +285,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index eb0c3bdbb9..bd483ecf0a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -277,7 +277,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 68948f7de9..0715380e22 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -483,7 +483,7 @@ #endif // Alter timing for graphical display - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index ab0a7dd962..bb77285c01 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -478,7 +478,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 120 #define BOARD_ST7920_DELAY_2 80 #define BOARD_ST7920_DELAY_3 580 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 72154be2ee..3314d0154d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -453,6 +453,39 @@ #define BTN_EN1 EXP2_08_PIN #define BTN_EN2 EXP2_06_PIN + #elif ENABLED(WYH_L12864) + + #error "CAUTION! WYH_L12864 requires wiring modifications. Comment out this line to continue." + + /** + * 1. Cut the tab off the LCD connector so it can be plugged into the "EXP1" connector the other way. + * 2. Swap the LCD's +5V (Pin2) and GND (Pin1) wires. + * + * !!! If you are unsure, ask for help! Your motherboard may be damaged in some circumstances !!! + * + * The WYH_L12864 connector plug: + * + * BEFORE AFTER + * ______ ______ + * GND | 1 2 | 5V 5V | 1 2 | GND + * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 + * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 + * SCK | 7 8 | BTN_ENC SCK | 7 8 | BTN_ENC + * MOSI | 9 10 | MOSI | 9 10 | + * ------ ------ + * LCD LCD + */ + #undef BEEPER_PIN + #undef BTN_ENC + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_08_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_07_PIN + #define DOGLCD_MOSI EXP1_09_PIN + #define LCD_BACKLIGHT_PIN -1 + #else #define LCD_PINS_RS EXP1_07_PIN @@ -499,7 +532,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 125 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index a05f4fb5b9..95cfb1234d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -483,7 +483,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 120 #endif diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 8a9ac56e9e..794649e416 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -305,7 +305,7 @@ #define FIL_RUNOUT_PIN PA3 // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 3fe7449330..a604a71c4b 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -245,7 +245,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 6b6f644159..e2454b578d 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -314,7 +314,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 640 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 4c0e3515f6..00f49acbeb 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -172,7 +172,7 @@ #endif // HAS_WIRED_LCD // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 640 diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index f936df2c2c..bb5507b29a 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -183,7 +183,7 @@ #endif // Alter timing for graphical display -#if ENABLED(U8GLIB_ST7920) +#if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 715 From 97295c552de9b72ad69833094776e34c3502fa0a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 4 Oct 2021 01:05:57 +0000 Subject: [PATCH 0747/2168] [cron] Bump distribution date (2021-10-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 2a8161bea6..727e86205d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-03" +//#define STRING_DISTRIBUTION_DATE "2021-10-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fbcf0f23d1..762854f779 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 "2021-10-03" + #define STRING_DISTRIBUTION_DATE "2021-10-04" #endif /** From eb784d6e55c84c05b2a5353899d8bc25276e0640 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 2 Oct 2021 02:33:14 -0500 Subject: [PATCH 0748/2168] =?UTF-8?q?=F0=9F=8E=A8=20Rename=20MarlinUI::zof?= =?UTF-8?q?fset=5Foverlay?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 10 +++++++--- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 10 +--------- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 14 +++----------- Marlin/src/lcd/marlinui.cpp | 14 ++++++++++++++ Marlin/src/lcd/marlinui.h | 5 +++++ Marlin/src/lcd/menu/menu.cpp | 5 +---- Marlin/src/lcd/menu/menu.h | 4 ---- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- 8 files changed, 32 insertions(+), 32 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 8417292934..a4d7d37aac 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -900,7 +900,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination" #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE #error "BABYSTEP_ZPROBE_OFFSET requires a probe." - #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && !HAS_MARLINUI_U8GLIB + #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && NONE(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI) #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a Graphical LCD." #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && DISABLED(BABYSTEP_ZPROBE_OFFSET) #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET." @@ -1762,8 +1762,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !(ENABLED(AUTO_BED_LEVELING_UBL) && EITHER(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI)) - #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." +#if ENABLED(MESH_EDIT_GFX_OVERLAY) + #if DISABLED(AUTO_BED_LEVELING_UBL) + #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL." + #elif NONE(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI) + #error "MESH_EDIT_GFX_OVERLAY requires a Graphical LCD." + #endif #endif #if ENABLED(G29_RETRY_AND_RECOVER) && NONE(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index f1c5eebbb5..4a7e26ae83 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -715,15 +715,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop B00001100,B00000000 }; - void _lcd_zoffset_overlay_gfx(const_float_t zvalue) { - // Determine whether the user is raising or lowering the nozzle. - static int8_t dir; - static float old_zvalue; - if (zvalue != old_zvalue) { - dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; - old_zvalue = zvalue; - } - + void MarlinUI::zoffset_overlay(const int8_t dir) { const unsigned char *rot_up = TERN(OVERLAY_GFX_REVERSE, ccw_bmp, cw_bmp), *rot_down = TERN(OVERLAY_GFX_REVERSE, cw_bmp, ccw_bmp); diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 09458401be..9ad258b3ac 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -562,19 +562,11 @@ void MarlinUI::draw_status_message(const bool blink) { #endif // AUTO_BED_LEVELING_UBL - #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY, BABYSTEP_GFX_OVERLAY) - - void _lcd_zoffset_overlay_gfx(const float zvalue) { - // Determine whether the user is raising or lowering the nozzle. - static int8_t dir; - static float old_zvalue; - if (zvalue != old_zvalue) { - dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; - old_zvalue = zvalue; - } + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + void MarlinUI::zoffset_overlay(const int8_t dir) { const int rot_up = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCCW, ICON_RotateCW), - rot_down = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCW, ICON_RotateCCW); + rot_down = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCW, ICON_RotateCCW); const int nozzle = (LCD_PIXEL_WIDTH / 2) - 20; diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 5fcbff870e..14d0e182c0 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1714,6 +1714,20 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; if (touch_calibration.need_calibration()) ui.goto_screen(touch_screen_calibration); #endif } + + #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + void MarlinUI::zoffset_overlay(const_float_t zvalue) { + // Determine whether the user is raising or lowering the nozzle. + static int8_t dir; + static float old_zvalue; + if (zvalue != old_zvalue) { + dir = zvalue ? zvalue < old_zvalue ? -1 : 1 : 0; + old_zvalue = zvalue; + } + zoffset_overlay(dir); + } + #endif + #endif #if BOTH(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 270ee3afce..02d5bf06bd 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -474,6 +474,11 @@ public: static bool did_first_redraw; #endif + #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + static void zoffset_overlay(const int8_t dir); + static void zoffset_overlay(const_float_t zvalue); + #endif + static void draw_kill_screen(); #else // No LCD diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 76cdd51cd5..61a1a16c6a 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -257,9 +257,6 @@ void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { * * encoderLine is the position based on the encoder * encoderTopLine is the top menu line to display - * _lcdLineNr is the index of the LCD line (e.g., 0-3) - * _menuLineNr is the menu item to draw and process - * _thisItemNr is the index of each MENU_ITEM or STATIC_ITEM * screen_items is the total number of items in the menu (after one call) */ void scroll_screen(const uint8_t limit, const bool is_menu) { @@ -336,7 +333,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { if (ui.should_draw()) { if (do_probe) { MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), BABYSTEP_TO_STR(probe.offset.z)); - TERN_(BABYSTEP_ZPROBE_GFX_OVERLAY, _lcd_zoffset_overlay_gfx(probe.offset.z)); + TERN_(BABYSTEP_ZPROBE_GFX_OVERLAY, ui.zoffset_overlay(probe.offset.z)); } else { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index ad2cf72000..50842dcaf8 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -39,10 +39,6 @@ typedef void (*selectFunc_t)(); #define SS_INVERT 0x02 #define SS_DEFAULT SS_CENTER -#if EITHER(HAS_MARLINUI_U8GLIB, IS_DWIN_MARLINUI) && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) - void _lcd_zoffset_overlay_gfx(const_float_t zvalue); -#endif - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) && Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 #define BABYSTEP_TO_STR(N) ftostr43sign(N) #elif ENABLED(BABYSTEPPING) diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 03aec39c83..8dea7d943d 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -83,7 +83,7 @@ void _lcd_mesh_fine_tune(PGM_P const msg) { if (ui.should_draw()) { const float rounded_f = rounded_mesh_value(); MenuEditItemBase::draw_edit_screen(msg, ftostr43sign(rounded_f)); - TERN_(MESH_EDIT_GFX_OVERLAY, _lcd_zoffset_overlay_gfx(rounded_f)); + TERN_(MESH_EDIT_GFX_OVERLAY, ui.zoffset_overlay(rounded_f)); TERN_(HAS_GRAPHICAL_TFT, ui.refresh(LCDVIEW_NONE)); } } From 54d400608db83bfa606e1b757589c169c9a38fc2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 Oct 2021 00:24:41 -0500 Subject: [PATCH 0749/2168] =?UTF-8?q?=F0=9F=8E=A8=20Axis=20name=20string?= =?UTF-8?q?=20interpolation,=20with=20examples=20(#22879)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp | 16 +++++----- Marlin/src/lcd/language/language_cz.h | 3 +- Marlin/src/lcd/language/language_de.h | 3 +- Marlin/src/lcd/language/language_en.h | 15 ++++----- Marlin/src/lcd/language/language_es.h | 3 +- Marlin/src/lcd/language/language_fr.h | 3 +- Marlin/src/lcd/language/language_gl.h | 3 +- Marlin/src/lcd/language/language_hu.h | 3 +- Marlin/src/lcd/language/language_it.h | 5 +-- Marlin/src/lcd/language/language_pl.h | 5 +-- Marlin/src/lcd/language/language_pt_br.h | 3 +- Marlin/src/lcd/language/language_ro.h | 3 +- Marlin/src/lcd/language/language_ru.h | 3 +- Marlin/src/lcd/language/language_sk.h | 6 ++-- Marlin/src/lcd/language/language_sv.h | 3 +- Marlin/src/lcd/language/language_tr.h | 3 +- Marlin/src/lcd/language/language_uk.h | 3 +- Marlin/src/lcd/language/language_zh_CN.h | 3 +- Marlin/src/lcd/language/language_zh_TW.h | 3 +- Marlin/src/lcd/lcdprint.cpp | 6 ++++ Marlin/src/lcd/menu/menu.cpp | 32 ++++++-------------- Marlin/src/lcd/menu/menu.h | 6 ++-- Marlin/src/lcd/menu/menu_configuration.cpp | 8 ++--- Marlin/src/lcd/menu/menu_item.h | 20 ++++++++++-- Marlin/src/lcd/menu/menu_motion.cpp | 24 +++++++-------- Marlin/src/lcd/tft/tft_string.cpp | 21 ++++++------- 26 files changed, 100 insertions(+), 106 deletions(-) diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp index 89e001b29c..e08d5360db 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -43,9 +43,11 @@ uint8_t read_byte(uint8_t *byte) { return *byte; } /** * Add a string, applying substitutions for the following characters: * + * $ displays the clipped C-string given by the itemString argument * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/*=nullptr*/) { wchar_t wchar; @@ -62,17 +64,15 @@ void DWIN_String::add(uint8_t *string, const int8_t index, uint8_t *itemString/* if (inum >= 10) { add_character('0' + (inum / 10)); inum %= 10; } add_character('0' + inum); } - else { + else add(index == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED)); - } - continue; } - else if (ch == '$' && itemString) { + else if (ch == '$' && itemString) add(itemString); - continue; - } - - add_character(ch); + else if (ch == '@') + add_character(axis_codes[index]); + else + add_character(ch); } eol(); } diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 2ee0534f9d..fd064b0834 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -129,9 +129,8 @@ namespace Language_cz { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikace"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrcadlení"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. tryska @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Provádím G29"); LSTR MSG_UBL_TOOLS = _UxGT("UBL nástroje"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 4aef4ac45c..8160ad4724 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -121,9 +121,8 @@ namespace Language_de { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplizieren"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Spiegelkopie"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("vollstä. Kontrolle"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. Düse X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. Düse Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. Düse Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. Düse @"); LSTR MSG_UBL_DOING_G29 = _UxGT("G29 ausführen"); LSTR MSG_UBL_TOOLS = _UxGT("UBL-Werkzeuge"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 8c7a78cd46..c9413d3cea 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -30,9 +30,11 @@ * Substitutions are applied for the following characters when used * in menu items that call lcd_put_u8str_ind_P with an index: * + * $ displays an inserted C-string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ #define en 1234 @@ -72,12 +74,7 @@ namespace Language_en { LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Progress Bar Test"); LSTR MSG_HOMING = _UxGT("Homing"); LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); - LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); - LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); - LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); - LSTR MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; + LSTR MSG_AUTO_HOME_A = _UxGT("Home @"); LSTR MSG_FILAMENT_SET = _UxGT("Filament Settings"); LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); LSTR MSG_LEVBED_FL = _UxGT("Front Left"); @@ -175,9 +172,8 @@ namespace Language_en { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2nd Nozzle @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Doing G29"); LSTR MSG_UBL_TOOLS = _UxGT("UBL Tools"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); @@ -279,7 +275,7 @@ namespace Language_en { LSTR MSG_MOVING = _UxGT("Moving..."); LSTR MSG_FREE_XY = _UxGT("Free XY"); - LSTR MSG_MOVE_X = _UxGT("Move X"); + LSTR MSG_MOVE_X = _UxGT("Move X"); // Used by draw_edit_screen LSTR MSG_MOVE_Y = _UxGT("Move Y"); LSTR MSG_MOVE_Z = _UxGT("Move Z"); LSTR MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; @@ -303,6 +299,7 @@ namespace Language_en { LSTR MSG_MAXSPEED_Y = _UxGT("Max ") LCD_STR_B _UxGT(" Speed"); LSTR MSG_MAXSPEED_Z = _UxGT("Max ") LCD_STR_C _UxGT(" Speed"); LSTR MSG_MAXSPEED_E = _UxGT("Max ") LCD_STR_E _UxGT(" Speed"); + LSTR MSG_MAXSPEED_A = _UxGT("Max @ Speed"); LSTR MSG_BED_Z = _UxGT("Bed Z"); LSTR MSG_NOZZLE = _UxGT("Nozzle"); LSTR MSG_NOZZLE_N = _UxGT("Nozzle ~"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 315a8413df..62dd69b526 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -124,9 +124,8 @@ namespace Language_es { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicar"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Reflejada"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2ª Fusor X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2ª Fusor Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2ª Fusor Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2ª Fusor @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Hacer G29"); LSTR MSG_UBL_TOOLS = _UxGT("Herramientas UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Nivelado UBL"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index a99659bf18..77472e4fbb 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -134,9 +134,8 @@ namespace Language_fr { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copie miroir"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Contrôle complet"); LSTR MSG_OFFSETS_MENU = _UxGT("Offsets Outil"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("Buse 2 X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("Buse 2 Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("Buse 2 Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("Buse 2 @"); LSTR MSG_G26_HEATING_BED = _UxGT("G26: Chauffage du lit"); LSTR MSG_G26_HEATING_NOZZLE = _UxGT("Buse en chauffe..."); LSTR MSG_G26_MANUAL_PRIME = _UxGT("Amorce manuelle..."); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index ad85ac9b48..0252cf30ec 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -121,9 +121,8 @@ namespace Language_gl { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicación"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Espello"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2º Bico X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2º Bico Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2º Bico Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2º Bico @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Executando G29"); LSTR MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 2c06a51c19..4028ab10cd 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -156,9 +156,8 @@ namespace Language_hu { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Tükrözött másolás"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Teljes felügyelet"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("X-hézag másolása"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. fej X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. fej Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. fej Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. fej @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Szintezz! G29"); LSTR MSG_UBL_TOOLS = _UxGT("UBL eszköz"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index e005567985..2e2529a845 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -30,9 +30,11 @@ * Substitutions are applied for the following characters when used * in menu items that call lcd_put_u8str_ind_P with an index: * + * $ displays an inserted C-string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ #define DISPLAY_CHARSET_ISO10646_1 @@ -160,9 +162,8 @@ namespace Language_it { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia speculare"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pieno controllo"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("X-Gap-X duplicato"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2° ugello X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2° ugello Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2° ugello Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2° ugello @"); LSTR MSG_UBL_DOING_G29 = _UxGT("G29 in corso"); LSTR MSG_UBL_TOOLS = _UxGT("Strumenti UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index b37e1d80cf..2dde747378 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -30,9 +30,11 @@ * Substitutions are applied for the following characters when used * in menu items that call lcd_put_u8str_ind_P with an index: * + * $ displays an inserted C-string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ #define DISPLAY_CHARSET_ISO10646_PL @@ -133,9 +135,8 @@ namespace Language_pl { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2ga dysza @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); LSTR MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 45e1879d4c..7d97d48336 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -111,9 +111,8 @@ namespace Language_pt_br { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicação"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Cópia espelhada"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Controle Total"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2o bico X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2o bico Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2o bico Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2o bico @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Executando G29"); LSTR MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Nivel. Mesa Unif."); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 6db2fe38fa..2eb4c0b996 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -120,9 +120,8 @@ namespace Language_ro { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2nd Nozzle @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Doing G29"); LSTR MSG_UBL_TOOLS = _UxGT("UBL Tools"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 25ea5fd471..2de45e7d8d 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -197,9 +197,8 @@ namespace Language_ru { LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Полный контроль"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("Дублировать X-зазор"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2-е сопло X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2-е сопло Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2-е сопло Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2-е сопло @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Выполняем G29"); LSTR MSG_UBL_TOOLS = _UxGT("Инструменты UBL"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 3a9eb23a8f..81fb9a3d01 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -34,9 +34,11 @@ * Substitutions are applied for the following characters when used * in menu items that call lcd_put_u8str_ind_P with an index: * + * $ displays an inserted C-string * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ #define DISPLAY_CHARSET_ISO10646_SK @@ -172,9 +174,8 @@ namespace Language_sk { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Zrkadlená kópia"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Plná kontrola"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplik. medz.-X"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. tryska X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. tryska Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. tryska Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. tryska @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Vykonávam G29"); LSTR MSG_UBL_TOOLS = _UxGT("Nástroje UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); @@ -300,6 +301,7 @@ namespace Language_sk { LSTR MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") LCD_STR_B; LSTR MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") LCD_STR_C; LSTR MSG_MAXSPEED_E = _UxGT("Max rýchl. ") LCD_STR_E; + LSTR MSG_MAXSPEED_A = _UxGT("Max rýchl. @"); LSTR MSG_BED_Z = _UxGT("Výška podl."); LSTR MSG_NOZZLE = _UxGT("Tryska"); LSTR MSG_NOZZLE_N = _UxGT("Tryska ~"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 91a842fe2d..3b4d6c24c1 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -145,9 +145,8 @@ namespace Language_sv { LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad Kopia"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Kontroll"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-Avstånd"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2:a Munstycke X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2:a Munstycke Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2:a Munstycke Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2:a Munstycke @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Utför G29"); LSTR MSG_UBL_TOOLS = _UxGT("UBL Verktyg"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Enad Bädd Nivellering (UBL)"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 9525a952a1..d6f2f52a0c 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -123,9 +123,8 @@ namespace Language_tr { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Kopyala"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Yansıtılmış kopya"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Tam Kontrol"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2. nozul X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2. nozul Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. nozul Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. nozul @"); LSTR MSG_UBL_DOING_G29 = _UxGT("G29 Çalışıyor"); LSTR MSG_UBL_TOOLS = _UxGT("UBL Araçları"); LSTR MSG_UBL_LEVEL_BED = _UxGT("UBL Yatak Hizalama"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 4cfe969307..581a501b49 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -198,9 +198,8 @@ namespace Language_uk { LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Повний контроль"); LSTR MSG_IDEX_DUPE_GAP = _UxGT("Дублюв. X-проміжок"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("Друге сопло X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("Друге сопло Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("Друге сопло Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("Друге сопло @"); LSTR MSG_UBL_DOING_G29 = _UxGT("Виконується G29"); LSTR MSG_UBL_TOOLS = _UxGT("Інструменти UBL"); diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 60ffb27337..afa51689cf 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -119,9 +119,8 @@ namespace Language_zh_CN { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("复制"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("镜像复制"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("完全控制"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("第二喷头是X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("第二喷头是Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("第二喷头是Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("第二喷头是@"); LSTR MSG_UBL_DOING_G29 = _UxGT("执行G29"); // "Doing G29" LSTR MSG_UBL_TOOLS = _UxGT("UBL工具"); // "UBL Tools" LSTR MSG_UBL_LEVEL_BED = _UxGT("统一热床调平(UBL)"); // "Unified Bed Leveling" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index fd43fefd29..01b11225e3 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -116,9 +116,8 @@ namespace Language_zh_TW { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); - LSTR MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); - LSTR MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); + LSTR MSG_HOTEND_OFFSET_A = _UxGT("2nd Nozzle @"); LSTR MSG_UBL_DOING_G29 = _UxGT("執行G29"); // "Doing G29" LSTR MSG_UBL_TOOLS = _UxGT("UBL工具"); // "UBL Tools" LSTR MSG_UBL_LEVEL_BED = _UxGT("統一熱床調平(UBL)"); // "Unified Bed Leveling" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index b2c939557d..498b478b12 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -36,9 +36,11 @@ * * Print a string with an index substituted within it: * + * $ displays the clipped C-string given by the inStr argument * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { const uint8_t prop = USE_WIDE_GLYPH ? 2 : 1; @@ -72,6 +74,10 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i else if (ch == '$' && inStr) { n -= lcd_put_u8str_max_P(inStr, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); } + else if (ch == '@') { + lcd_put_wchar(axis_codes[ind]); + n--; + } else { lcd_put_wchar(ch); n -= ch > 255 ? prop : 1; diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 61a1a16c6a..a24ad883f7 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -103,42 +103,28 @@ void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_b /////////// Menu Editing Actions /////////// //////////////////////////////////////////// -/** - * Functions for editing single values - * - * The "DEFINE_MENU_EDIT_ITEM" macro generates the classes needed to edit a numerical value. - * - * The prerequisite is that in the header the type was already declared: - * - * DEFINE_MENU_EDIT_ITEM_TYPE(int3, int16_t, i16tostr3rj, 1) - * - * For example, DEFINE_MENU_EDIT_ITEM(int3) expands into: - * - * template class TMenuEditItem - * - * You can then use one of the menu macros to present the edit interface: - * EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, 10, 999) - * - * This expands into a more primitive menu item: - * _MENU_ITEM_P(int3, false, GET_TEXT(MSG_SPEED), &feedrate_percentage, 10, 999) - * - * ...which calls: - * MenuItem_int3::action(plabel, &feedrate_percentage, 10, 999) - * MenuItem_int3::draw(encoderLine == _thisItemNr, _lcdLineNr, plabel, &feedrate_percentage, 10, 999) - */ +// All Edit Screens run the same way, but `draw_edit_screen` is implementation-specific void MenuEditItemBase::edit_screen(strfunc_t strfunc, loadfunc_t loadfunc) { + // Reset repeat_delay for Touch Buttons TERN_(HAS_TOUCH_BUTTONS, ui.repeat_delay = BUTTON_DELAY_EDIT); + // Constrain ui.encoderPosition to 0 ... maxEditValue (calculated in encoder steps) if (int32_t(ui.encoderPosition) < 0) ui.encoderPosition = 0; if (int32_t(ui.encoderPosition) > maxEditValue) ui.encoderPosition = maxEditValue; + // If drawing is flagged then redraw the (whole) edit screen if (ui.should_draw()) draw_edit_screen(strfunc(ui.encoderPosition + minEditValue)); + // If there was a click or "live editing" and encoder moved... if (ui.lcd_clicked || (liveEdit && ui.should_draw())) { + // Pass the editValue pointer to the loadfunc along with the encoder plus min if (editValue) loadfunc(editValue, ui.encoderPosition + minEditValue); + // If a callbackFunc was set, call it for click or always for "live editing" if (callbackFunc && (liveEdit || ui.lcd_clicked)) (*callbackFunc)(); + // Use up the click to finish editing and go to the previous screen if (ui.use_click()) ui.goto_previous_screen(); } } +// Going to an edit screen sets up some persistent values first void MenuEditItemBase::goto_edit_screen( PGM_P const el, // Edit label void * const ev, // Edit value pointer diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 50842dcaf8..44b0e89aca 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -60,7 +60,9 @@ class MenuItemBase { // Store the index of the item ahead of use by indexed items FORCE_INLINE static void init(const int8_t ind=0, PGM_P const pstr=nullptr) { itemIndex = ind; itemString = pstr; } + // Implementation-specific: // Draw an item either selected (pre_char) or not (space) with post_char + // Menus may set up itemIndex, itemString and pass them to string-building or string-emitting functions static void _draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char); // Draw an item either selected ('>') or not (space) with post_char @@ -167,11 +169,11 @@ class MenuEditItemBase : public MenuItemBase { ); static void edit_screen(strfunc_t, loadfunc_t); // Edit value handler public: - // Implemented for HD44780 and DOGM + // Implementation-specific: // Draw the current item at specified row with edit data static void draw(const bool sel, const uint8_t row, PGM_P const pstr, const char * const inStr, const bool pgm=false); - // Implemented for HD44780 and DOGM + // Implementation-specific: // This low-level method is good to draw from anywhere static void draw_edit_screen(PGM_P const pstr, const char * const value); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index c9227724ab..7021a0e667 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -174,12 +174,12 @@ void menu_advanced_settings(); START_MENU(); BACK_ITEM(MSG_CONFIGURATION); #if ENABLED(DUAL_X_CARRIAGE) - EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); #else - EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_X, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); #endif - EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Y, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); - EDIT_ITEM_FAST(float42_52, MSG_HOTEND_OFFSET_Z, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, Z_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 0a4f4bb7d1..a2f7c5bec2 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -106,9 +106,23 @@ 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_MENU_EDIT_ITEM_TYPE(int3, int16_t, i16tostr3rj, 1) + * + * Define struct types for use by EDIT_ITEM(...) macros, which encompass + * a primitive storage type, a string function, and a scale factor for edit / display. + * The EDIT_ITEM macros take care of calling action and draw methods as needed. + * + * For example, DEFINE_MENU_EDIT_ITEM_TYPE(percent, uint8_t, ui8tostr4pctrj, 100.f/255.f, +0.5f) expands into: + * + * struct MenuEditItemInfo_percent { + * typedef uint8_t type_t; + * static inline float scale(const_float_t value) { return value * (100.f/255.f) +0.5f; } + * static inline float unscale(const_float_t value) { return value / (100.f/255.f) +0.5f; } + * static inline const char* strfunc(const_float_t value) { return ui8tostr4pctrj(_DOFIX(uint8_t,value)); } + * }; + * typedef TMenuEditItem MenuItem_percent + */ #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, ETC...) \ diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 948c8807b2..7191e637d1 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -329,21 +329,21 @@ void menu_move() { BACK_ITEM(MSG_MOTION); GCODES_ITEM(MSG_AUTO_HOME, G28_STR); - GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); + GCODES_ITEM_N(X_AXIS, MSG_AUTO_HOME_A, PSTR("G28X")); #if HAS_Y_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + GCODES_ITEM_N(Y_AXIS, MSG_AUTO_HOME_A, PSTR("G28Y")); #endif #if HAS_Z_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif #if LINEAR_AXES >= 4 - GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); + GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); #endif #if LINEAR_AXES >= 5 - GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); + GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); #endif #if LINEAR_AXES >= 6 - GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); #endif END_MENU(); @@ -382,21 +382,21 @@ void menu_motion() { #else GCODES_ITEM(MSG_AUTO_HOME, G28_STR); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) - GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); + GCODES_ITEM_N(X_AXIS, MSG_AUTO_HOME_A, PSTR("G28X")); #if HAS_Y_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + GCODES_ITEM_N(Y_AXIS, MSG_AUTO_HOME_A, PSTR("G28Y")); #endif #if HAS_Z_AXIS - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif #if LINEAR_AXES >= 4 - GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" AXIS4_STR)); + GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); #endif #if LINEAR_AXES >= 5 - GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" AXIS5_STR)); + GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); #endif #if LINEAR_AXES >= 6 - GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" AXIS6_STR)); + GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); #endif #endif #endif diff --git a/Marlin/src/lcd/tft/tft_string.cpp b/Marlin/src/lcd/tft/tft_string.cpp index 6f2d8690b2..d5ccfe323a 100644 --- a/Marlin/src/lcd/tft/tft_string.cpp +++ b/Marlin/src/lcd/tft/tft_string.cpp @@ -89,11 +89,13 @@ uint8_t read_byte(uint8_t *byte) { return *byte; } /** * Add a string, applying substitutions for the following characters: * + * $ displays an inserted C-string given by the itemString parameter * = displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder */ -void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { +void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString/*=nullptr*/) { wchar_t wchar; while (*string) { @@ -108,17 +110,15 @@ void TFT_String::add(uint8_t *string, int8_t index, uint8_t *itemString) { if (inum >= 10) { add_character('0' + (inum / 10)); inum %= 10; } add_character('0' + inum); } - else { + else add(index == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED)); - } - continue; } - else if (ch == '$' && itemString) { + else if (ch == '$' && itemString) add(itemString); - continue; - } - - add_character(ch); + else if (ch == '@') + add_character(axis_codes[index]); + else + add_character(ch); } eol(); } @@ -150,9 +150,8 @@ void TFT_String::rtrim(uint8_t character) { span -= glyph(data[length])->DWidth; eol(); } - else { + else break; - } } } From cb9fafd4f3a0dc3d963bd13664b58d3e2487d5b3 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 4 Oct 2021 18:25:45 +1300 Subject: [PATCH 0750/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Arduino=20IDE=20?= =?UTF-8?q?compile=20error=20(#22877)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp index d909767526..bf684e43f9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp @@ -21,7 +21,7 @@ #include "../../../../MarlinCore.h" - -#include "language.h" - -uint8_t lang = 0; +#if ENABLED(TOUCH_UI_FTDI_EVE) + #include "language.h" + uint8_t lang = 0; +#endif From 23f10563e03fd8f7368885b1c406a4f7c7c3d1ae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 18:22:37 -0500 Subject: [PATCH 0751/2168] =?UTF-8?q?=F0=9F=8E=A8=20Update=20F=20string=20?= =?UTF-8?q?declarations?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/Marduino.h | 7 +++++++ Marlin/src/HAL/shared/progmem.h | 3 ++- Marlin/src/core/types.h | 7 ------- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h index 56be8d7211..e7f085a68d 100644 --- a/Marlin/src/HAL/shared/Marduino.h +++ b/Marlin/src/HAL/shared/Marduino.h @@ -87,3 +87,10 @@ #endif #include "progmem.h" + +class __FlashStringHelper; +typedef const __FlashStringHelper* FSTR_P; +#ifndef FPSTR + #define FPSTR(S) (reinterpret_cast(S)) +#endif +#define FTOP(S) (reinterpret_cast(S)) diff --git a/Marlin/src/HAL/shared/progmem.h b/Marlin/src/HAL/shared/progmem.h index 539d02705e..a76b379bb8 100644 --- a/Marlin/src/HAL/shared/progmem.h +++ b/Marlin/src/HAL/shared/progmem.h @@ -38,7 +38,8 @@ #define PSTR(str) (str) #endif #ifndef F -#define F(str) (str) +class __FlashStringHelper; +#define F(str) (reinterpret_cast(PSTR(str))) #endif #ifndef _SFR_BYTE #define _SFR_BYTE(n) (n) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index e11a6cd03e..72099fb408 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -26,13 +26,6 @@ #include "../inc/MarlinConfigPre.h" -class __FlashStringHelper; -typedef const __FlashStringHelper* FSTR_P; -#ifndef FPSTR - #define FPSTR(S) (reinterpret_cast(S)) -#endif -#define FTOP(S) (reinterpret_cast(S)) - // // Conditional type assignment magic. For example... // From 59dac3a7e41ae7964686d9dff56baba821a278f7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 18:43:52 -0500 Subject: [PATCH 0752/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20G-c?= =?UTF-8?q?ode=20subcommands?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 14 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/feature/power.cpp | 4 +- Marlin/src/feature/powerloss.cpp | 12 +- Marlin/src/gcode/bedlevel/G35.cpp | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/calibrate/G34.cpp | 4 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 2 +- Marlin/src/gcode/calibrate/G425.cpp | 4 +- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 2 +- Marlin/src/gcode/control/M605.cpp | 2 +- Marlin/src/gcode/feature/L6470/M916-918.cpp | 14 +- Marlin/src/gcode/feature/clean/G12.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 9 +- Marlin/src/gcode/gcode.h | 4 +- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/gcode/queue.cpp | 8 +- Marlin/src/gcode/sd/M1001.cpp | 6 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 10 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 131 +++++++++--------- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 2 +- .../generic/spinner_dialog_box.cpp | 2 +- .../lcd/extui/mks_ui/draw_baby_stepping.cpp | 12 +- .../lcd/extui/mks_ui/draw_filament_change.cpp | 2 +- .../src/lcd/extui/mks_ui/draw_number_key.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 2 +- .../lcd/extui/mks_ui/printer_operation.cpp | 4 +- Marlin/src/module/tool_change.cpp | 6 +- 28 files changed, 136 insertions(+), 134 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 00cb5ed738..7b2280fcde 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -281,10 +281,10 @@ bool unified_bed_leveling::sanity_check() { } #endif - process_subcommands_now_P(G28_STR); // Home - process_subcommands_now_P(PSTR(ALIGN_GCODE "\n" // Align multi z axis if available - PROBE_GCODE "\n" // Build mesh with available hardware - "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice + process_subcommands_now(FPSTR(G28_STR)); // Home + process_subcommands_now(F(ALIGN_GCODE "\n" // Align multi z axis if available + PROBE_GCODE "\n" // Build mesh with available hardware + "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice if (parser.seenval('S')) { char umw_gcode[32]; @@ -292,9 +292,9 @@ bool unified_bed_leveling::sanity_check() { queue.inject(umw_gcode); } - process_subcommands_now_P(PSTR("G29A\nG29F10\n" // Set UBL Active & Fade 10 - "M140S0\nM104S0\n" // Turn off heaters - "M500")); // Store settings + process_subcommands_now(F("G29A\nG29F10\n" // Set UBL Active & Fade 10 + "M140S0\nM104S0\n" // Turn off heaters + "M500")); // Store settings } #endif // UBL_MESH_WIZARD diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 750c63f7c6..9b85b5b972 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -656,7 +656,7 @@ void unified_bed_leveling::G29() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); if (probe_deployed) { planner.synchronize(); - gcode.process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); + gcode.process_subcommands_now(F(Z_PROBE_END_SCRIPT)); } #else UNUSED(probe_deployed); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 8116bd2e44..fabe35b989 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -82,7 +82,7 @@ void Power::power_on() { TERN_(HAS_TRINAMIC_CONFIG, safe_delay(PSU_POWERUP_DELAY)); #ifdef PSU_POWERUP_GCODE - GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWERUP_GCODE)); + gcode.process_subcommands_now(F(PSU_POWERUP_GCODE)); #endif } @@ -95,7 +95,7 @@ void Power::power_off() { if (!psu_on) return; #ifdef PSU_POWEROFF_GCODE - GcodeSuite::process_subcommands_now_P(PSTR(PSU_POWEROFF_GCODE)); + gcode.process_subcommands_now(F(PSU_POWEROFF_GCODE)); #endif #if ENABLED(PS_OFF_SOUND) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 8db31daa40..a551ba4c8b 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -244,7 +244,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #if POWER_LOSS_RETRACT_LEN // Retract filament now - gcode.process_subcommands_now_P(PSTR("G1 F3000 E-" STRINGIFY(POWER_LOSS_RETRACT_LEN))); + gcode.process_subcommands_now(F("G1 F3000 E-" STRINGIFY(POWER_LOSS_RETRACT_LEN))); #endif #if POWER_LOSS_ZRAISE @@ -337,7 +337,7 @@ void PrintJobRecovery::resume() { #if HAS_LEVELING // Make sure leveling is off before any G92 and G28 - gcode.process_subcommands_now_P(PSTR("M420 S0 Z0")); + gcode.process_subcommands_now(F("M420 S0 Z0")); #endif #if HAS_HEATED_BED @@ -373,7 +373,7 @@ void PrintJobRecovery::resume() { // establish the current position as best we can. // - gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0 + gcode.process_subcommands_now(F("G92.9E0")); // Reset E to 0 #if Z_HOME_TO_MAX @@ -410,7 +410,7 @@ void PrintJobRecovery::resume() { } // Home XY with no Z raise, and also home Z here if Z isn't homing down below. - gcode.process_subcommands_now_P(PSTR("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28 + gcode.process_subcommands_now(F("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28 #endif @@ -513,7 +513,7 @@ void PrintJobRecovery::resume() { // Un-retract if there was a retract at outage #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 - gcode.process_subcommands_now_P(PSTR("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000")); + gcode.process_subcommands_now(F("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000")); #endif // Additional purge on resume if configured @@ -523,7 +523,7 @@ void PrintJobRecovery::resume() { #endif #if ENABLED(NOZZLE_CLEAN_FEATURE) - gcode.process_subcommands_now_P(PSTR("G12")); + gcode.process_subcommands_now(F("G12")); #endif // Move back over to the saved XY diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 8d5c057361..cb634d973b 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -92,7 +92,7 @@ void GcodeSuite::G35() { TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); // Home only Z axis when X and Y is trusted, otherwise all axes, if needed before this procedure - if (!all_axes_trusted()) process_subcommands_now_P(PSTR("G28Z")); + if (!all_axes_trusted()) process_subcommands_now(F("G28Z")); bool err_break = false; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 0eb13dba96..03b0450c6b 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -244,7 +244,7 @@ G29_TYPE GcodeSuite::G29() { // Send 'N' to force homing before G29 (internal only) if (parser.seen_test('N')) - process_subcommands_now_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); + process_subcommands_now(TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR))); // Don't allow auto-leveling without homing first if (homing_needed_error()) G29_RETURN(false); @@ -882,7 +882,7 @@ G29_TYPE GcodeSuite::G29() { #ifdef Z_PROBE_END_SCRIPT if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT); planner.synchronize(); - process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT)); + process_subcommands_now(F(Z_PROBE_END_SCRIPT)); #endif TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedLeveling()); diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index f335a12311..98a0bdef88 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -47,7 +47,7 @@ void GcodeSuite::G34() { TemporaryGlobalEndstopsState unlock_z(false); #ifdef GANTRY_CALIBRATION_COMMANDS_PRE - gcode.process_subcommands_now_P(PSTR(GANTRY_CALIBRATION_COMMANDS_PRE)); + process_subcommands_now(F(GANTRY_CALIBRATION_COMMANDS_PRE)); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Sub Commands Processed"); #endif @@ -148,7 +148,7 @@ void GcodeSuite::G34() { #ifdef GANTRY_CALIBRATION_COMMANDS_POST if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Running Post Commands"); - gcode.process_subcommands_now_P(PSTR(GANTRY_CALIBRATION_COMMANDS_POST)); + process_subcommands_now(F(GANTRY_CALIBRATION_COMMANDS_POST)); #endif SET_SOFT_ENDSTOP_LOOSE(false); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index dd1dd5622a..63d839c847 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -433,7 +433,7 @@ void GcodeSuite::G34() { // After this operation the z position needs correction set_axis_never_homed(Z_AXIS); // Home Z after the alignment procedure - process_subcommands_now_P(PSTR("G28Z")); + process_subcommands_now(F("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. diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 23a66dd0c5..88c906f493 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -709,7 +709,7 @@ inline void calibrate_all() { void GcodeSuite::G425() { #ifdef CALIBRATION_SCRIPT_PRE - GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_PRE)); + process_subcommands_now(F(CALIBRATION_SCRIPT_PRE)); #endif if (homing_needed_error()) return; @@ -745,7 +745,7 @@ void GcodeSuite::G425() { SET_SOFT_ENDSTOP_LOOSE(false); #ifdef CALIBRATION_SCRIPT_POST - GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_POST)); + process_subcommands_now(F(CALIBRATION_SCRIPT_POST)); #endif } diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 170958cab4..a6c4ed0287 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -158,7 +158,7 @@ void GcodeSuite::G76() { return; } - process_subcommands_now_P(G28_STR); + process_subcommands_now(FPSTR(G28_STR)); } remember_feedrate_scaling_off(); diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 08efaab59d..788659e7e2 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -110,7 +110,7 @@ set_duplication_enabled(false); #ifdef EVENT_GCODE_IDEX_AFTER_MODECHANGE - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_IDEX_AFTER_MODECHANGE)); + process_subcommands_now(F(EVENT_GCODE_IDEX_AFTER_MODECHANGE)); #endif } else if (!parser.seen('W')) // if no S or W parameter, the DXC mode gets reset to the user's default diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp index ad0a91111d..8d614603ed 100644 --- a/Marlin/src/gcode/feature/L6470/M916-918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp @@ -138,10 +138,10 @@ void GcodeSuite::M916() { do { // turn the motor(s) both directions sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); // get the status after the motors have stopped planner.synchronize(); @@ -266,10 +266,10 @@ void GcodeSuite::M917() { DEBUG_ECHOLNPGM(" OCD threshold : ", (OCD_TH_val + 1) * 375); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); planner.synchronize(); @@ -308,7 +308,7 @@ void GcodeSuite::M917() { L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold); } DEBUG_ECHOLNPGM("."); - gcode.reset_stepper_timeout(); // keep steppers powered + reset_stepper_timeout(); // keep steppers powered watchdog_refresh(); safe_delay(5000); status_composite_temp = 0; @@ -615,10 +615,10 @@ void GcodeSuite::M918() { DEBUG_ECHOLNPGM("...feedrate = ", current_feedrate); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(current_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(current_feedrate)); - gcode.process_subcommands_now_P(gcode_string); + process_subcommands_now(gcode_string); planner.synchronize(); diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index b19932eb98..a0b87b1abc 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -50,7 +50,7 @@ void GcodeSuite::G12() { #ifdef WIPE_SEQUENCE_COMMANDS if (!parser.seen_any()) { - gcode.process_subcommands_now_P(PSTR(WIPE_SEQUENCE_COMMANDS)); + process_subcommands_now(F(WIPE_SEQUENCE_COMMANDS)); return; } #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 888dbe7027..e7be0bd37f 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -242,7 +242,7 @@ void GcodeSuite::dwell(millis_t time) { host_action(PSTR(ACTION_ON_G29_RECOVER)); #endif #ifdef G29_RECOVER_COMMANDS - process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS)); + process_subcommands_now(F(G29_RECOVER_COMMANDS)); #endif } @@ -255,7 +255,7 @@ void GcodeSuite::dwell(millis_t time) { host_action(PSTR(ACTION_ON_G29_FAILURE)); #endif #ifdef G29_FAILURE_COMMANDS - process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS)); + process_subcommands_now(F(G29_FAILURE_COMMANDS)); #endif #if ENABLED(G29_HALT_ON_FAILURE) #ifdef ACTION_ON_CANCEL @@ -285,7 +285,7 @@ void GcodeSuite::dwell(millis_t time) { TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end()); #ifdef G29_SUCCESS_COMMANDS - process_subcommands_now_P(PSTR(G29_SUCCESS_COMMANDS)); + process_subcommands_now(F(G29_SUCCESS_COMMANDS)); #endif } @@ -1100,7 +1100,8 @@ void GcodeSuite::process_next_command() { * G-code "macros" to be called from within other G-code handlers. */ -void GcodeSuite::process_subcommands_now_P(PGM_P pgcode) { +void GcodeSuite::process_subcommands_now(FSTR_P fgcode) { + PGM_P pgcode = FTOP(fgcode); char * const saved_cmd = parser.command_ptr; // Save the parser state for (;;) { PGM_P const delim = strchr_P(pgcode, '\n'); // Get address of next newline diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 4a3c865a4f..e6e50e8a1c 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -397,11 +397,11 @@ public: static void process_next_command(); // Execute G-code in-place, preserving current G-code parameters - static void process_subcommands_now_P(PGM_P pgcode); + static void process_subcommands_now(FSTR_P fgcode); static void process_subcommands_now(char * gcode); static inline void home_all_axes(const bool keep_leveling=false) { - process_subcommands_now_P(keep_leveling ? G28_STR : TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); + process_subcommands_now(keep_leveling ? FPSTR(G28_STR) : TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR))); } #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 33167d9dff..0c7bdc7a3a 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -403,7 +403,7 @@ void GcodeSuite::G2_G3(const bool clockwise) { else { #if ENABLED(CNC_WORKSPACE_PLANES) char achar, bchar; - switch (gcode.workspace_plane) { + switch (workspace_plane) { default: case GcodeSuite::PLANE_XY: achar = 'I'; bchar = 'J'; break; case GcodeSuite::PLANE_YZ: achar = 'J'; bchar = 'K'; break; diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index d11b2823f2..8ffa043b51 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -693,8 +693,8 @@ void GCodeQueue::advance() { void GCodeQueue::report_buffer_statistics() { SERIAL_ECHOLNPGM("D576" - " P:", planner.moves_free(), " ", -queue.planner_buffer_underruns, " (", queue.max_planner_buffer_empty_duration, ")" - " B:", BUFSIZE - ring_buffer.length, " ", -queue.command_buffer_underruns, " (", queue.max_command_buffer_empty_duration, ")" + " P:", planner.moves_free(), " ", -planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" + " B:", BUFSIZE - ring_buffer.length, " ", -command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" ); command_buffer_underruns = planner_buffer_underruns = 0; max_command_buffer_empty_duration = max_planner_buffer_empty_duration = 0; @@ -717,8 +717,8 @@ void GCodeQueue::advance() { NOLESS(max_planner_buffer_empty_duration, planner_buffer_empty_duration); // if it's longer than the currently tracked max duration, replace it } - if (queue.auto_buffer_report_interval && ELAPSED(ms, queue.next_buffer_report_ms)) { - queue.next_buffer_report_ms = ms + 1000UL * queue.auto_buffer_report_interval; + if (auto_buffer_report_interval && ELAPSED(ms, next_buffer_report_ms)) { + next_buffer_report_ms = ms + 1000UL * auto_buffer_report_interval; PORT_REDIRECT(SERIAL_BOTH); report_buffer_statistics(); PORT_RESTORE(); diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index f5ee6a94d1..d436d88817 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -77,10 +77,10 @@ void GcodeSuite::M1001() { // Report total print time const bool long_print = print_job_timer.duration() > 60; - if (long_print) gcode.process_subcommands_now_P(PSTR("M31")); + if (long_print) process_subcommands_now(F("M31")); // Stop the print job timer - gcode.process_subcommands_now_P(PSTR("M77")); + process_subcommands_now(F("M77")); // Set the progress bar "done" state TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress_done()); @@ -104,7 +104,7 @@ void GcodeSuite::M1001() { // Inject SD_FINISHED_RELEASECOMMAND, if any #ifdef SD_FINISHED_RELEASECOMMAND - gcode.process_subcommands_now_P(PSTR(SD_FINISHED_RELEASECOMMAND)); + process_subcommands_now(F(SD_FINISHED_RELEASECOMMAND)); #endif TERN_(EXTENSIBLE_UI, ExtUI::onPrintFinished()); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 8bb5a155ee..c56608a13c 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -2172,7 +2172,7 @@ void SetMoveZto0() { dtostrf(Y_CENTER, 1, 1, str_2) #endif ); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); ui.set_status_P(PSTR("Now adjust Z Offset")); HMI_AudioFeedback(true); @@ -2185,7 +2185,7 @@ void SetPID(celsius_t t, heater_id_t h) { dtostrf(X_CENTER, 1, 1, str_1), dtostrf(Y_CENTER, 1, 1, str_2) ); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); thermalManager.PID_autotune(t, h, HMI_data.PidCycles, true); } @@ -2375,7 +2375,7 @@ void LevBed(uint8_t point) { #if HAS_ONESTEP_LEVELING planner.synchronize(); - gcode.process_subcommands_now_P(PSTR("M420S0\nG28O")); + gcode.process_subcommands_now(F("M420S0\nG28O")); planner.synchronize(); zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); sprintf_P(cmd, PSTR(fmt), @@ -2401,7 +2401,7 @@ void LevBedC () { LevBed(4); } void ManualMeshStart(){ ui.set_status_P(GET_TEXT(MSG_UBL_BUILD_MESH_MENU)); - gcode.process_subcommands_now_P(PSTR("G28 XYO\nG28 Z\nM211 S0\nG29S1")); + gcode.process_subcommands_now(F("G28 XYO\nG28 Z\nM211 S0\nG29S1")); planner.synchronize(); #ifdef MANUAL_PROBE_START_Z const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); @@ -2419,7 +2419,7 @@ void LevBedC () { LevBed(4); } void SetMMeshMoveZ() { SetPFloatOnClick(-1, 1, 2, planner.synchronize, LiveMeshMoveZ);} void ManualMeshContinue(){ - gcode.process_subcommands_now_P(PSTR("G29S2")); + gcode.process_subcommands_now(F("G29S2")); planner.synchronize(); MMeshMoveZItem->draw(CurrentMenu->line(MMeshMoveZItem->pos)); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 6d4f8b0a3a..2bdb15a30f 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -207,7 +207,7 @@ CrealityDWINClass CrealityDWIN; void manual_value_update(bool undefined=false) { sprintf_P(cmd, PSTR("M421 I%i J%i Z%s %s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1), undefined ? "N" : ""); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); } @@ -267,7 +267,7 @@ CrealityDWINClass CrealityDWIN; void manual_value_update() { sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); } @@ -283,9 +283,9 @@ CrealityDWINClass CrealityDWIN; else { CrealityDWIN.Popup_Handler(MoveWait); sprintf_P(cmd, PSTR("G0 F300 Z%s"), dtostrf(Z_CLEARANCE_BETWEEN_PROBES, 1, 3, str_1)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); current_position.z = goto_mesh_value ? Z_VALUES_ARR[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); @@ -1116,7 +1116,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ } Popup_Handler(FilChange); sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); } #endif } @@ -1156,7 +1156,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_MoveX, "Home X"); else { Popup_Handler(Home); - gcode.process_subcommands_now_P(PSTR("G28 X")); + gcode.process_subcommands_now(F("G28 X")); planner.synchronize(); Redraw_Menu(); } @@ -1166,7 +1166,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_MoveY, "Home Y"); else { Popup_Handler(Home); - gcode.process_subcommands_now_P(PSTR("G28 Y")); + gcode.process_subcommands_now(F("G28 Y")); planner.synchronize(); Redraw_Menu(); } @@ -1176,7 +1176,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_MoveZ,"Home Z"); else { Popup_Handler(Home); - gcode.process_subcommands_now_P(PSTR("G28 Z")); + gcode.process_subcommands_now(F("G28 Z")); planner.synchronize(); Redraw_Menu(); } @@ -1185,7 +1185,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_SetHome, "Set Home Position"); else { - gcode.process_subcommands_now_P(PSTR("G92 X0 Y0 Z0")); + gcode.process_subcommands_now(F("G92 X0 Y0 Z0")); AudioFeedback(); } break; @@ -1350,14 +1350,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (use_probe) { #if HAS_BED_PROBE sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Popup_Handler(ManualProbing); #endif } else { sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -1371,14 +1371,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (use_probe) { #if HAS_BED_PROBE sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Popup_Handler(ManualProbing); #endif } else { sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -1392,14 +1392,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (use_probe) { #if HAS_BED_PROBE sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Popup_Handler(ManualProbing); #endif } else { sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -1413,14 +1413,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (use_probe) { #if HAS_BED_PROBE sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Popup_Handler(ManualProbing); #endif } else { sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -1434,14 +1434,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (use_probe) { #if HAS_BED_PROBE sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(X_MAX_POS / 2.0f - probe.offset.x, 1, 3, str_1), dtostrf(Y_MAX_POS / 2.0f - probe.offset.y, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Popup_Handler(ManualProbing); #endif } else { sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -1484,16 +1484,16 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_Homing, "Home Z Axis"); else { Popup_Handler(Home); - gcode.process_subcommands_now_P(PSTR("G28 Z")); + gcode.process_subcommands_now(F("G28 Z")); Popup_Handler(MoveWait); #if ENABLED(Z_SAFE_HOMING) planner.synchronize(); sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); #else - gcode.process_subcommands_now_P(PSTR("G0 F4000 X117.5 Y117.5")); + gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); #endif - gcode.process_subcommands_now_P(PSTR("G0 F300 Z0")); + gcode.process_subcommands_now(F("G0 F300 Z0")); planner.synchronize(); Redraw_Menu(); } @@ -1513,11 +1513,11 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(Z_SAFE_HOMING) planner.synchronize(); sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); #else - gcode.process_subcommands_now_P(PSTR("G0 F4000 X117.5 Y117.5")); + gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); #endif - gcode.process_subcommands_now_P(PSTR("G0 F300 Z0")); + gcode.process_subcommands_now(F("G0 F300 Z0")); planner.synchronize(); Redraw_Menu(); } @@ -1539,7 +1539,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ else { if (zoffsetvalue < MAX_Z_OFFSET) { if (liveadjust) { - gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + gcode.process_subcommands_now(F("M290 Z0.01")); planner.synchronize(); } zoffsetvalue += 0.01; @@ -1553,7 +1553,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ else { if (zoffsetvalue > MIN_Z_OFFSET) { if (liveadjust) { - gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + gcode.process_subcommands_now(F("M290 Z-0.01")); planner.synchronize(); } zoffsetvalue -= 0.01; @@ -1721,7 +1721,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ thermalManager.wait_for_hotend(0); } Popup_Handler(FilLoad); - gcode.process_subcommands_now_P(PSTR("M701")); + gcode.process_subcommands_now(F("M701")); planner.synchronize(); Redraw_Menu(); } @@ -1740,7 +1740,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ thermalManager.wait_for_hotend(0); } Popup_Handler(FilLoad, true); - gcode.process_subcommands_now_P(PSTR("M702")); + gcode.process_subcommands_now(F("M702")); planner.synchronize(); Redraw_Menu(); } @@ -1759,7 +1759,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ } Popup_Handler(FilChange); sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); } } break; @@ -2016,7 +2016,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ else { Popup_Handler(PIDWait); sprintf_P(cmd, PSTR("M303 E0 C%i S%i U1"), PID_cycles, PID_e_temp); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -2083,7 +2083,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ else { Popup_Handler(PIDWait); sprintf_P(cmd, PSTR("M303 E-1 C%i S%i U1"), PID_cycles, PID_bed_temp); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); planner.synchronize(); Redraw_Menu(); } @@ -3029,7 +3029,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_StepY, "M48 Probe Test"); else { sprintf_P(cmd, PSTR("G28O\nM48 X%s Y%s P%i"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), testcount); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); } break; case PROBE_TEST_COUNT: @@ -3141,11 +3141,12 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Popup_Handler(Home); gcode.home_all_axes(true); Popup_Handler(Level); - if (mesh_conf.tilt_grid > 1) + if (mesh_conf.tilt_grid > 1) { sprintf_P(cmd, PSTR("G29 J%i"), mesh_conf.tilt_grid); + gcode.process_subcommands_now(cmd); + } else - sprintf_P(cmd, PSTR("G29 J")); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(F("G29 J")); planner.synchronize(); Redraw_Menu(); } @@ -3173,8 +3174,8 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif #if HAS_BED_PROBE Popup_Handler(Level); - gcode.process_subcommands_now_P(PSTR("G29 P0\nG29 P1")); - gcode.process_subcommands_now_P(PSTR("G29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nM420 S1")); + gcode.process_subcommands_now(F("G29 P0\nG29 P1")); + gcode.process_subcommands_now(F("G29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nM420 S1")); planner.synchronize(); Update_Status("Probed all reachable points"); Popup_Handler(SaveLevel); @@ -3189,7 +3190,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif #elif HAS_BED_PROBE Popup_Handler(Level); - gcode.process_subcommands_now_P(PSTR("G29")); + gcode.process_subcommands_now(F("G29")); planner.synchronize(); Popup_Handler(SaveLevel); #else @@ -3197,7 +3198,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ set_bed_leveling_enabled(false); gridpoint = 1; Popup_Handler(MoveWait); - gcode.process_subcommands_now_P(PSTR("G29")); + gcode.process_subcommands_now(F("G29")); planner.synchronize(); Draw_Menu(ManualMesh); #endif @@ -3280,7 +3281,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Popup_Handler(MeshSlot); break; } - gcode.process_subcommands_now_P(PSTR("G29 L")); + gcode.process_subcommands_now(F("G29 L")); planner.synchronize(); AudioFeedback(true); } @@ -3293,7 +3294,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Popup_Handler(MeshSlot); break; } - gcode.process_subcommands_now_P(PSTR("G29 S")); + gcode.process_subcommands_now(F("G29 S")); planner.synchronize(); AudioFeedback(true); } @@ -3389,7 +3390,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_ResumeEEPROM, "Convert Mesh to Plane"); else { if (mesh_conf.create_plane_from_mesh()) break; - gcode.process_subcommands_now_P(PSTR("M420 S1")); + gcode.process_subcommands_now(F("M420 S1")); planner.synchronize(); AudioFeedback(true); } @@ -3497,7 +3498,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + gcode.process_subcommands_now(F("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); @@ -3509,7 +3510,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + gcode.process_subcommands_now(F("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); @@ -3580,7 +3581,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ mesh_conf.manual_move(); } else { - gcode.process_subcommands_now_P(PSTR("G29 S")); + gcode.process_subcommands_now(F("G29 S")); planner.synchronize(); AudioFeedback(true); Draw_Menu(Leveling, LEVELING_GET_MESH); @@ -3618,7 +3619,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + gcode.process_subcommands_now(F("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); @@ -3630,7 +3631,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(row, ICON_Axis, "Microstep Down"); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + gcode.process_subcommands_now(F("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); @@ -3657,7 +3658,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_Back, "Cancel"); else { - gcode.process_subcommands_now_P(PSTR("G29 A")); + gcode.process_subcommands_now(F("G29 A")); planner.synchronize(); set_bed_leveling_enabled(level_state); Draw_Menu(Leveling, LEVELING_GET_MESH); @@ -3672,13 +3673,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ } else if (gridpoint < GRID_MAX_POINTS) { Popup_Handler(MoveWait); - gcode.process_subcommands_now_P(PSTR("G29")); + gcode.process_subcommands_now(F("G29")); planner.synchronize(); gridpoint++; Redraw_Menu(); } else { - gcode.process_subcommands_now_P(PSTR("G29")); + gcode.process_subcommands_now(F("G29")); planner.synchronize(); AudioFeedback(settings.save()); Draw_Menu(Leveling, LEVELING_GET_MESH); @@ -3697,7 +3698,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); else if (current_position.z < MAX_Z_OFFSET) { - gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + gcode.process_subcommands_now(F("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); @@ -3708,7 +3709,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); else if (current_position.z > MIN_Z_OFFSET) { - gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + gcode.process_subcommands_now(F("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); @@ -3829,7 +3830,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_Axis, "Z-Offset Up"); else if (zoffsetvalue < MAX_Z_OFFSET) { - gcode.process_subcommands_now_P(PSTR("M290 Z0.01")); + gcode.process_subcommands_now(F("M290 Z0.01")); zoffsetvalue += 0.01; Draw_Float(zoffsetvalue, row - 1, false, 100); } @@ -3838,7 +3839,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_AxisD, "Z-Offset Down"); else if (zoffsetvalue > MIN_Z_OFFSET) { - gcode.process_subcommands_now_P(PSTR("M290 Z-0.01")); + gcode.process_subcommands_now(F("M290 Z-0.01")); zoffsetvalue -= 0.01; Draw_Float(zoffsetvalue, row - 2, false, 100); } @@ -3916,27 +3917,27 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case Prepare: Popup_Handler(FilChange); sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); break; #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) case ChangeFilament: switch (last_selection) { case CHANGEFIL_LOAD: Popup_Handler(FilLoad); - gcode.process_subcommands_now_P("M701"); + gcode.process_subcommands_now(F("M701")); planner.synchronize(); Redraw_Menu(true, true, true); break; case CHANGEFIL_UNLOAD: Popup_Handler(FilLoad, true); - gcode.process_subcommands_now_P("M702"); + gcode.process_subcommands_now(F("M702")); planner.synchronize(); Redraw_Menu(true, true, true); break; case CHANGEFIL_CHANGE: Popup_Handler(FilChange); sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); break; } break; @@ -4275,7 +4276,7 @@ void CrealityDWINClass::Value_Control() { } else if (active_menu == Tune && selection == TUNE_ZOFFSET) { sprintf_P(cmd, PSTR("M290 Z%s"), dtostrf((tempvalue / valueunit - zoffsetvalue), 1, 3, str_1)); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); } if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) tempvalue = scalePID_i(tempvalue); @@ -4474,11 +4475,11 @@ void CrealityDWINClass::Print_Screen_Control() { char cmnd[20]; #if HAS_HEATED_BED cmnd[sprintf_P(cmnd, PSTR("M140 S%i"), pausebed)] = '\0'; - gcode.process_subcommands_now_P(PSTR(cmnd)); + gcode.process_subcommands_now(cmnd); #endif #if HAS_EXTRUDERS cmnd[sprintf_P(cmnd, PSTR("M109 S%i"), pausetemp)] = '\0'; - gcode.process_subcommands_now_P(PSTR(cmnd)); + gcode.process_subcommands_now(cmnd); #endif TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); planner.synchronize(); @@ -4603,7 +4604,7 @@ void CrealityDWINClass::Popup_Control() { } Popup_Handler(FilChange); sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); - gcode.process_subcommands_now_P(cmd); + gcode.process_subcommands_now(cmd); } } else @@ -4626,7 +4627,7 @@ void CrealityDWINClass::Popup_Control() { case SaveLevel: if (selection == 0) { #if ENABLED(AUTO_BED_LEVELING_UBL) - gcode.process_subcommands_now_P(PSTR("G29 S")); + gcode.process_subcommands_now(F("G29 S")); planner.synchronize(); AudioFeedback(true); #else diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 60c3790882..2ec67b2727 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -262,7 +262,7 @@ void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { void DGUSScreenHandler::SDPrintingFinished() { if (DGUSAutoTurnOff) { queue.exhaust(); - gcode.process_subcommands_now_P(PSTR("M81")); + gcode.process_subcommands_now(F("M81")); } GotoScreen(MKSLCD_SCREEN_PrintDone); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 9117bcee10..2493de795a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -99,7 +99,7 @@ void SpinnerDialogBox::enqueueAndWait(FSTR_P message, char *commands) { } void SpinnerDialogBox::onIdle() { - if (mydata.auto_hide && !commandsInQueue() && TERN1(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state == GcodeSuite::NOT_BUSY)) { + if (mydata.auto_hide && !commandsInQueue() && TERN1(HOST_KEEPALIVE_FEATURE, gcode.busy_state == gcode.NOT_BUSY)) { mydata.auto_hide = false; hide(); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp index c7e6a62341..65617fa9bb 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.cpp @@ -65,32 +65,32 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_BABY_STEP_X_P: sprintf_P(baby_buf, PSTR("M290 X%s"), dtostrf(babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_X_N: sprintf_P(baby_buf, PSTR("M290 X%s"), dtostrf(-babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_Y_P: sprintf_P(baby_buf, PSTR("M290 Y%s"), dtostrf(babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_Y_N: sprintf_P(baby_buf, PSTR("M290 Y%s"), dtostrf(-babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_Z_P: sprintf_P(baby_buf, PSTR("M290 Z%s"), dtostrf(babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_Z_N: sprintf_P(baby_buf, PSTR("M290 Z%s"), dtostrf(-babystep_dist, 1, 3, str_1)); - gcode.process_subcommands_now_P(PSTR(baby_buf)); + gcode.process_subcommands_now(F(baby_buf)); has_adjust_z = 1; break; case ID_BABY_STEP_DIST: diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp index 8432c74b1a..61d212303b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.cpp @@ -94,7 +94,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_FILAMNT_RETURN: #if HAS_MULTI_EXTRUDER if (uiCfg.print_state != IDLE && uiCfg.print_state != REPRINTED) - gcode.process_subcommands_now_P(uiCfg.extruderIndexBak == 1 ? PSTR("T1") : PSTR("T0")); + gcode.process_subcommands_now(uiCfg.extruderIndexBak == 1 ? F("T1") : F("T0")); #endif feedrate_mm_s = (float)uiCfg.moveSpeed_bak; if (uiCfg.print_state == PAUSED) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp index a3cb7f6c1c..630bb4efef 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -404,7 +404,7 @@ static void set_value_confirm() { case z_sensitivity: TERN_(Z_SENSORLESS, stepperZ.homing_threshold(atoi(key_value))); break; case z2_sensitivity: TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(atoi(key_value))); break; } - gcode.process_subcommands_now_P(PSTR("M500")); + gcode.process_subcommands_now(F("M500")); } static void event_handler(lv_obj_t *obj, lv_event_t event) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index 58bbbfbd5b..322d0581ca 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -307,7 +307,7 @@ void setProBarRate() { #if HAS_SUICIDE if (gCfgItems.finish_power_off) { - gcode.process_subcommands_now_P(PSTR("M1001")); + gcode.process_subcommands_now(F("M1001")); queue.inject_P(PSTR("M81")); marlin_state = MF_RUNNING; } diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 04d8f16fcc..8f5b89cf34 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -53,7 +53,7 @@ void printer_state_polling() { uiCfg.waitEndMoves = 0; planner.synchronize(); - gcode.process_subcommands_now_P(PSTR("M25")); + gcode.process_subcommands_now(F("M25")); // save the position uiCfg.current_x_position_bak = current_position.x; @@ -93,7 +93,7 @@ void printer_state_polling() { sprintf_P(public_buf_m, PSTR("G1 Z%s"), dtostrf(uiCfg.current_z_position_bak, 1, 1, str_1)); gcode.process_subcommands_now(public_buf_m); } - gcode.process_subcommands_now_P(M24_STR); + gcode.process_subcommands_now(FPSTR(M24_STR)); uiCfg.print_state = WORKING; start_print_time(); diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index cb551647d7..b695c9408c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1310,17 +1310,17 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (!no_move) { #ifdef EVENT_GCODE_TOOLCHANGE_T0 if (new_tool == 0) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0)); + gcode.process_subcommands_now(F(EVENT_GCODE_TOOLCHANGE_T0)); #endif #ifdef EVENT_GCODE_TOOLCHANGE_T1 if (new_tool == 1) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1)); + gcode.process_subcommands_now(F(EVENT_GCODE_TOOLCHANGE_T1)); #endif #ifdef EVENT_GCODE_AFTER_TOOLCHANGE if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); + gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_TOOLCHANGE)); #endif } From 64a919da2a6dbe8b529c3471935a6d632420ca3a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Sep 2021 05:59:03 -0500 Subject: [PATCH 0753/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20E3V?= =?UTF-8?q?2=20titles,=20popups?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/lcd/M0_M1.cpp | 5 +- Marlin/src/lcd/e3v2/common/dwin_api.h | 7 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 52 ++- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 73 +-- Marlin/src/lcd/e3v2/enhanced/dwin.h | 30 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 642 +++++++++++++------------- Marlin/src/lcd/e3v2/jyersui/dwin.h | 6 +- 7 files changed, 429 insertions(+), 386 deletions(-) diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 9ba6ed5fc7..241f11c813 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -71,7 +71,10 @@ void GcodeSuite::M0_M1() { else ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) - DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg ?: GET_TEXT(MSG_STOPPED), GET_TEXT(MSG_USERWAIT)); + if (parser.string_arg) + DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); + else + DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT)); #else if (parser.string_arg) { diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index 735907e4a4..11b065e420 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -174,9 +174,10 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // rlimit: For draw less chars than string length use rlimit void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF); -inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P title) { - // Note that this won't work on AVR, only 32-bit systems! - DWIN_Draw_String(bShow, size, color, bColor, x, y, FTOP(title)); +inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P const ftitle) { + char ctitle[strlen_P(FTOP(ftitle)) + 1]; + strcpy_P(ctitle, FTOP(ftitle)); + DWIN_Draw_String(bShow, size, color, bColor, x, y, ctitle); } // Draw a positive integer diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 006ff5db26..54fa6f941b 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -359,12 +359,8 @@ inline void Clear_Title_Bar() { DWIN_Draw_Box(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, TITLE_HEIGHT); } -void Draw_Title(const char * const title) { - DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); -} - -void Draw_Title(FSTR_P title) { - DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); +void Draw_Title(FSTR_P ftitle) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, ftitle); } inline void Clear_Menu_Area() { @@ -420,32 +416,40 @@ inline uint16_t nr_sd_menu_items() { return card.get_num_Files() + !card.flag.workDirIsRoot; } -void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { - DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); -} - void Erase_Menu_Text(const uint8_t line) { DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); } -void Draw_Menu_Item(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { - if (label) DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); +void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { + DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); +} + +void _Decorate_Menu_Item(const uint8_t line, const uint8_t icon, bool more) { if (icon) Draw_Menu_Icon(line, icon); if (more) Draw_More_Icon(line); } +void Draw_Menu_Item(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { + if (label) DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); + _Decorate_Menu_Item(line, icon, more); +} +void Draw_Menu_Item(const uint8_t line, const uint8_t icon=0, FSTR_P const flabel=nullptr, bool more=false) { + if (flabel) DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, flabel); + _Decorate_Menu_Item(line, icon, more); +} void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { Draw_Menu_Item(line, icon, label, more); DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } -void Draw_Menu_LineF(const uint8_t line, const uint8_t icon=0, FSTR_P label=nullptr, bool more=false) { - Draw_Menu_Line(line, icon, (char*)label, more); +void Draw_Menu_Line(const uint8_t line, const uint8_t icon, FSTR_P const flabel, bool more=false) { + Draw_Menu_Item(line, icon, flabel, more); + DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } void Draw_Checkbox_Line(const uint8_t line, const bool ison) { const uint16_t x = 225, y = EBASE(line) - 2; - DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x + 5, y, F(ison ? "X" : " ")); + DWIN_Draw_String(true, font8x16, Color_White, Color_Bg_Black, x + 5, y, ison ? F("X") : F(" ")); DWIN_Draw_Rectangle(0, Color_White, x + 2, y + 2, x + 16, y + 16); } @@ -1853,7 +1857,7 @@ void Draw_SDItem(const uint16_t item, int16_t row=-1) { if (row < 0) row = item + 1 + MROWS - index_file; const bool is_subdir = !card.flag.workDirIsRoot; if (is_subdir && item == 0) { - Draw_Menu_Line(row, ICON_Folder, ".."); + Draw_Menu_Line(row, ICON_Folder, F("..")); return; } @@ -2531,7 +2535,7 @@ void Item_HomeOffs_X(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X)); + Draw_Menu_Line(row, ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X)); #else say_home_offs_en(row); say_x_en(75, row); // "Home Offset X" #endif @@ -2546,7 +2550,7 @@ void Item_HomeOffs_Y(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); + Draw_Menu_Line(row, ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y)); #else say_home_offs_en(row); say_y_en(75, row); // "Home Offset X" #endif @@ -2561,7 +2565,7 @@ void Item_HomeOffs_Z(const uint8_t row) { } else { #ifdef USE_STRING_TITLES - Draw_Menu_LineF(row, ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); + Draw_Menu_Line(row, ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z)); #else say_home_offs_en(row); say_z_en(75, row); // "Home Offset Z" #endif @@ -2604,8 +2608,8 @@ void Draw_HomeOff_Menu() { DWIN_Frame_TitleCopy(124, 431, 91, 12); // "Probe Offsets" #endif #ifdef USE_STRING_TITLES - Draw_Menu_LineF(1, ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset - Draw_Menu_LineF(2, ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset + Draw_Menu_Line(1, ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET)); // Probe X Offset + Draw_Menu_Line(2, ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET)); // Probe Y Offset #else say_probe_offs_en(1); say_x_en(75, 1); // "Probe Offset X" say_probe_offs_en(2); say_y_en(75, 2); // "Probe Offset Y" @@ -3090,7 +3094,7 @@ void HMI_Temperature() { } else { #ifdef USE_STRING_HEADINGS - Draw_Title(PREHEAT_1_LABEL " Settings"); // TODO: GET_TEXT_F + Draw_Title(F(PREHEAT_1_LABEL " Settings")); // TODO: GET_TEXT_F #else DWIN_Frame_TitleCopy(56, 15, 85, 14); // "Temperature" TODO: "PLA Settings" #endif @@ -3169,7 +3173,7 @@ void HMI_Temperature() { } else { #ifdef USE_STRING_HEADINGS - Draw_Title("ABS Settings"); // TODO: GET_TEXT_F + Draw_Title(F("ABS Settings")); // TODO: GET_TEXT_F #else DWIN_Frame_TitleCopy(56, 15, 85, 14); // "Temperature" TODO: "ABS Settings" #endif @@ -3252,7 +3256,7 @@ void Draw_Max_Speed_Menu() { } else { #ifdef USE_STRING_HEADINGS - Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F + Draw_Title(F("Max Speed (mm/s)")); // TODO: GET_TEXT_F #else DWIN_Frame_TitleCopy(144, 16, 46, 11); // "Max Speed (mm/s)" #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index c56608a13c..dcadc78a5c 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -486,24 +486,31 @@ void Clear_Popup_Area() { DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); } -void DWIN_Draw_Popup(uint8_t icon=0, const char * const msg1=nullptr, const char * const msg2=nullptr, uint8_t button=0) { +void DWIN_Draw_Popup1(const uint8_t icon) { DWINUI::ClearMenuArea(); Draw_Popup_Bkgd_60(); if (icon) DWINUI::Draw_Icon(icon, 101, 105); - if (msg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, msg1); - if (msg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, msg2); +} +void DWIN_Draw_Popup2(FSTR_P const fmsg2, uint8_t button) { + if (fmsg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, fmsg2); if (button) DWINUI::Draw_Icon(button, 86, 280); } -void DWIN_Popup_Confirm(uint8_t icon, const char * const msg1, const char * const msg2) { - HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, msg1, msg2, ICON_Confirm_E); // Button Confirm - DWIN_UpdateLCD(); +void DWIN_Draw_Popup(const uint8_t icon, const char * const cmsg1, FSTR_P const fmsg2, uint8_t button) { + DWIN_Draw_Popup1(icon); + if (cmsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, cmsg1); + DWIN_Draw_Popup2(fmsg2, button); } -void DWIN_Popup_Continue(uint8_t icon, const char * const msg1, const char * const msg2) { +void DWIN_Draw_Popup(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2, uint8_t button) { + DWIN_Draw_Popup1(icon); + if (fmsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, fmsg1); + DWIN_Draw_Popup2(fmsg2, button); +} + +void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2) { HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, msg1, msg2, ICON_Continue_E); // Button Continue + DWIN_Draw_Popup(icon, fmsg1, fmsg2, ICON_Continue_E); // Button Continue DWIN_UpdateLCD(); } @@ -521,7 +528,7 @@ void DWIN_Popup_Continue(uint8_t icon, const char * const msg1, const char * con DWIN_UpdateLCD(); } else - DWIN_Popup_Confirm(ICON_TempTooLow, "Nozzle is too cold", "Preheat the hotend"); + DWIN_Popup_Confirm(ICON_TempTooLow, F("Nozzle is too cold"), F("Preheat the hotend")); } #endif @@ -565,7 +572,7 @@ void Popup_window_PauseOrStop() { DWINUI::Draw_Icon(ICON_Cancel_C, 146, 280); } else { - DWIN_Draw_Popup(ICON_BLTouch, "Please confirm", select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT(MSG_PAUSE_PRINT) : GET_TEXT(MSG_STOP_PRINT)); + DWIN_Draw_Popup(ICON_BLTouch, F("Please confirm"), select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT_F(MSG_PAUSE_PRINT) : GET_TEXT_F(MSG_STOP_PRINT)); DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); } @@ -1386,7 +1393,7 @@ void HMI_PauseOrStop() { #ifdef ACTION_ON_CANCEL host_action_cancel(); #endif - DWIN_Draw_Popup(ICON_BLTouch, "Stopping..." , "Please wait until done."); + DWIN_Draw_Popup(ICON_BLTouch, F("Stopping...") , F("Please wait until done.")); } else Goto_PrintProcess(); // cancel stop @@ -1644,7 +1651,7 @@ void HMI_SaveProcessID(const uint8_t id) { void DWIN_StartHoming() { HMI_flag.home_flag = true; HMI_SaveProcessID(Homing); - DWIN_Draw_Popup(ICON_BLTouch, "Axis Homing", "Please wait until done."); + DWIN_Draw_Popup(ICON_BLTouch, F("Axis Homing"), F("Please wait until done.")); } void DWIN_CompletedHoming() { @@ -1659,7 +1666,7 @@ void DWIN_CompletedHoming() { void DWIN_MeshLevelingStart() { #if HAS_ONESTEP_LEVELING HMI_SaveProcessID(Leveling); - DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT(MSG_BED_LEVELING), "Please wait until done."); + DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), F("Please wait until done.")); #elif ENABLED(MESH_BED_LEVELING) Draw_ManualMesh_Menu(); #endif @@ -1682,27 +1689,27 @@ void DWIN_PidTuning(pidresult_t result) { switch (result) { case PID_BED_START: HMI_SaveProcessID(NothingToDo); - DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT(MSG_PID_AUTOTUNE), "for BED is running."); + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for BED is running.")); break; case PID_EXTR_START: HMI_SaveProcessID(NothingToDo); - DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT(MSG_PID_AUTOTUNE), "for Nozzle is running."); + DWIN_Draw_Popup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for Nozzle is running.")); break; case PID_BAD_EXTRUDER_NUM: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooLow, "PID Autotune failed!", "Bad extruder"); + DWIN_Popup_Confirm(ICON_TempTooLow, F("PID Autotune failed!"), F("Bad extruder")); break; case PID_TUNING_TIMEOUT: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooHigh, "Error", GET_TEXT(MSG_PID_TIMEOUT)); + DWIN_Popup_Confirm(ICON_TempTooHigh, F("Error"), GET_TEXT_F(MSG_PID_TIMEOUT)); break; case PID_TEMP_TOO_HIGH: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooHigh, "PID Autotune failed!", "Temperature too high"); + DWIN_Popup_Confirm(ICON_TempTooHigh, F("PID Autotune failed!"), F("Temperature too high")); break; case PID_DONE: checkkey = last_checkkey; - DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT(MSG_PID_AUTOTUNE), GET_TEXT(MSG_BUTTON_DONE)); + DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); break; default: checkkey = last_checkkey; @@ -1864,24 +1871,24 @@ void DWIN_Redraw_screen() { #if ENABLED(ADVANCED_PAUSE_FEATURE) - void DWIN_Popup_Pause(const char *msg, uint8_t button = 0) { + void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button = 0) { HMI_SaveProcessID(button ? WaitResponse : NothingToDo); - DWIN_Draw_Popup(ICON_BLTouch, "Advanced Pause", msg, button); + DWIN_Draw_Popup(ICON_BLTouch, F("Advanced Pause"), fmsg, button); ui.reset_status(true); } void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { switch (message) { - case PAUSE_MESSAGE_PARKING: DWIN_Popup_Pause(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); break; - case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); break; - case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); break; - case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING), ICON_Continue_E); break; - case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, "Advanced Pause", GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); break; - case PAUSE_MESSAGE_LOAD: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); break; - case PAUSE_MESSAGE_PURGE: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE)); break; + case PAUSE_MESSAGE_PARKING: DWIN_Popup_Pause(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); break; + case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); break; + case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); break; + case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING), ICON_Continue_E); break; + case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, F("Advanced Pause"), GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); break; + case PAUSE_MESSAGE_LOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); break; + case PAUSE_MESSAGE_PURGE: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)); break; case PAUSE_MESSAGE_OPTION: DWIN_Popup_FilamentPurge(); break; - case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); break; - case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT), ICON_Continue_E); break; + case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); break; + case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT), ICON_Continue_E); break; case PAUSE_MESSAGE_HEATING: ui.set_status_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); break; case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; default: break; @@ -1889,7 +1896,7 @@ void DWIN_Redraw_screen() { } void Draw_Popup_FilamentPurge() { - DWIN_Draw_Popup(ICON_BLTouch, "Advanced Pause", "Purge or Continue?"); + DWIN_Draw_Popup(ICON_BLTouch, F("Advanced Pause"), F("Purge or Continue?")); DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); DWINUI::Draw_Icon(ICON_Continue_E, 146, 280); Draw_Select_Highlight(true); @@ -1928,7 +1935,7 @@ void DWIN_Redraw_screen() { #if HAS_MESH void DWIN_MeshViewer() { if (!leveling_is_valid()) - DWIN_Popup_Continue(ICON_BLTouch, "Mesh viewer", "No valid mesh"); + DWIN_Popup_Continue(ICON_BLTouch, F("Mesh viewer"), F("No valid mesh")); else { HMI_SaveProcessID(WaitResponse); MeshViewer.Draw(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 6b131592a8..f71d54b482 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -152,16 +152,6 @@ extern HMI_data_t HMI_data; extern uint8_t checkkey; extern millis_t dwin_heat_time; -// Popup windows -void DWIN_Popup_Confirm(uint8_t icon, const char * const msg1, const char * const msg2); -#if HAS_HOTEND || HAS_HEATED_BED - void DWIN_Popup_Temperature(const bool toohigh); -#endif -#if HAS_HOTEND - void Popup_Window_ETempTooLow(); -#endif -void Popup_Window_Resume(); - // SD Card void HMI_SDCardInit(); void HMI_SDCardUpdate(); @@ -278,3 +268,23 @@ void Draw_Steps_Menu(); #if EITHER(HAS_BED_PROBE, BABYSTEPPING) void Draw_ZOffsetWiz_Menu(); #endif + +// Popup windows + +void DWIN_Draw_Popup(const uint8_t icon, const char * const cmsg1, FSTR_P const fmsg2, uint8_t button=0); +void DWIN_Draw_Popup(const uint8_t icon, FSTR_P const fmsg1=nullptr, FSTR_P const fmsg2=nullptr, uint8_t button=0); + +template +void DWIN_Popup_Confirm(const uint8_t icon, T amsg1, U amsg2) { + HMI_SaveProcessID(WaitResponse); + DWIN_Draw_Popup(icon, amsg1, amsg2, ICON_Confirm_E); // Button Confirm + DWIN_UpdateLCD(); +} + +#if HAS_HOTEND || HAS_HEATED_BED + void DWIN_Popup_Temperature(const bool toohigh); +#endif +#if HAS_HOTEND + void Popup_Window_ETempTooLow(); +#endif +void Popup_Window_Resume(); diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 2bdb15a30f..11c2c01259 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -470,19 +470,35 @@ uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool ligh return Color_White; } -void CrealityDWINClass::Draw_Title(const char * title) { - DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(title) * STAT_CHR_W) / 2, 5, title); +void CrealityDWINClass::Draw_Title(const char * ctitle) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(ctitle) * STAT_CHR_W) / 2, 5, ctitle); +} +void CrealityDWINClass::Draw_Title(FSTR_P const ftitle) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen_P(FTOP(ftitle)) * STAT_CHR_W) / 2, 5, ftitle); +} + +void _Decorate_Menu_Item(uint8_t row, uint8_t icon, bool more) { + if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon + if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow + DWIN_Draw_Line(CrealityDWIN.GetColor(CrealityDWIN.eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line } void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { - const uint8_t label_offset_y = !(label1 && label2) ? 0 : MENU_CHR_H * 3 / 5; - const uint8_t label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2); - const uint8_t label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); + const uint8_t label_offset_y = (label1 || label2) ? MENU_CHR_H * 3 / 5 : 0, + label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2), + label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); if (label1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label if (label2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label - if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon - if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow - DWIN_Draw_Line(GetColor(eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line + _Decorate_Menu_Item(row, icon, more); +} + +void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, FSTR_P const flabel1, FSTR_P const flabel2, bool more/*=false*/, bool centered/*=false*/) { + const uint8_t label_offset_y = (flabel1 || flabel2) ? MENU_CHR_H * 3 / 5 : 0, + label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel1 ? strlen_P(FTOP(flabel1)) : 0) * MENU_CHR_W) / 2), + label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel2 ? strlen_P(FTOP(flabel2)) : 0) * MENU_CHR_W) / 2); + if (flabel1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, flabel1); // Draw Label + if (flabel2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, flabel2); // Draw Label + _Decorate_Menu_Item(row, icon, more); } void CrealityDWINClass::Draw_Checkbox(uint8_t row, bool value) { @@ -742,7 +758,7 @@ void CrealityDWINClass::Draw_Print_confirm() { void CrealityDWINClass::Draw_SD_Item(uint8_t item, uint8_t row) { if (item == 0) - Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? "Back" : ".."); + Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? F("Back") : F("..")); else { card.getfilename_sorted(SD_ORDER(item - 1, card.get_num_Files())); char * const filename = card.longest_filename(); @@ -772,7 +788,7 @@ void CrealityDWINClass::Draw_SD_List(bool removed/*=false*/) { Draw_SD_Item(i, i); } else { - Draw_Menu_Item(0, ICON_Back, "Back"); + Draw_Menu_Item(0, ICON_Back, F("Back")); DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); DWIN_Draw_String(false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); } @@ -907,7 +923,7 @@ void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { DWIN_UpdateLCD(); } -void CrealityDWINClass::Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P const line3, uint8_t mode, uint8_t icon/*=0*/) { +void CrealityDWINClass::Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon/*=0*/) { if (process != Confirm && process != Popup && process != Wait) last_process = process; if ((process == Menu || process == Wait) && mode == Popup) last_selection = selection; process = mode; @@ -916,9 +932,9 @@ void CrealityDWINClass::Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P c DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 350); const uint8_t ypos = (mode == Popup || mode == Confirm) ? 150 : 230; if (icon > 0) DWIN_ICON_Show(ICON, icon, 101, 105); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line1)) / 2, ypos, line1); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line2)) / 2, ypos + 30, line2); - DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(line3)) / 2, ypos + 60, line3); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line1))) / 2, ypos, line1); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line2))) / 2, ypos + 30, line2); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line3))) / 2, ypos + 60, line3); if (mode == Popup) { selection = 0; DWIN_Draw_Rectangle(1, Confirm_Color, 26, 280, 125, 317); @@ -934,7 +950,7 @@ void CrealityDWINClass::Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P c } void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { - CrealityDWIN.Draw_Popup(PSTR("Printer Kill Reason:"), error, PSTR("Restart Required"), Wait, ICON_BLTouch); + CrealityDWIN.Draw_Popup(F("Printer Kill Reason:"), error, F("Restart Required"), Wait, ICON_BLTouch); } void CrealityDWINClass::Popup_Select() { @@ -1025,31 +1041,31 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREPARE_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Main_Menu(1); break; case PREPARE_MOVE: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Move", nullptr, true); + Draw_Menu_Item(row, ICON_Axis, F("Move"), nullptr, true); else Draw_Menu(Move); break; case PREPARE_DISABLE: if (draw) - Draw_Menu_Item(row, ICON_CloseMotor, "Disable Stepper"); + Draw_Menu_Item(row, ICON_CloseMotor, F("Disable Stepper")); else queue.inject_P(PSTR("M84")); break; case PREPARE_HOME: if (draw) - Draw_Menu_Item(row, ICON_SetHome, "Homing", nullptr, true); + Draw_Menu_Item(row, ICON_SetHome, F("Homing"), nullptr, true); else Draw_Menu(HomeMenu); break; case PREPARE_MANUALLEVEL: if (draw) - Draw_Menu_Item(row, ICON_PrintSize, "Manual Leveling", nullptr, true); + Draw_Menu_Item(row, ICON_PrintSize, F("Manual Leveling"), nullptr, true); else { if (axes_should_home()) { Popup_Handler(Home); @@ -1066,7 +1082,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_ZOFFSET_ITEM case PREPARE_ZOFFSET: if (draw) - Draw_Menu_Item(row, ICON_Zoffset, "Z-Offset", nullptr, true); + Draw_Menu_Item(row, ICON_Zoffset, F("Z-Offset"), nullptr, true); else { #if HAS_LEVELING level_state = planner.leveling_active; @@ -1080,13 +1096,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_PREHEAT case PREPARE_PREHEAT: if (draw) - Draw_Menu_Item(row, ICON_Temperature, "Preheat", nullptr, true); + Draw_Menu_Item(row, ICON_Temperature, F("Preheat"), nullptr, true); else Draw_Menu(Preheat); break; case PREPARE_COOLDOWN: if (draw) - Draw_Menu_Item(row, ICON_Cool, "Cooldown"); + Draw_Menu_Item(row, ICON_Cool, F("Cooldown")); else { TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); thermalManager.disable_all_heaters(); @@ -1097,7 +1113,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(ADVANCED_PAUSE_FEATURE) case PREPARE_CHANGEFIL: if (draw) { - Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament" + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament") #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) , nullptr, true #endif @@ -1138,13 +1154,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case HOME_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Prepare, PREPARE_HOME); break; case HOME_ALL: if (draw) - Draw_Menu_Item(row, ICON_Homing, "Home All"); + Draw_Menu_Item(row, ICON_Homing, F("Home All")); else { Popup_Handler(Home); gcode.home_all_axes(true); @@ -1153,7 +1169,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOME_X: if (draw) - Draw_Menu_Item(row, ICON_MoveX, "Home X"); + Draw_Menu_Item(row, ICON_MoveX, F("Home X")); else { Popup_Handler(Home); gcode.process_subcommands_now(F("G28 X")); @@ -1163,7 +1179,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOME_Y: if (draw) - Draw_Menu_Item(row, ICON_MoveY, "Home Y"); + Draw_Menu_Item(row, ICON_MoveY, F("Home Y")); else { Popup_Handler(Home); gcode.process_subcommands_now(F("G28 Y")); @@ -1173,7 +1189,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOME_Z: if (draw) - Draw_Menu_Item(row, ICON_MoveZ,"Home Z"); + Draw_Menu_Item(row, ICON_MoveZ, F("Home Z")); else { Popup_Handler(Home); gcode.process_subcommands_now(F("G28 Z")); @@ -1183,7 +1199,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOME_SET: if (draw) - Draw_Menu_Item(row, ICON_SetHome, "Set Home Position"); + Draw_Menu_Item(row, ICON_SetHome, F("Set Home Position")); else { gcode.process_subcommands_now(F("G92 X0 Y0 Z0")); AudioFeedback(); @@ -1206,7 +1222,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case MOVE_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else { #if HAS_BED_PROBE probe_deployed = false; @@ -1217,7 +1233,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MOVE_X: if (draw) { - Draw_Menu_Item(row, ICON_MoveX, "Move X"); + Draw_Menu_Item(row, ICON_MoveX, F("Move X")); Draw_Float(current_position.x, row, false); } else @@ -1225,7 +1241,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MOVE_Y: if (draw) { - Draw_Menu_Item(row, ICON_MoveY, "Move Y"); + Draw_Menu_Item(row, ICON_MoveY, F("Move Y")); Draw_Float(current_position.y, row); } else @@ -1233,7 +1249,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MOVE_Z: if (draw) { - Draw_Menu_Item(row, ICON_MoveZ, "Move Z"); + Draw_Menu_Item(row, ICON_MoveZ, F("Move Z")); Draw_Float(current_position.z, row); } else @@ -1243,7 +1259,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case MOVE_E: if (draw) { - Draw_Menu_Item(row, ICON_Extruder, "Extruder"); + Draw_Menu_Item(row, ICON_Extruder, F("Extruder")); current_position.e = 0; sync_plan_position(); Draw_Float(current_position.e, row); @@ -1269,7 +1285,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_BED_PROBE case MOVE_P: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, "Probe"); + Draw_Menu_Item(row, ICON_StockConfiguration, F("Probe")); Draw_Checkbox(row, probe_deployed); } else { @@ -1282,7 +1298,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case MOVE_LIVE: if (draw) { - Draw_Menu_Item(row, ICON_Axis, "Live Movement"); + Draw_Menu_Item(row, ICON_Axis, F("Live Movement")); Draw_Checkbox(row, livemove); } else { @@ -1310,7 +1326,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case MLEVEL_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else { TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); Draw_Menu(Prepare, PREPARE_MANUALLEVEL); @@ -1319,7 +1335,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_BED_PROBE case MLEVEL_PROBE: if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, "Use Probe"); + Draw_Menu_Item(row, ICON_Zoffset, F("Use Probe")); Draw_Checkbox(row, use_probe); } else { @@ -1344,7 +1360,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif case MLEVEL_BL: if (draw) - Draw_Menu_Item(row, ICON_AxisBL, "Bottom Left"); + Draw_Menu_Item(row, ICON_AxisBL, F("Bottom Left")); else { Popup_Handler(MoveWait); if (use_probe) { @@ -1365,7 +1381,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MLEVEL_TL: if (draw) - Draw_Menu_Item(row, ICON_AxisTL, "Top Left"); + Draw_Menu_Item(row, ICON_AxisTL, F("Top Left")); else { Popup_Handler(MoveWait); if (use_probe) { @@ -1386,7 +1402,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MLEVEL_TR: if (draw) - Draw_Menu_Item(row, ICON_AxisTR, "Top Right"); + Draw_Menu_Item(row, ICON_AxisTR, F("Top Right")); else { Popup_Handler(MoveWait); if (use_probe) { @@ -1407,7 +1423,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MLEVEL_BR: if (draw) - Draw_Menu_Item(row, ICON_AxisBR, "Bottom Right"); + Draw_Menu_Item(row, ICON_AxisBR, F("Bottom Right")); else { Popup_Handler(MoveWait); if (use_probe) { @@ -1428,7 +1444,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MLEVEL_C: if (draw) - Draw_Menu_Item(row, ICON_AxisC, "Center"); + Draw_Menu_Item(row, ICON_AxisC, F("Center")); else { Popup_Handler(MoveWait); if (use_probe) { @@ -1449,7 +1465,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MLEVEL_ZPOS: if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, "Z Position"); + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); Draw_Float(mlev_z_pos, row, false, 100); } else @@ -1472,7 +1488,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case ZOFFSET_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else { liveadjust = false; TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); @@ -1481,7 +1497,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ZOFFSET_HOME: if (draw) - Draw_Menu_Item(row, ICON_Homing, "Home Z Axis"); + Draw_Menu_Item(row, ICON_Homing, F("Home Z Axis")); else { Popup_Handler(Home); gcode.process_subcommands_now(F("G28 Z")); @@ -1500,7 +1516,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ZOFFSET_MODE: if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, "Live Adjustment"); + Draw_Menu_Item(row, ICON_Zoffset, F("Live Adjustment")); Draw_Checkbox(row, liveadjust); } else { @@ -1527,7 +1543,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ZOFFSET_OFFSET: if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, "Z Offset"); + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Offset")); Draw_Float(zoffsetvalue, row, false, 100); } else @@ -1535,7 +1551,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ZOFFSET_UP: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); else { if (zoffsetvalue < MAX_Z_OFFSET) { if (liveadjust) { @@ -1549,7 +1565,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ZOFFSET_DOWN: if (draw) - Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); else { if (zoffsetvalue > MIN_Z_OFFSET) { if (liveadjust) { @@ -1564,7 +1580,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(EEPROM_SETTINGS) case ZOFFSET_SAVE: if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, "Save"); + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save")); else AudioFeedback(settings.save()); break; @@ -1587,13 +1603,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Prepare, PREPARE_PREHEAT); break; case PREHEAT_MODE: if (draw) { - Draw_Menu_Item(row, ICON_Homing, "Preheat Mode"); + Draw_Menu_Item(row, ICON_Homing, F("Preheat Mode")); Draw_Option(preheatmode, preheat_modes, row); } else @@ -1603,7 +1619,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 1 case PREHEAT_1: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_1_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_1_LABEL)); else { thermalManager.disable_all_heaters(); TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); @@ -1621,7 +1637,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 2 case PREHEAT_2: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_2_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_2_LABEL)); else { thermalManager.disable_all_heaters(); TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); @@ -1639,7 +1655,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 3 case PREHEAT_3: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_3_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_3_LABEL)); else { thermalManager.disable_all_heaters(); TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); @@ -1657,7 +1673,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 4 case PREHEAT_4: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_4_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_4_LABEL)); else { thermalManager.disable_all_heaters(); TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); @@ -1675,7 +1691,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 5 case PREHEAT_5: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_5_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_5_LABEL)); else { thermalManager.disable_all_heaters(); TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); @@ -1705,13 +1721,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case CHANGEFIL_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Prepare, PREPARE_CHANGEFIL); break; case CHANGEFIL_LOAD: if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, "Load Filament"); + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Filament")); else { if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) Popup_Handler(ETemp); @@ -1729,7 +1745,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case CHANGEFIL_UNLOAD: if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, "Unload Filament"); + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Filament")); else { if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { Popup_Handler(ETemp); @@ -1748,7 +1764,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case CHANGEFIL_CHANGE: if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament"); + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); else { if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) Popup_Handler(ETemp); @@ -1783,50 +1799,50 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case CONTROL_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Main_Menu(2); break; case CONTROL_TEMP: if (draw) - Draw_Menu_Item(row, ICON_Temperature, "Temperature", nullptr, true); + Draw_Menu_Item(row, ICON_Temperature, F("Temperature"), nullptr, true); else Draw_Menu(TempMenu); break; case CONTROL_MOTION: if (draw) - Draw_Menu_Item(row, ICON_Motion, "Motion", nullptr, true); + Draw_Menu_Item(row, ICON_Motion, F("Motion"), nullptr, true); else Draw_Menu(Motion); break; case CONTROL_VISUAL: if (draw) - Draw_Menu_Item(row, ICON_PrintSize, "Visual", nullptr, true); + Draw_Menu_Item(row, ICON_PrintSize, F("Visual"), nullptr, true); else Draw_Menu(Visual); break; case CONTROL_ADVANCED: if (draw) - Draw_Menu_Item(row, ICON_Version, "Advanced", nullptr, true); + Draw_Menu_Item(row, ICON_Version, F("Advanced"), nullptr, true); else Draw_Menu(Advanced); break; #if ENABLED(EEPROM_SETTINGS) case CONTROL_SAVE: if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, "Store Settings"); + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Store Settings")); else AudioFeedback(settings.save()); break; case CONTROL_RESTORE: if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, "Restore Settings"); + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Restore Settings")); else AudioFeedback(settings.load()); break; case CONTROL_RESET: if (draw) - Draw_Menu_Item(row, ICON_Temperature, "Reset to Defaults"); + Draw_Menu_Item(row, ICON_Temperature, F("Reset to Defaults")); else { settings.reset(); AudioFeedback(); @@ -1835,7 +1851,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif case CONTROL_INFO: if (draw) - Draw_Menu_Item(row, ICON_Info, "Info"); + Draw_Menu_Item(row, ICON_Info, F("Info")); else Draw_Menu(Info); break; @@ -1859,14 +1875,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case TEMP_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Control, CONTROL_TEMP); break; #if HAS_HOTEND case TEMP_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); } else @@ -1876,7 +1892,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case TEMP_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(thermalManager.temp_bed.target, row, false, 1); } else @@ -1886,7 +1902,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case TEMP_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(thermalManager.fan_speed[0], row, false, 1); } else @@ -1896,7 +1912,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND || HAS_HEATED_BED case TEMP_PID: if (draw) - Draw_Menu_Item(row, ICON_Step, "PID", nullptr, true); + Draw_Menu_Item(row, ICON_Step, F("PID"), nullptr, true); else Draw_Menu(PID); break; @@ -1904,7 +1920,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 1 case TEMP_PREHEAT1: if (draw) - Draw_Menu_Item(row, ICON_Step, PREHEAT_1_LABEL, nullptr, true); + Draw_Menu_Item(row, ICON_Step, F(PREHEAT_1_LABEL), nullptr, true); else Draw_Menu(Preheat1); break; @@ -1912,7 +1928,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 2 case TEMP_PREHEAT2: if (draw) - Draw_Menu_Item(row, ICON_Step, PREHEAT_2_LABEL, nullptr, true); + Draw_Menu_Item(row, ICON_Step, F(PREHEAT_2_LABEL), nullptr, true); else Draw_Menu(Preheat2); break; @@ -1920,7 +1936,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 3 case TEMP_PREHEAT3: if (draw) - Draw_Menu_Item(row, ICON_Step, PREHEAT_3_LABEL, nullptr, true); + Draw_Menu_Item(row, ICON_Step, F(PREHEAT_3_LABEL), nullptr, true); else Draw_Menu(Preheat3); break; @@ -1928,7 +1944,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 4 case TEMP_PREHEAT4: if (draw) - Draw_Menu_Item(row, ICON_Step, PREHEAT_4_LABEL, nullptr, true); + Draw_Menu_Item(row, ICON_Step, F(PREHEAT_4_LABEL), nullptr, true); else Draw_Menu(Preheat4); break; @@ -1936,7 +1952,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 5 case TEMP_PREHEAT5: if (draw) - Draw_Menu_Item(row, ICON_Step, PREHEAT_5_LABEL, nullptr, true); + Draw_Menu_Item(row, ICON_Step, F(PREHEAT_5_LABEL), nullptr, true); else Draw_Menu(Preheat5); break; @@ -1958,14 +1974,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PID_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PID); break; #if HAS_HOTEND case PID_HOTEND: if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, "Hotend", nullptr, true); + Draw_Menu_Item(row, ICON_HotendTemp, F("Hotend"), nullptr, true); else Draw_Menu(HotendPID); break; @@ -1973,14 +1989,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PID_BED: if (draw) - Draw_Menu_Item(row, ICON_BedTemp, "Bed", nullptr, true); + Draw_Menu_Item(row, ICON_BedTemp, F("Bed"), nullptr, true); else Draw_Menu(BedPID); break; #endif case PID_CYCLES: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Cycles"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Cycles")); Draw_Float(PID_cycles, row, false, 1); } else @@ -2006,13 +2022,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case HOTENDPID_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(PID, PID_HOTEND); break; case HOTENDPID_TUNE: if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, "Autotune"); + Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); else { Popup_Handler(PIDWait); sprintf_P(cmd, PSTR("M303 E0 C%i S%i U1"), PID_cycles, PID_e_temp); @@ -2023,7 +2039,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOTENDPID_TEMP: if (draw) { - Draw_Menu_Item(row, ICON_Temperature, "Temperature"); + Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); Draw_Float(PID_e_temp, row, false, 1); } else @@ -2031,7 +2047,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOTENDPID_KP: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Kp Value"); + Draw_Menu_Item(row, ICON_Version, F("Kp Value")); Draw_Float(thermalManager.temp_hotend[0].pid.Kp, row, false, 100); } else @@ -2039,7 +2055,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOTENDPID_KI: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Ki Value"); + Draw_Menu_Item(row, ICON_Version, F("Ki Value")); Draw_Float(unscalePID_i(thermalManager.temp_hotend[0].pid.Ki), row, false, 100); } else @@ -2047,7 +2063,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOTENDPID_KD: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Kd Value"); + Draw_Menu_Item(row, ICON_Version, F("Kd Value")); Draw_Float(unscalePID_d(thermalManager.temp_hotend[0].pid.Kd), row, false, 100); } else @@ -2073,13 +2089,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case BEDPID_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(PID, PID_BED); break; case BEDPID_TUNE: if (draw) - Draw_Menu_Item(row, ICON_HotendTemp, "Autotune"); + Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); else { Popup_Handler(PIDWait); sprintf_P(cmd, PSTR("M303 E-1 C%i S%i U1"), PID_cycles, PID_bed_temp); @@ -2090,7 +2106,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case BEDPID_TEMP: if (draw) { - Draw_Menu_Item(row, ICON_Temperature, "Temperature"); + Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); Draw_Float(PID_bed_temp, row, false, 1); } else @@ -2098,7 +2114,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case BEDPID_KP: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Kp Value"); + Draw_Menu_Item(row, ICON_Version, F("Kp Value")); Draw_Float(thermalManager.temp_bed.pid.Kp, row, false, 100); } else { @@ -2107,7 +2123,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case BEDPID_KI: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Ki Value"); + Draw_Menu_Item(row, ICON_Version, F("Ki Value")); Draw_Float(unscalePID_i(thermalManager.temp_bed.pid.Ki), row, false, 100); } else @@ -2115,7 +2131,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case BEDPID_KD: if (draw) { - Draw_Menu_Item(row, ICON_Version, "Kd Value"); + Draw_Menu_Item(row, ICON_Version, F("Kd Value")); Draw_Float(unscalePID_d(thermalManager.temp_bed.pid.Kd), row, false, 100); } else @@ -2137,14 +2153,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT1_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PREHEAT1); break; #if HAS_HOTEND case PREHEAT1_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(ui.material_preset[0].hotend_temp, row, false, 1); } else @@ -2154,7 +2170,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PREHEAT1_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(ui.material_preset[0].bed_temp, row, false, 1); } else @@ -2164,7 +2180,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case PREHEAT1_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(ui.material_preset[0].fan_speed, row, false, 1); } else @@ -2187,14 +2203,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT2_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PREHEAT2); break; #if HAS_HOTEND case PREHEAT2_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(ui.material_preset[1].hotend_temp, row, false, 1); } else @@ -2204,7 +2220,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PREHEAT2_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(ui.material_preset[1].bed_temp, row, false, 1); } else @@ -2214,7 +2230,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case PREHEAT2_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(ui.material_preset[1].fan_speed, row, false, 1); } else @@ -2237,14 +2253,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT3_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PREHEAT3); break; #if HAS_HOTEND case PREHEAT3_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(ui.material_preset[2].hotend_temp, row, false, 1); } else @@ -2254,7 +2270,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PREHEAT3_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(ui.material_preset[2].bed_temp, row, false, 1); } else @@ -2264,7 +2280,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case PREHEAT3_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(ui.material_preset[2].fan_speed, row, false, 1); } else @@ -2287,14 +2303,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT4_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PREHEAT4); break; #if HAS_HOTEND case PREHEAT4_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(ui.material_preset[3].hotend_temp, row, false, 1); } else @@ -2304,7 +2320,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PREHEAT4_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(ui.material_preset[3].bed_temp, row, false, 1); } else @@ -2314,7 +2330,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case PREHEAT4_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(ui.material_preset[3].fan_speed, row, false, 1); } else @@ -2337,14 +2353,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEAT5_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(TempMenu, TEMP_PREHEAT5); break; #if HAS_HOTEND case PREHEAT5_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(ui.material_preset[4].hotend_temp, row, false, 1); } else @@ -2354,7 +2370,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case PREHEAT5_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(ui.material_preset[4].bed_temp, row, false, 1); } else @@ -2364,7 +2380,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case PREHEAT5_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(ui.material_preset[4].fan_speed, row, false, 1); } else @@ -2389,46 +2405,46 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case MOTION_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Control, CONTROL_MOTION); break; case MOTION_HOMEOFFSETS: if (draw) - Draw_Menu_Item(row, ICON_SetHome, "Home Offsets", nullptr, true); + Draw_Menu_Item(row, ICON_SetHome, F("Home Offsets"), nullptr, true); else Draw_Menu(HomeOffsets); break; case MOTION_SPEED: if (draw) - Draw_Menu_Item(row, ICON_MaxSpeed, "Max Speed", nullptr, true); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Max Speed"), nullptr, true); else Draw_Menu(MaxSpeed); break; case MOTION_ACCEL: if (draw) - Draw_Menu_Item(row, ICON_MaxAccelerated, "Max Acceleration", nullptr, true); + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Max Acceleration"), nullptr, true); else Draw_Menu(MaxAcceleration); break; #if HAS_CLASSIC_JERK case MOTION_JERK: if (draw) - Draw_Menu_Item(row, ICON_MaxJerk, "Max Jerk", nullptr, true); + Draw_Menu_Item(row, ICON_MaxJerk, F("Max Jerk"), nullptr, true); else Draw_Menu(MaxJerk); break; #endif case MOTION_STEPS: if (draw) - Draw_Menu_Item(row, ICON_Step, "Steps/mm", nullptr, true); + Draw_Menu_Item(row, ICON_Step, F("Steps/mm"), nullptr, true); else Draw_Menu(Steps); break; #if HAS_HOTEND case MOTION_FLOW: if (draw) { - Draw_Menu_Item(row, ICON_Speed, "Flow Rate"); + Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); Draw_Float(planner.flow_percentage[0], row, false, 1); } else @@ -2448,13 +2464,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case HOMEOFFSETS_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Motion, MOTION_HOMEOFFSETS); break; case HOMEOFFSETS_XOFFSET: if (draw) { - Draw_Menu_Item(row, ICON_StepX, "X Offset"); + Draw_Menu_Item(row, ICON_StepX, F("X Offset")); Draw_Float(home_offset.x, row, false, 100); } else @@ -2462,7 +2478,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case HOMEOFFSETS_YOFFSET: if (draw) { - Draw_Menu_Item(row, ICON_StepY, "Y Offset"); + Draw_Menu_Item(row, ICON_StepY, F("Y Offset")); Draw_Float(home_offset.y, row, false, 100); } else @@ -2482,13 +2498,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case SPEED_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Motion, MOTION_SPEED); break; case SPEED_X: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedX, "X Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedX, F("X Axis")); Draw_Float(planner.settings.max_feedrate_mm_s[X_AXIS], row, false, 1); } else @@ -2498,7 +2514,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_Y_AXIS case SPEED_Y: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedY, "Y Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedY, F("Y Axis")); Draw_Float(planner.settings.max_feedrate_mm_s[Y_AXIS], row, false, 1); } else @@ -2509,7 +2525,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_Z_AXIS case SPEED_Z: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedZ, "Z Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedZ, F("Z Axis")); Draw_Float(planner.settings.max_feedrate_mm_s[Z_AXIS], row, false, 1); } else @@ -2520,7 +2536,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case SPEED_E: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedE, "Extruder"); + Draw_Menu_Item(row, ICON_MaxSpeedE, F("Extruder")); Draw_Float(planner.settings.max_feedrate_mm_s[E_AXIS], row, false, 1); } else @@ -2542,13 +2558,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case ACCEL_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Motion, MOTION_ACCEL); break; case ACCEL_X: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccX, "X Axis"); + Draw_Menu_Item(row, ICON_MaxAccX, F("X Axis")); Draw_Float(planner.settings.max_acceleration_mm_per_s2[X_AXIS], row, false, 1); } else @@ -2556,7 +2572,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ACCEL_Y: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccY, "Y Axis"); + Draw_Menu_Item(row, ICON_MaxAccY, F("Y Axis")); Draw_Float(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], row, false, 1); } else @@ -2564,7 +2580,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ACCEL_Z: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccZ, "Z Axis"); + Draw_Menu_Item(row, ICON_MaxAccZ, F("Z Axis")); Draw_Float(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], row, false, 1); } else @@ -2573,7 +2589,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case ACCEL_E: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccE, "Extruder"); + Draw_Menu_Item(row, ICON_MaxAccE, F("Extruder")); Draw_Float(planner.settings.max_acceleration_mm_per_s2[E_AXIS], row, false, 1); } else @@ -2595,13 +2611,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case JERK_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Motion, MOTION_JERK); break; case JERK_X: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkX, "X Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedJerkX, F("X Axis")); Draw_Float(planner.max_jerk[X_AXIS], row, false, 10); } else @@ -2609,7 +2625,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case JERK_Y: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkY, "Y Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedJerkY, F("Y Axis")); Draw_Float(planner.max_jerk[Y_AXIS], row, false, 10); } else @@ -2617,7 +2633,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case JERK_Z: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkZ, "Z Axis"); + Draw_Menu_Item(row, ICON_MaxSpeedJerkZ, F("Z Axis")); Draw_Float(planner.max_jerk[Z_AXIS], row, false, 10); } else @@ -2626,7 +2642,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case JERK_E: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeedJerkE, "Extruder"); + Draw_Menu_Item(row, ICON_MaxSpeedJerkE, F("Extruder")); Draw_Float(planner.max_jerk[E_AXIS], row, false, 10); } else @@ -2648,13 +2664,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case STEPS_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Motion, MOTION_STEPS); break; case STEPS_X: if (draw) { - Draw_Menu_Item(row, ICON_StepX, "X Axis"); + Draw_Menu_Item(row, ICON_StepX, F("X Axis")); Draw_Float(planner.settings.axis_steps_per_mm[X_AXIS], row, false, 10); } else @@ -2662,7 +2678,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case STEPS_Y: if (draw) { - Draw_Menu_Item(row, ICON_StepY, "Y Axis"); + Draw_Menu_Item(row, ICON_StepY, F("Y Axis")); Draw_Float(planner.settings.axis_steps_per_mm[Y_AXIS], row, false, 10); } else @@ -2670,7 +2686,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case STEPS_Z: if (draw) { - Draw_Menu_Item(row, ICON_StepZ, "Z Axis"); + Draw_Menu_Item(row, ICON_StepZ, F("Z Axis")); Draw_Float(planner.settings.axis_steps_per_mm[Z_AXIS], row, false, 10); } else @@ -2679,7 +2695,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case STEPS_E: if (draw) { - Draw_Menu_Item(row, ICON_StepE, "Extruder"); + Draw_Menu_Item(row, ICON_StepE, F("Extruder")); Draw_Float(planner.settings.axis_steps_per_mm[E_AXIS], row, false, 10); } else @@ -2701,19 +2717,19 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case VISUAL_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Control, CONTROL_VISUAL); break; case VISUAL_BACKLIGHT: if (draw) - Draw_Menu_Item(row, ICON_Brightness, "Display Off"); + Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); else ui.set_brightness(0); break; case VISUAL_BRIGHTNESS: if (draw) { - Draw_Menu_Item(row, ICON_Brightness, "LCD Brightness"); + Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); Draw_Float(ui.brightness, row, false, 1); } else @@ -2721,7 +2737,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case VISUAL_TIME_FORMAT: if (draw) { - Draw_Menu_Item(row, ICON_PrintTime, "Progress as __h__m"); + Draw_Menu_Item(row, ICON_PrintTime, F("Progress as __h__m")); Draw_Checkbox(row, eeprom_settings.time_format_textual); } else { @@ -2731,7 +2747,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case VISUAL_COLOR_THEMES: if (draw) - Draw_Menu_Item(row, ICON_MaxSpeed, "UI Color Settings", nullptr, true); + Draw_Menu_Item(row, ICON_MaxSpeed, F("UI Color Settings"), nullptr, true); else Draw_Menu(ColorSettings); break; @@ -2757,13 +2773,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case COLORSETTINGS_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Visual, VISUAL_COLOR_THEMES); break; case COLORSETTINGS_CURSOR: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Cursor"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Cursor")); Draw_Option(eeprom_settings.cursor_color, color_names, row, false, true); } else @@ -2771,7 +2787,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_SPLIT_LINE: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Split Line"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Split Line")); Draw_Option(eeprom_settings.menu_split_line, color_names, row, false, true); } else @@ -2779,7 +2795,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_MENU_TOP_TXT: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Header Text"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Text")); Draw_Option(eeprom_settings.menu_top_txt, color_names, row, false, true); } else @@ -2787,7 +2803,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_MENU_TOP_BG: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Menu Header Bg"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Bg")); Draw_Option(eeprom_settings.menu_top_bg, color_names, row, false, true); } else @@ -2795,7 +2811,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_HIGHLIGHT_BORDER: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Highlight Box"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Highlight Box")); Draw_Option(eeprom_settings.highlight_box, color_names, row, false, true); } else @@ -2803,7 +2819,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_PERCENT: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Progress Percent"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Percent")); Draw_Option(eeprom_settings.progress_percent, color_names, row, false, true); } else @@ -2811,7 +2827,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_TIME: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Progress Time"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Time")); Draw_Option(eeprom_settings.progress_time, color_names, row, false, true); } else @@ -2819,7 +2835,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_STATUS_BAR: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Status Bar Text"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Bar Text")); Draw_Option(eeprom_settings.status_bar_text, color_names, row, false, true); } else @@ -2827,7 +2843,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_STATUS_AREA: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Status Area Text"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Area Text")); Draw_Option(eeprom_settings.status_area_text, color_names, row, false, true); } else @@ -2835,7 +2851,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_COORDINATES: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Coordinates Text"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Text")); Draw_Option(eeprom_settings.coordinates_text, color_names, row, false, true); } else @@ -2843,7 +2859,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case COLORSETTINGS_PROGRESS_COORDINATES_LINE: if (draw) { - Draw_Menu_Item(row, ICON_MaxSpeed, "Coordinates Line"); + Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Line")); Draw_Option(eeprom_settings.coordinates_split_line, color_names, row, false, true); } else @@ -2870,7 +2886,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case ADVANCED_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Control, CONTROL_ADVANCED); break; @@ -2878,7 +2894,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(SOUND_MENU_ITEM) case ADVANCED_BEEPER: if (draw) { - Draw_Menu_Item(row, ICON_Version, "LCD Beeper"); + Draw_Menu_Item(row, ICON_Version, F("LCD Beeper")); Draw_Checkbox(row, ui.buzzer_enabled); } else { @@ -2891,7 +2907,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_BED_PROBE case ADVANCED_PROBE: if (draw) - Draw_Menu_Item(row, ICON_StepX, "Probe", nullptr, true); + Draw_Menu_Item(row, ICON_StepX, F("Probe"), nullptr, true); else Draw_Menu(ProbeMenu); break; @@ -2899,7 +2915,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case ADVANCED_CORNER: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccelerated, "Bed Screw Inset"); + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Bed Screw Inset")); Draw_Float(corner_pos, row, false, 10); } else @@ -2909,7 +2925,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(LIN_ADVANCE) case ADVANCED_LA: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccelerated, "Lin Advance Kp"); + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Lin Advance Kp")); Draw_Float(planner.extruder_advance_K[0], row, false, 100); } else @@ -2920,7 +2936,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(ADVANCED_PAUSE_FEATURE) case ADVANCED_LOAD: if (draw) { - Draw_Menu_Item(row, ICON_WriteEEPROM, "Load Length"); + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Length")); Draw_Float(fc_settings[0].load_length, row, false, 1); } else @@ -2928,7 +2944,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case ADVANCED_UNLOAD: if (draw) { - Draw_Menu_Item(row, ICON_ReadEEPROM, "Unload Length"); + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Length")); Draw_Float(fc_settings[0].unload_length, row, false, 1); } else @@ -2939,7 +2955,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(PREVENT_COLD_EXTRUSION) case ADVANCED_COLD_EXTRUDE: if (draw) { - Draw_Menu_Item(row, ICON_Cool, "Min Extrusion T"); + Draw_Menu_Item(row, ICON_Cool, F("Min Extrusion T")); Draw_Float(thermalManager.extrude_min_temp, row, false, 1); } else { @@ -2952,7 +2968,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(FILAMENT_RUNOUT_SENSOR) case ADVANCED_FILSENSORENABLED: if (draw) { - Draw_Menu_Item(row, ICON_Extruder, "Filament Sensor"); + Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); Draw_Checkbox(row, runout.enabled); } else { @@ -2964,7 +2980,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE) case ADVANCED_FILSENSORDISTANCE: if (draw) { - Draw_Menu_Item(row, ICON_MaxAccE, "Runout Distance"); + Draw_Menu_Item(row, ICON_MaxAccE, F("Runout Distance")); Draw_Float(runout.runout_distance(), row, false, 10); } else @@ -2976,7 +2992,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(POWER_LOSS_RECOVERY) case ADVANCED_POWER_LOSS: if (draw) { - Draw_Menu_Item(row, ICON_Motion, "Power-loss recovery"); + Draw_Menu_Item(row, ICON_Motion, F("Power-loss recovery")); Draw_Checkbox(row, recovery.enabled); } else { @@ -3003,14 +3019,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PROBE_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Advanced, ADVANCED_PROBE); break; case PROBE_XOFFSET: if (draw) { - Draw_Menu_Item(row, ICON_StepX, "Probe X Offset"); + Draw_Menu_Item(row, ICON_StepX, F("Probe X Offset")); Draw_Float(probe.offset.x, row, false, 10); } else @@ -3018,7 +3034,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case PROBE_YOFFSET: if (draw) { - Draw_Menu_Item(row, ICON_StepY, "Probe Y Offset"); + Draw_Menu_Item(row, ICON_StepY, F("Probe Y Offset")); Draw_Float(probe.offset.y, row, false, 10); } else @@ -3026,7 +3042,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case PROBE_TEST: if (draw) - Draw_Menu_Item(row, ICON_StepY, "M48 Probe Test"); + Draw_Menu_Item(row, ICON_StepY, F("M48 Probe Test")); else { sprintf_P(cmd, PSTR("G28O\nM48 X%s Y%s P%i"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), testcount); gcode.process_subcommands_now(cmd); @@ -3034,7 +3050,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case PROBE_TEST_COUNT: if (draw) { - Draw_Menu_Item(row, ICON_StepY, "Probe Test Count"); + Draw_Menu_Item(row, ICON_StepY, F("Probe Test Count")); Draw_Float(testcount, row, false, 1); } else @@ -3058,7 +3074,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case INFO_BACK: if (draw) { - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); #if ENABLED(PRINTCOUNTER) char row1[50], row2[50], buf[32]; @@ -3075,9 +3091,9 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ Draw_Menu_Item(INFO_PRINTTIME, ICON_PrintTime, row1, row2, false, true); #endif - Draw_Menu_Item(INFO_SIZE, ICON_PrintSize, MACHINE_SIZE, nullptr, false, true); - Draw_Menu_Item(INFO_VERSION, ICON_Version, SHORT_BUILD_VERSION, nullptr, false, true); - Draw_Menu_Item(INFO_CONTACT, ICON_Contact, CORP_WEBSITE, nullptr, false, true); + Draw_Menu_Item(INFO_SIZE, ICON_PrintSize, F(MACHINE_SIZE), nullptr, false, true); + Draw_Menu_Item(INFO_VERSION, ICON_Version, F(SHORT_BUILD_VERSION), nullptr, false, true); + Draw_Menu_Item(INFO_CONTACT, ICON_Contact, F(CORP_WEBSITE), nullptr, false, true); } else { if (menu == Info) @@ -3107,13 +3123,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case LEVELING_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Main_Menu(3); break; case LEVELING_ACTIVE: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, "Leveling Active"); + Draw_Menu_Item(row, ICON_StockConfiguration, F("Leveling Active")); Draw_Checkbox(row, planner.leveling_active); } else { @@ -3132,7 +3148,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) case LEVELING_GET_TILT: if (draw) - Draw_Menu_Item(row, ICON_Tilt, "Autotilt Current Mesh"); + Draw_Menu_Item(row, ICON_Tilt, F("Autotilt Current Mesh")); else { if (ubl.storage_slot < 0) { Popup_Handler(MeshSlot); @@ -3154,7 +3170,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif case LEVELING_GET_MESH: if (draw) - Draw_Menu_Item(row, ICON_Mesh, "Create New Mesh"); + Draw_Menu_Item(row, ICON_Mesh, F("Create New Mesh")); else { Popup_Handler(Home); gcode.home_all_axes(true); @@ -3206,7 +3222,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_MANUAL: if (draw) - Draw_Menu_Item(row, ICON_Mesh, "Manual Tuning", nullptr, true); + Draw_Menu_Item(row, ICON_Mesh, F("Manual Tuning"), nullptr, true); else { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (!leveling_is_valid()) { @@ -3260,14 +3276,14 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_SETTINGS: if (draw) - Draw_Menu_Item(row, ICON_Step, "Leveling Settings", nullptr, true); + Draw_Menu_Item(row, ICON_Step, F("Leveling Settings"), nullptr, true); else Draw_Menu(LevelSettings); break; #if ENABLED(AUTO_BED_LEVELING_UBL) case LEVELING_SLOT: if (draw) { - Draw_Menu_Item(row, ICON_PrintSize, "Mesh Slot"); + Draw_Menu_Item(row, ICON_PrintSize, F("Mesh Slot")); Draw_Float(ubl.storage_slot, row, false, 1); } else @@ -3275,7 +3291,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_LOAD: if (draw) - Draw_Menu_Item(row, ICON_ReadEEPROM, "Load Mesh"); + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Load Mesh")); else { if (ubl.storage_slot < 0) { Popup_Handler(MeshSlot); @@ -3288,7 +3304,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_SAVE: if (draw) - Draw_Menu_Item(row, ICON_WriteEEPROM, "Save Mesh"); + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save Mesh")); else { if (ubl.storage_slot < 0) { Popup_Handler(MeshSlot); @@ -3314,7 +3330,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case LEVELING_VIEW_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Leveling, LEVELING_VIEW); break; @@ -3326,7 +3342,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW_TEXT: if (draw) { - Draw_Menu_Item(row, ICON_Contact, "Viewer Show Values"); + Draw_Menu_Item(row, ICON_Contact, F("Viewer Show Values")); Draw_Checkbox(row, mesh_conf.viewer_print_value); } else { @@ -3336,7 +3352,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_VIEW_ASYMMETRIC: if (draw) { - Draw_Menu_Item(row, ICON_Axis, "Viewer Asymmetric"); + Draw_Menu_Item(row, ICON_Axis, F("Viewer Asymmetric")); Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); } else { @@ -3360,13 +3376,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case LEVELING_SETTINGS_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Menu(Leveling, LEVELING_SETTINGS); break; case LEVELING_SETTINGS_FADE: if (draw) { - Draw_Menu_Item(row, ICON_Fade, "Fade Mesh within"); + Draw_Menu_Item(row, ICON_Fade, F("Fade Mesh within")); Draw_Float(planner.z_fade_height, row, false, 1); } else { @@ -3379,7 +3395,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(AUTO_BED_LEVELING_UBL) case LEVELING_SETTINGS_TILT: if (draw) { - Draw_Menu_Item(row, ICON_Tilt, "Tilting Grid Size"); + Draw_Menu_Item(row, ICON_Tilt, F("Tilting Grid Size")); Draw_Float(mesh_conf.tilt_grid, row, false, 1); } else @@ -3387,7 +3403,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_SETTINGS_PLANE: if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, "Convert Mesh to Plane"); + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Convert Mesh to Plane")); else { if (mesh_conf.create_plane_from_mesh()) break; gcode.process_subcommands_now(F("M420 S1")); @@ -3397,13 +3413,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_SETTINGS_ZERO: if (draw) - Draw_Menu_Item(row, ICON_Mesh, "Zero Current Mesh"); + Draw_Menu_Item(row, ICON_Mesh, F("Zero Current Mesh")); else ZERO(Z_VALUES_ARR); break; case LEVELING_SETTINGS_UNDEF: if (draw) - Draw_Menu_Item(row, ICON_Mesh, "Clear Current Mesh"); + Draw_Menu_Item(row, ICON_Mesh, F("Clear Current Mesh")); else ubl.invalidate(); break; @@ -3417,7 +3433,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (item == MESHVIEW_BACK) { if (draw) { - Draw_Menu_Item(0, ICON_Back, "Back"); + Draw_Menu_Item(0, ICON_Back, F("Back")); mesh_conf.Draw_Bed_Mesh(); mesh_conf.Set_Mesh_Viewer_Status(); } @@ -3444,7 +3460,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case LEVELING_M_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else { set_bed_leveling_enabled(level_state); TERN_(AUTO_BED_LEVELING_BILINEAR, refresh_bed_level()); @@ -3453,7 +3469,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_X: if (draw) { - Draw_Menu_Item(row, ICON_MoveX, "Mesh Point X"); + Draw_Menu_Item(row, ICON_MoveX, F("Mesh Point X")); Draw_Float(mesh_conf.mesh_x, row, 0, 1); } else @@ -3461,7 +3477,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_Y: if (draw) { - Draw_Menu_Item(row, ICON_MoveY, "Mesh Point Y"); + Draw_Menu_Item(row, ICON_MoveY, F("Mesh Point Y")); Draw_Float(mesh_conf.mesh_y, row, 0, 1); } else @@ -3469,7 +3485,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_NEXT: if (draw) - Draw_Menu_Item(row, ICON_More, "Next Point"); + Draw_Menu_Item(row, ICON_More, F("Next Point")); else { if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) @@ -3484,7 +3500,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_OFFSET: if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); + Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); } else { @@ -3495,7 +3511,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_UP: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; gcode.process_subcommands_now(F("M290 Z0.01")); @@ -3507,7 +3523,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_DOWN: if (draw) - Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; gcode.process_subcommands_now(F("M290 Z-0.01")); @@ -3519,7 +3535,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case LEVELING_M_GOTO_VALUE: if (draw) { - Draw_Menu_Item(row, ICON_StockConfiguration, "Go to Mesh Z Value"); + Draw_Menu_Item(row, ICON_StockConfiguration, F("Go to Mesh Z Value")); Draw_Checkbox(row, mesh_conf.goto_mesh_value); } else { @@ -3532,7 +3548,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(AUTO_BED_LEVELING_UBL) case LEVELING_M_UNDEF: if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, "Clear Point Value"); + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Clear Point Value")); else { mesh_conf.manual_value_update(true); Redraw_Menu(false); @@ -3557,7 +3573,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case UBL_M_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else { set_bed_leveling_enabled(level_state); Draw_Menu(Leveling, LEVELING_GET_MESH); @@ -3566,9 +3582,9 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case UBL_M_NEXT: if (draw) { if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) - Draw_Menu_Item(row, ICON_More, "Next Point"); + Draw_Menu_Item(row, ICON_More, F("Next Point")); else - Draw_Menu_Item(row, ICON_More, "Save Mesh"); + Draw_Menu_Item(row, ICON_More, F("Save Mesh")); } else { if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { @@ -3590,7 +3606,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case UBL_M_PREV: if (draw) - Draw_Menu_Item(row, ICON_More, "Previous Point"); + Draw_Menu_Item(row, ICON_More, F("Previous Point")); else { if (mesh_conf.mesh_x != 0 || mesh_conf.mesh_y != 0) { if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 1) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 0)) @@ -3605,7 +3621,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case UBL_M_OFFSET: if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, "Point Z Offset"); + Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); Draw_Float(Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); } else { @@ -3616,7 +3632,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case UBL_M_UP: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; gcode.process_subcommands_now(F("M290 Z0.01")); @@ -3628,7 +3644,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case UBL_M_DOWN: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Microstep Down"); + Draw_Menu_Item(row, ICON_Axis, F("Microstep Down")); else if (Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { Z_VALUES_ARR[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; gcode.process_subcommands_now(F("M290 Z-0.01")); @@ -3656,7 +3672,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case MMESH_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Cancel"); + Draw_Menu_Item(row, ICON_Back, F("Cancel")); else { gcode.process_subcommands_now(F("G29 A")); planner.synchronize(); @@ -3667,9 +3683,9 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case MMESH_NEXT: if (draw) { if (gridpoint < GRID_MAX_POINTS) - Draw_Menu_Item(row, ICON_More, "Next Point"); + Draw_Menu_Item(row, ICON_More, F("Next Point")); else - Draw_Menu_Item(row, ICON_More, "Save Mesh"); + Draw_Menu_Item(row, ICON_More, F("Save Mesh")); } else if (gridpoint < GRID_MAX_POINTS) { Popup_Handler(MoveWait); @@ -3687,7 +3703,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MMESH_OFFSET: if (draw) { - Draw_Menu_Item(row, ICON_SetZOffset, "Z Position"); + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); current_position.z = MANUAL_PROBE_START_Z; Draw_Float(current_position.z, row, false, 100); } @@ -3696,7 +3712,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MMESH_UP: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Microstep Up"); + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); else if (current_position.z < MAX_Z_OFFSET) { gcode.process_subcommands_now(F("M290 Z0.01")); planner.synchronize(); @@ -3707,7 +3723,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case MMESH_DOWN: if (draw) - Draw_Menu_Item(row, ICON_AxisD, "Microstep Down"); + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); else if (current_position.z > MIN_Z_OFFSET) { gcode.process_subcommands_now(F("M290 Z-0.01")); planner.synchronize(); @@ -3728,7 +3744,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ const float currval = Z_VALUES_ARR[mesh_x][mesh_y]; if (draw) { - Draw_Menu_Item(row, ICON_Zoffset, "Goto Mesh Value"); + Draw_Menu_Item(row, ICON_Zoffset, F("Goto Mesh Value")); Draw_Float(currval, row, false, 100); } else if (!isnan(currval)) { @@ -3763,13 +3779,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case TUNE_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Back"); + Draw_Menu_Item(row, ICON_Back, F("Back")); else Draw_Print_Screen(); break; case TUNE_SPEED: if (draw) { - Draw_Menu_Item(row, ICON_Speed, "Print Speed"); + Draw_Menu_Item(row, ICON_Speed, F("Print Speed")); Draw_Float(feedrate_percentage, row, false, 1); } else @@ -3779,7 +3795,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HOTEND case TUNE_FLOW: if (draw) { - Draw_Menu_Item(row, ICON_Speed, "Flow Rate"); + Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); Draw_Float(planner.flow_percentage[0], row, false, 1); } else @@ -3787,7 +3803,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case TUNE_HOTEND: if (draw) { - Draw_Menu_Item(row, ICON_SetEndTemp, "Hotend"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); } else @@ -3798,7 +3814,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_HEATED_BED case TUNE_BED: if (draw) { - Draw_Menu_Item(row, ICON_SetBedTemp, "Bed"); + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); Draw_Float(thermalManager.temp_bed.target, row, false, 1); } else @@ -3809,7 +3825,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_FAN case TUNE_FAN: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Fan"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); Draw_Float(thermalManager.fan_speed[0], row, false, 1); } else @@ -3820,7 +3836,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if HAS_ZOFFSET_ITEM case TUNE_ZOFFSET: if (draw) { - Draw_Menu_Item(row, ICON_FanSpeed, "Z-Offset"); + Draw_Menu_Item(row, ICON_FanSpeed, F("Z-Offset")); Draw_Float(zoffsetvalue, row, false, 100); } else @@ -3828,7 +3844,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case TUNE_ZUP: if (draw) - Draw_Menu_Item(row, ICON_Axis, "Z-Offset Up"); + Draw_Menu_Item(row, ICON_Axis, F("Z-Offset Up")); else if (zoffsetvalue < MAX_Z_OFFSET) { gcode.process_subcommands_now(F("M290 Z0.01")); zoffsetvalue += 0.01; @@ -3837,7 +3853,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case TUNE_ZDOWN: if (draw) - Draw_Menu_Item(row, ICON_AxisD, "Z-Offset Down"); + Draw_Menu_Item(row, ICON_AxisD, F("Z-Offset Down")); else if (zoffsetvalue > MIN_Z_OFFSET) { gcode.process_subcommands_now(F("M290 Z-0.01")); zoffsetvalue -= 0.01; @@ -3849,7 +3865,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) case TUNE_CHANGEFIL: if (draw) - Draw_Menu_Item(row, ICON_ResumeEEPROM, "Change Filament"); + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); else Popup_Handler(ConfFilChange); break; @@ -3858,7 +3874,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if ENABLED(FILAMENT_RUNOUT_SENSOR) case TUNE_FILSENSORENABLED: if (draw) { - Draw_Menu_Item(row, ICON_Extruder, "Filament Sensor"); + Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); Draw_Checkbox(row, runout.enabled); } else { @@ -3870,13 +3886,13 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ case TUNE_BACKLIGHT_OFF: if (draw) - Draw_Menu_Item(row, ICON_Brightness, "Display Off"); + Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); else ui.set_brightness(0); break; case TUNE_BACKLIGHT: if (draw) { - Draw_Menu_Item(row, ICON_Brightness, "LCD Brightness"); + Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); Draw_Float(ui.brightness, row, false, 1); } else @@ -3900,7 +3916,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ switch (item) { case PREHEATHOTEND_BACK: if (draw) - Draw_Menu_Item(row, ICON_Back, "Cancel"); + Draw_Menu_Item(row, ICON_Back, F("Cancel")); else { thermalManager.setTargetHotend(0, 0); thermalManager.set_fan_speed(0, 0); @@ -3909,7 +3925,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ break; case PREHEATHOTEND_CONTINUE: if (draw) - Draw_Menu_Item(row, ICON_SetEndTemp, "Continue"); + Draw_Menu_Item(row, ICON_SetEndTemp, F("Continue")); else { Popup_Handler(Heating); thermalManager.wait_for_hotend(0); @@ -3951,7 +3967,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 1 case PREHEATHOTEND_1: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_1_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_1_LABEL)); else { thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); @@ -3961,7 +3977,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 2 case PREHEATHOTEND_2: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_2_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_2_LABEL)); else { thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); @@ -3971,7 +3987,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 3 case PREHEATHOTEND_3: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_3_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_3_LABEL)); else { thermalManager.setTargetHotend(ui.material_preset[2].hotend_temp, 0); thermalManager.set_fan_speed(0, ui.material_preset[2].fan_speed); @@ -3981,7 +3997,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 4 case PREHEATHOTEND_4: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_4_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_4_LABEL)); else { thermalManager.setTargetHotend(ui.material_preset[3].hotend_temp, 0); thermalManager.set_fan_speed(0, ui.material_preset[3].fan_speed); @@ -3991,7 +4007,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #if PREHEAT_COUNT >= 5 case PREHEATHOTEND_5: if (draw) - Draw_Menu_Item(row, ICON_Temperature, PREHEAT_5_LABEL); + Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_5_LABEL)); else { thermalManager.setTargetHotend(ui.material_preset[4].hotend_temp, 0); thermalManager.set_fan_speed(0, ui.material_preset[4].fan_speed); @@ -4000,7 +4016,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ #endif case PREHEATHOTEND_CUSTOM: if (draw) { - Draw_Menu_Item(row, ICON_Temperature, "Custom"); + Draw_Menu_Item(row, ICON_Temperature, F("Custom")); Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); } else @@ -4011,81 +4027,81 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ } } -const char * CrealityDWINClass::Get_Menu_Title(uint8_t menu) { +FSTR_P CrealityDWINClass::Get_Menu_Title(uint8_t menu) { switch (menu) { - case MainMenu: return "Main Menu"; - case Prepare: return "Prepare"; - case HomeMenu: return "Homing Menu"; - case Move: return "Move"; - case ManualLevel: return "Manual Leveling"; + case MainMenu: return F("Main Menu"); + case Prepare: return F("Prepare"); + case HomeMenu: return F("Homing Menu"); + case Move: return F("Move"); + case ManualLevel: return F("Manual Leveling"); #if HAS_ZOFFSET_ITEM - case ZOffset: return "Z Offset"; + case ZOffset: return F("Z Offset"); #endif #if HAS_PREHEAT - case Preheat: return "Preheat"; + case Preheat: return F("Preheat"); #endif #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - case ChangeFilament: return "Change Filament"; + case ChangeFilament: return F("Change Filament"); #endif - case Control: return "Control"; - case TempMenu: return "Temperature"; + case Control: return F("Control"); + case TempMenu: return F("Temperature"); #if HAS_HOTEND || HAS_HEATED_BED - case PID: return "PID Menu"; + case PID: return F("PID Menu"); #endif #if HAS_HOTEND - case HotendPID: return "Hotend PID Settings"; + case HotendPID: return F("Hotend PID Settings"); #endif #if HAS_HEATED_BED - case BedPID: return "Bed PID Settings"; + case BedPID: return F("Bed PID Settings"); #endif #if PREHEAT_COUNT >= 1 - case Preheat1: return (PREHEAT_1_LABEL " Settings"); + case Preheat1: return F(PREHEAT_1_LABEL " Settings"); #endif #if PREHEAT_COUNT >= 2 - case Preheat2: return (PREHEAT_2_LABEL " Settings"); + case Preheat2: return F(PREHEAT_2_LABEL " Settings"); #endif #if PREHEAT_COUNT >= 3 - case Preheat3: return (PREHEAT_3_LABEL " Settings"); + case Preheat3: return F(PREHEAT_3_LABEL " Settings"); #endif #if PREHEAT_COUNT >= 4 - case Preheat4: return (PREHEAT_4_LABEL " Settings"); + case Preheat4: return F(PREHEAT_4_LABEL " Settings"); #endif #if PREHEAT_COUNT >= 5 - case Preheat5: return (PREHEAT_5_LABEL " Settings"); + case Preheat5: return F(PREHEAT_5_LABEL " Settings"); #endif - case Motion: return "Motion Settings"; - case HomeOffsets: return "Home Offsets"; - case MaxSpeed: return "Max Speed"; - case MaxAcceleration: return "Max Acceleration"; + case Motion: return F("Motion Settings"); + case HomeOffsets: return F("Home Offsets"); + case MaxSpeed: return F("Max Speed"); + case MaxAcceleration: return F("Max Acceleration"); #if HAS_CLASSIC_JERK - case MaxJerk: return "Max Jerk"; + case MaxJerk: return F("Max Jerk"); #endif - case Steps: return "Steps/mm"; - case Visual: return "Visual Settings"; - case Advanced: return "Advanced Settings"; + case Steps: return F("Steps/mm"); + case Visual: return F("Visual Settings"); + case Advanced: return F("Advanced Settings"); #if HAS_BED_PROBE - case ProbeMenu: return "Probe Menu"; + case ProbeMenu: return F("Probe Menu"); #endif - case ColorSettings: return "UI Color Settings"; - case Info: return "Info"; - case InfoMain: return "Info"; + case ColorSettings: return F("UI Color Settings"); + case Info: return F("Info"); + case InfoMain: return F("Info"); #if HAS_MESH - case Leveling: return "Leveling"; - case LevelView: return GET_TEXT(MSG_MESH_VIEW); - case LevelSettings: return "Leveling Settings"; - case MeshViewer: return GET_TEXT(MSG_MESH_VIEW); - case LevelManual: return "Manual Tuning"; + case Leveling: return F("Leveling"); + case LevelView: return GET_TEXT_F(MSG_MESH_VIEW); + case LevelSettings: return F("Leveling Settings"); + case MeshViewer: return GET_TEXT_F(MSG_MESH_VIEW); + case LevelManual: return F("Manual Tuning"); #endif #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE - case UBLMesh: return "UBL Bed Leveling"; + case UBLMesh: return F("UBL Bed Leveling"); #endif #if ENABLED(PROBE_MANUALLY) - case ManualMesh: return "Mesh Bed Leveling"; + case ManualMesh: return F("Mesh Bed Leveling"); #endif - case Tune: return "Tune"; - case PreheatHotend: return "Preheat Hotend"; + case Tune: return F("Tune"); + case PreheatHotend: return F("Preheat Hotend"); } - return ""; + return F(""); } uint8_t CrealityDWINClass::Get_Menu_Size(uint8_t menu) { @@ -4169,25 +4185,25 @@ uint8_t CrealityDWINClass::Get_Menu_Size(uint8_t menu) { void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { popup = last_popup = popupid; switch (popupid) { - case Pause: Draw_Popup(PSTR("Pause Print"), PSTR(""), PSTR(""), Popup); break; - case Stop: Draw_Popup(PSTR("Stop Print"), PSTR(""), PSTR(""), Popup); break; - case Resume: Draw_Popup(PSTR("Resume Print?"), PSTR("Looks Like the last"), PSTR("print was interupted."), Popup); break; - case ConfFilChange: Draw_Popup(PSTR("Confirm Filament Change"), PSTR(""), PSTR(""), Popup); break; - case PurgeMore: Draw_Popup(PSTR("Purge more filament?"), PSTR("(Cancel to finish process)"), PSTR(""), Popup); break; - case SaveLevel: Draw_Popup(PSTR("Leveling Complete"), PSTR("Save to EEPROM?"), PSTR(""), Popup); break; - case MeshSlot: Draw_Popup(PSTR("Mesh slot not selected"), PSTR("(Confirm to select slot 0)"), PSTR(""), Popup); break; - case ETemp: Draw_Popup(PSTR("Nozzle is too cold"), PSTR("Open Preheat Menu?"), PSTR(""), Popup); break; - case ManualProbing: Draw_Popup(PSTR("Manual Probing"), PSTR("(Confirm to probe)"), PSTR("(cancel to exit)"), Popup); break; - case Level: Draw_Popup(PSTR("Auto Bed Leveling"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_AutoLeveling); break; - case Home: Draw_Popup(option ? PSTR("Parking") : PSTR("Homing"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; - case MoveWait: Draw_Popup(PSTR("Moving to Point"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; - case Heating: Draw_Popup(PSTR("Heating"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; - case FilLoad: Draw_Popup(option ? PSTR("Unloading Filament") : PSTR("Loading Filament"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; - case FilChange: Draw_Popup(PSTR("Filament Change"), PSTR("Please wait for prompt."), PSTR(""), Wait, ICON_BLTouch); break; - case TempWarn: Draw_Popup(option ? PSTR("Nozzle temp too low!") : PSTR("Nozzle temp too high!"), PSTR(""), PSTR(""), Wait, option ? ICON_TempTooLow : ICON_TempTooHigh); break; - case Runout: Draw_Popup(PSTR("Filament Runout"), PSTR(""), PSTR(""), Wait, ICON_BLTouch); break; - case PIDWait: Draw_Popup(PSTR("PID Autotune"), PSTR("in process"), PSTR("Please wait until done."), Wait, ICON_BLTouch); break; - case Resuming: Draw_Popup(PSTR("Resuming Print"), PSTR("Please wait until done."), PSTR(""), Wait, ICON_BLTouch); break; + case Pause: Draw_Popup(F("Pause Print"), F(""), F(""), Popup); break; + case Stop: Draw_Popup(F("Stop Print"), F(""), F(""), Popup); break; + case Resume: Draw_Popup(F("Resume Print?"), F("Looks Like the last"), F("print was interupted."), Popup); break; + case ConfFilChange: Draw_Popup(F("Confirm Filament Change"), F(""), F(""), Popup); break; + case PurgeMore: Draw_Popup(F("Purge more filament?"), F("(Cancel to finish process)"), F(""), Popup); break; + case SaveLevel: Draw_Popup(F("Leveling Complete"), F("Save to EEPROM?"), F(""), Popup); break; + case MeshSlot: Draw_Popup(F("Mesh slot not selected"), F("(Confirm to select slot 0)"), F(""), Popup); break; + case ETemp: Draw_Popup(F("Nozzle is too cold"), F("Open Preheat Menu?"), F(""), Popup); break; + case ManualProbing: Draw_Popup(F("Manual Probing"), F("(Confirm to probe)"), F("(cancel to exit)"), Popup); break; + case Level: Draw_Popup(F("Auto Bed Leveling"), F("Please wait until done."), F(""), Wait, ICON_AutoLeveling); break; + case Home: Draw_Popup(option ? F("Parking") : F("Homing"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case MoveWait: Draw_Popup(F("Moving to Point"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case Heating: Draw_Popup(F("Heating"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case FilLoad: Draw_Popup(option ? F("Unloading Filament") : F("Loading Filament"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case FilChange: Draw_Popup(F("Filament Change"), F("Please wait for prompt."), F(""), Wait, ICON_BLTouch); break; + case TempWarn: Draw_Popup(option ? F("Nozzle temp too low!") : F("Nozzle temp too high!"), F(""), F(""), Wait, option ? ICON_TempTooLow : ICON_TempTooHigh); break; + case Runout: Draw_Popup(F("Filament Runout"), F(""), F(""), Wait, ICON_BLTouch); break; + case PIDWait: Draw_Popup(F("PID Autotune"), F("in process"), F("Please wait until done."), Wait, ICON_BLTouch); break; + case Resuming: Draw_Popup(F("Resuming Print"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; default: break; } } @@ -4195,11 +4211,11 @@ void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { void CrealityDWINClass::Confirm_Handler(PopupID popupid) { popup = popupid; switch (popupid) { - case FilInsert: Draw_Popup(PSTR("Insert Filament"), PSTR("Press to Continue"), PSTR(""), Confirm); break; - case HeaterTime: Draw_Popup(PSTR("Heater Timed Out"), PSTR("Press to Reheat"), PSTR(""), Confirm); break; - case UserInput: Draw_Popup(PSTR("Waiting for Input"), PSTR("Press to Continue"), PSTR(""), Confirm); break; - case LevelError: Draw_Popup(PSTR("Couldn't enable Leveling"), PSTR("(Valid mesh must exist)"), PSTR(""), Confirm); break; - case InvalidMesh: Draw_Popup(PSTR("Valid mesh must exist"), PSTR("before tuning can be"), PSTR("performed"), Confirm); break; + case FilInsert: Draw_Popup(F("Insert Filament"), F("Press to Continue"), F(""), Confirm); break; + case HeaterTime: Draw_Popup(F("Heater Timed Out"), F("Press to Reheat"), F(""), Confirm); break; + case UserInput: Draw_Popup(F("Waiting for Input"), F("Press to Continue"), F(""), Confirm); break; + case LevelError: Draw_Popup(F("Couldn't enable Leveling"), F("(Valid mesh must exist)"), F(""), Confirm); break; + case InvalidMesh: Draw_Popup(F("Valid mesh must exist"), F("before tuning can be"), F("performed"), Confirm); break; default: break; } } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index 92470c2f0e..0157f673ce 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -175,7 +175,9 @@ public: static uint16_t GetColor(uint8_t color, uint16_t original, bool light=false); static void Draw_Checkbox(uint8_t row, bool value); static void Draw_Title(const char * title); + static void Draw_Title(FSTR_P const title); static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, const char * const label1=nullptr, const char * const label2=nullptr, bool more=false, bool centered=false); + static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, FSTR_P const flabel1=nullptr, FSTR_P const flabel2=nullptr, bool more=false, bool centered=false); static void Draw_Menu(uint8_t menu, uint8_t select=0, uint8_t scroll=0); static void Redraw_Menu(bool lastprocess=true, bool lastselection=false, bool lastmenu=false); static void Redraw_Screen(); @@ -194,7 +196,7 @@ public: static void Draw_SD_Item(uint8_t item, uint8_t row); static void Draw_SD_List(bool removed=false); static void Draw_Status_Area(bool icons=false); - static void Draw_Popup(PGM_P const line1, PGM_P const line2, PGM_P const line3, uint8_t mode, uint8_t icon=0); + static void Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon=0); static void Popup_Select(); static void Update_Status_Bar(bool refresh=false); @@ -203,7 +205,7 @@ public: static void Set_Mesh_Viewer_Status(); #endif - static const char * Get_Menu_Title(uint8_t menu); + static FSTR_P Get_Menu_Title(uint8_t menu); static uint8_t Get_Menu_Size(uint8_t menu); static void Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw=true); From 417e2530ebc5b6c74ac34adaba8be552b407383a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 21:11:31 -0500 Subject: [PATCH 0754/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20G-c?= =?UTF-8?q?ode=20suite=20and=20queue?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 10 ++-- Marlin/src/feature/mmu/mmu2.cpp | 2 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/feature/runout.cpp | 2 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/queue.cpp | 8 +-- Marlin/src/gcode/queue.h | 8 +-- Marlin/src/lcd/e3v2/creality/dwin.cpp | 16 +++--- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 26 ++++----- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 14 ++--- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 2 +- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 4 +- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 4 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 54 +++++++++---------- .../extui/dgus/origin/DGUSScreenHandler.cpp | 4 +- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 18 +++---- .../extui/dgus_reloaded/DGUSSetupHandler.cpp | 6 +-- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 2 +- .../src/lcd/extui/mks_ui/draw_extrusion.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/draw_home.cpp | 10 ++-- Marlin/src/lcd/extui/mks_ui/draw_more.cpp | 12 ++--- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_set.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_tool.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 4 +- Marlin/src/lcd/marlinui.cpp | 6 +-- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 8 +-- Marlin/src/lcd/menu/menu_configuration.cpp | 6 +-- Marlin/src/lcd/menu/menu_filament.cpp | 2 +- Marlin/src/lcd/menu/menu_item.h | 6 +-- Marlin/src/lcd/menu/menu_job_recovery.cpp | 2 +- Marlin/src/lcd/menu/menu_main.cpp | 6 +-- Marlin/src/lcd/menu/menu_probe_offset.cpp | 2 +- Marlin/src/lcd/menu/menu_tramming.cpp | 2 +- Marlin/src/lcd/tft/ui_1024x600.cpp | 2 +- Marlin/src/lcd/tft/ui_320x240.cpp | 2 +- Marlin/src/lcd/tft/ui_480x320.cpp | 2 +- 39 files changed, 136 insertions(+), 134 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1b9c8885b1..6309f9f0d5 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -357,15 +357,15 @@ void startOrResumeJob() { TERN_(POWER_LOSS_RECOVERY, recovery.purge()); #ifdef EVENT_GCODE_SD_ABORT - queue.inject_P(PSTR(EVENT_GCODE_SD_ABORT)); + queue.inject(F(EVENT_GCODE_SD_ABORT)); #endif TERN_(PASSWORD_AFTER_SD_PRINT_ABORT, password.lock_machine()); } inline void finishSDPrinting() { - if (queue.enqueue_one_P(PSTR("M1001"))) { // Keep trying until it gets queued - marlin_state = MF_RUNNING; // Signal to stop trying + if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued + marlin_state = MF_RUNNING; // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished()); } @@ -493,7 +493,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { if (ELAPSED(ms, next_cub_ms_##N)) { \ next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ CODE; \ - queue.inject_P(PSTR(BUTTON##N##_GCODE)); \ + queue.inject(F(BUTTON##N##_GCODE)); \ TERN_(HAS_LCD_MENU, ui.quick_feedback()); \ } \ } \ @@ -1521,7 +1521,7 @@ void setup() { #ifdef STARTUP_COMMANDS SETUP_LOG("STARTUP_COMMANDS"); - queue.inject_P(PSTR(STARTUP_COMMANDS)); + queue.inject(F(STARTUP_COMMANDS)); #endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 3727c8c86d..d9a4c07d57 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -842,7 +842,7 @@ void MMU2::set_filament_type(const uint8_t index, const uint8_t filamentType) { } void MMU2::filament_runout() { - queue.inject_P(PSTR(MMU2_FILAMENT_RUNOUT_SCRIPT)); + queue.inject(F(MMU2_FILAMENT_RUNOUT_SCRIPT)); planner.synchronize(); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index a551ba4c8b..9808113ecc 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -109,7 +109,7 @@ void PrintJobRecovery::check() { if (card.isMounted()) { load(); if (!valid()) return cancel(); - queue.inject_P(PSTR("M1000S")); + queue.inject(F("M1000S")); } } diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 1c56378359..85280d7cb1 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -140,7 +140,7 @@ void event_filament_runout(const uint8_t extruder) { SERIAL_ECHOPGM("Runout Command: "); SERIAL_ECHOLNPGM(FILAMENT_RUNOUT_SCRIPT); #endif - queue.inject_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); + queue.inject(F(FILAMENT_RUNOUT_SCRIPT)); #endif } } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 11e503f013..930953ea14 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -103,7 +103,7 @@ void GcodeSuite::G29() { mbl.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2")); + queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2")); TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); return; } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 8ffa043b51..063f76bd85 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -126,7 +126,7 @@ bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ * Enqueue with Serial Echo * Return true if the command was consumed */ -bool GCodeQueue::enqueue_one(const char *cmd) { +bool GCodeQueue::enqueue_one(const char * const cmd) { //SERIAL_ECHOLNPGM("enqueue_one(\"", cmd, "\")"); if (*cmd == 0 || ISEOL(*cmd)) return true; @@ -195,15 +195,15 @@ bool GCodeQueue::process_injected_command() { * Enqueue and return only when commands are actually enqueued. * Never call this from a G-code handler! */ -void GCodeQueue::enqueue_one_now(const char *cmd) { while (!enqueue_one(cmd)) idle(); } +void GCodeQueue::enqueue_one_now(const char * const 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) { +bool GCodeQueue::enqueue_one(FSTR_P const fgcode) { size_t i = 0; - PGM_P p = pgcode; + PGM_P p = FTOP(fgcode); char c; while ((c = pgm_read_byte(&p[i])) && c != '\n') i++; char cmd[i + 1]; diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 6bcf4a97e4..71a710b8cb 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -127,6 +127,7 @@ public: * Aborts the current PROGMEM queue so only use for one or two commands. */ static inline void inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } + static inline void inject(FSTR_P const fgcode) { inject_P(FTOP(fgcode)); } /** * Enqueue command(s) to run from SRAM. Drained by process_injected_command(). @@ -139,18 +140,19 @@ public: /** * Enqueue and return only when commands are actually enqueued */ - static void enqueue_one_now(const char *cmd); + static void enqueue_one_now(const char * const cmd); /** * Attempt to enqueue a single G-code command * and return 'true' if successful. */ - static bool enqueue_one_P(PGM_P const pgcode); + static bool enqueue_one(FSTR_P const fgcode); /** * Enqueue from program memory and return only when commands are actually enqueued */ - static void enqueue_now_P(PGM_P const cmd); + static void enqueue_now_P(PGM_P const pcmd); + static inline void enqueue_now(FSTR_P const fcmd) { enqueue_now_P(FTOP(fcmd)); } /** * Check whether there are any commands yet to be executed diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 54fa6f941b..5b1d36fdae 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -2352,7 +2352,7 @@ void HMI_PauseOrStop() { if (select_print.now == PRINT_PAUSE_RESUME) { if (HMI_flag.select_flag) { HMI_flag.pause_action = true; - queue.inject_P(PSTR("M25")); + queue.inject(F("M25")); } Goto_PrintProcess(); } @@ -2711,7 +2711,7 @@ void HMI_Prepare() { #endif break; - case PREPARE_CASE_DISA: queue.inject_P(PSTR("M84")); break; + case PREPARE_CASE_DISA: queue.inject(F("M84")); break; case PREPARE_CASE_HOME: // Homing checkkey = Last_Prepare; @@ -2729,7 +2729,7 @@ void HMI_Prepare() { EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); + queue.inject(F("G92 X0 Y0 Z0")); HMI_AudioFeedback(); #endif break; @@ -2944,7 +2944,7 @@ void HMI_Control() { void HMI_Leveling() { Popup_Window_Leveling(); DWIN_UpdateLCD(); - queue.inject_P(PSTR("G28O\nG29")); + queue.inject(F("G28O\nG29")); } #endif @@ -3803,7 +3803,7 @@ void HMI_Tune() { EncoderRate.enabled = true; #else // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); + queue.inject(F("G92 X0 Y0 Z0")); HMI_AudioFeedback(); #endif break; @@ -4112,7 +4112,7 @@ void EachMomentUpdate() { TERN_(HAS_HEATED_BED, resume_bed_temp = thermalManager.degTargetBed()); thermalManager.disable_all_heaters(); #endif - queue.inject_P(PSTR("G1 F1200 X0 Y0")); + queue.inject(F("G1 F1200 X0 Y0")); } if (card.isPrinting() && checkkey == PrintProcess) { // print process @@ -4182,7 +4182,7 @@ void EachMomentUpdate() { if (encoder_diffState == ENCODER_DIFF_ENTER) { recovery_flag = false; if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); + TERN_(POWER_LOSS_RECOVERY, queue.inject(F("M1000C"))); HMI_StartFrame(true); return; } @@ -4195,7 +4195,7 @@ void EachMomentUpdate() { select_print.set(0); HMI_ValueStruct.show_mode = 0; - queue.inject_P(PSTR("M1000")); + queue.inject(F("M1000")); Goto_PrintProcess(); Draw_Status_Area(true); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index dcadc78a5c..285c23cd2b 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -1157,7 +1157,7 @@ void HMI_MainMenu() { case PAGE_INFO_LEVELING: #if HAS_ONESTEP_LEVELING - queue.inject_P(PSTR("G28XYO\nG28Z\nG29")); // TODO: 'G29' should be homing when needed. Does it make sense for every LCD to do this differently? + queue.inject(F("G28XYO\nG28Z\nG29")); // TODO: 'G29' should be homing when needed. Does it make sense for every LCD to do this differently? #else checkkey = Info; Draw_Info_Menu(); @@ -1376,7 +1376,7 @@ void HMI_PauseOrStop() { if (HMI_flag.select_flag) { HMI_flag.pause_action = true; ICON_Resume(); - queue.inject_P(PSTR("M25")); + queue.inject(F("M25")); } else { // cancel pause @@ -1510,7 +1510,7 @@ void EachMomentUpdate() { TERN_(HAS_FAN, resume_fan = thermalManager.fan_speed[0]); #endif IF_DISABLED(ADVANCED_PAUSE_FEATURE, thermalManager.disable_all_heaters()); - IF_DISABLED(PARK_HEAD_ON_PAUSE, queue.inject_P(PSTR("G1 F1200 X0 Y0"))); + IF_DISABLED(PARK_HEAD_ON_PAUSE, queue.inject(F("G1 F1200 X0 Y0"))); } if (checkkey == PrintProcess) { // print process @@ -1588,7 +1588,7 @@ void EachMomentUpdate() { if (encoder_diffState == ENCODER_DIFF_ENTER) { recovery_flag = false; if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); + TERN_(POWER_LOSS_RECOVERY, queue.inject(F("M1000C"))); return HMI_StartFrame(true); } else @@ -1600,7 +1600,7 @@ void EachMomentUpdate() { } select_print.set(PRINT_SETUP); - queue.inject_P(PSTR("M1000")); + queue.inject(F("M1000")); sdprint = true; Goto_PrintProcess(); Draw_Status_Area(true); @@ -2086,13 +2086,13 @@ void Goto_InfoMenu(){ Draw_Info_Menu(); } -void DisableMotors() { queue.inject_P(PSTR("M84")); } +void DisableMotors() { queue.inject(F("M84")); } void AutoHome() { queue.inject_P(G28_STR); } void SetHome() { // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); + queue.inject(F("G92 X0 Y0 Z0")); HMI_AudioFeedback(); } @@ -2239,7 +2239,7 @@ void Goto_LockScreen() { DWIN_LockScreen(true); } void SetProbeOffsetZ() { SetPFloatOnClick(-10, 10, 2); } void ProbeTest() { ui.set_status_P(GET_TEXT(MSG_M48_TEST)); - queue.inject_P(PSTR("G28O\nM48 P10")); + queue.inject(F("G28O\nM48 P10")); } #endif @@ -2319,23 +2319,23 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } void ChangeFilament() { HMI_SaveProcessID(NothingToDo); - queue.inject_P(PSTR("M600 B2")); + queue.inject(F("M600 B2")); } void ParkHead(){ ui.set_status_P(GET_TEXT(MSG_FILAMENT_PARK_ENABLED)); - queue.inject_P(PSTR("G28O\nG27")); + queue.inject(F("G28O\nG27")); } #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) void UnloadFilament(){ ui.set_status_P(GET_TEXT(MSG_FILAMENTUNLOAD)); - queue.inject_P(PSTR("M702 Z20")); + queue.inject(F("M702 Z20")); } void LoadFilament(){ ui.set_status_P(GET_TEXT(MSG_FILAMENTLOAD)); - queue.inject_P(PSTR("M701 Z20")); + queue.inject(F("M701 Z20")); } #endif @@ -2433,7 +2433,7 @@ void LevBedC () { LevBed(4); } void ManualMeshSave(){ ui.set_status_P(GET_TEXT(MSG_UBL_STORAGE_MESH_MENU)); - queue.inject_P(PSTR("M211 S1\nM500")); + queue.inject(F("M211 S1\nM500")); } #endif // MESH_BED_LEVELING diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 11c2c01259..8e4abbe4bc 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -1055,7 +1055,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/ if (draw) Draw_Menu_Item(row, ICON_CloseMotor, F("Disable Stepper")); else - queue.inject_P(PSTR("M84")); + queue.inject(F("M84")); break; case PREPARE_HOME: if (draw) @@ -4499,7 +4499,7 @@ void CrealityDWINClass::Print_Screen_Control() { #endif TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); planner.synchronize(); - TERN_(SDSUPPORT, queue.inject_P(PSTR("M24"))); + TERN_(SDSUPPORT, queue.inject(F("M24"))); #endif } else { @@ -4541,10 +4541,10 @@ void CrealityDWINClass::Popup_Control() { if (IS_SD_PRINTING()) card.pauseSDPrint(); #endif planner.synchronize(); - queue.inject_P(PSTR("M125")); + queue.inject(F("M125")); planner.synchronize(); #else - queue.inject_P(PSTR("M25")); + queue.inject(F("M25")); TERN_(HAS_HOTEND, pausetemp = thermalManager.temp_hotend[0].target); TERN_(HAS_HEATED_BED, pausebed = thermalManager.temp_bed.target); TERN_(HAS_FAN, pausefan = thermalManager.fan_speed[0]); @@ -4574,9 +4574,9 @@ void CrealityDWINClass::Popup_Control() { break; case Resume: if (selection == 0) - queue.inject_P(PSTR("M1000")); + queue.inject(F("M1000")); else { - queue.inject_P(PSTR("M1000 C")); + queue.inject(F("M1000 C")); Draw_Main_Menu(); } break; @@ -5008,7 +5008,7 @@ void CrealityDWINClass::Load_Settings(const char *buff) { static bool init = true; if (init) { init = false; - queue.inject_P(PSTR("M1000 S")); + queue.inject(F("M1000 S")); } #endif } diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 16576f7039..06b350ff77 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -683,7 +683,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr void DGUSScreenHandler::HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr) { uint16_t value = swap16(*(uint16_t*)val_ptr); if (value) { - queue.inject_P(PSTR("M1000")); + queue.inject(F("M1000")); dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), 32, true); GotoScreen(PLR_SCREEN_RECOVER); } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 60a0f6c5bb..2f08136cbb 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -205,7 +205,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); //DEBUG_ECHOPGM(" ✓ "); } char buf[32]; // G1 X9999.99 F12345 @@ -227,7 +227,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { //DEBUG_ECHOLNPGM(" ✓ "); if (!old_relative_mode) { //DEBUG_ECHOPGM("G90"); - queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now(F("G90")); //DEBUG_ECHOPGM(" ✓ "); } } diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index 83f7a39c28..f72a9f439d 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -205,7 +205,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); //DEBUG_ECHOPGM(" ✓ "); } char buf[32]; // G1 X9999.99 F12345 @@ -227,7 +227,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { //DEBUG_ECHOLNPGM(" ✓ "); if (!old_relative_mode) { //DEBUG_ECHOPGM("G90"); - queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now(F("G90")); //DEBUG_ECHOPGM(" ✓ "); } } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 2ec67b2727..0dc1e2245e 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -450,7 +450,7 @@ void DGUSScreenHandler::Level_Ctrl_MKS(DGUS_VP_Variable &var, void *val_ptr) { a_first_level = 0; queue.enqueue_now_P(G28_STR); } - queue.enqueue_now_P(PSTR("G29")); + queue.enqueue_now(F("G29")); #elif ENABLED(MESH_BED_LEVELING) @@ -512,10 +512,10 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { Deci2 = offset * 100; Deci2 = Deci2 % 10; soft_endstop._enabled = false; - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); snprintf_P(cmd_buf, 30, PSTR("G1 Z%d.%d%d"), integer, Deci, Deci2); queue.enqueue_one_now(cmd_buf); - queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now(F("G90")); //soft_endstop._enabled = true; break; @@ -527,17 +527,17 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { Deci2 = offset * 100; Deci2 = Deci2 % 10; soft_endstop._enabled = false; - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); snprintf_P(cmd_buf, 30, PSTR("G1 Z-%d.%d%d"), integer, Deci, Deci2); queue.enqueue_one_now(cmd_buf); - queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now(F("G90")); break; case 2: if (mesh_point_count == GRID_MAX_POINTS) { // The first point - queue.enqueue_now_P(PSTR("G28")); - queue.enqueue_now_P(PSTR("G29S1")); + queue.enqueue_now(F("G28")); + queue.enqueue_now(F("G29S1")); mesh_point_count--; if (mks_language_index == MKS_English) { @@ -550,7 +550,7 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { } } else if (mesh_point_count > 1) { // 倒数第二个点 - queue.enqueue_now_P(PSTR("G29S2")); + queue.enqueue_now(F("G29S2")); mesh_point_count--; if (mks_language_index == MKS_English) { const char level_buf_en2[] = "Next Point"; @@ -562,7 +562,7 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { } } else if (mesh_point_count == 1) { - queue.enqueue_now_P(PSTR("G29S2")); + queue.enqueue_now(F("G29S2")); mesh_point_count--; if (mks_language_index == MKS_English) { const char level_buf_en2[] = "Level Finsh"; @@ -620,13 +620,13 @@ void DGUSScreenHandler::ManualAssistLeveling(DGUS_VP_Variable &var, void *val_pt }; if (WITHIN(point_value, 0x0001, 0x0005)) - queue.enqueue_now_P(PSTR("G1Z10")); + queue.enqueue_now(F("G1Z10")); switch (point_value) { case 0x0001: enqueue_corner_move(X_MIN_POS + ABS(mks_corner_offsets[0].x), Y_MIN_POS + ABS(mks_corner_offsets[0].y), level_speed); - queue.enqueue_now_P(PSTR("G28Z")); + queue.enqueue_now(F("G28Z")); break; case 0x0002: enqueue_corner_move(X_MAX_POS - ABS(mks_corner_offsets[1].x), @@ -647,8 +647,8 @@ void DGUSScreenHandler::ManualAssistLeveling(DGUS_VP_Variable &var, void *val_pt } if (WITHIN(point_value, 0x0002, 0x0005)) { - //queue.enqueue_now_P(PSTR("G28Z")); - queue.enqueue_now_P(PSTR("G1Z-10")); + //queue.enqueue_now(F("G28Z")); + queue.enqueue_now(F("G1Z-10")); } } @@ -856,7 +856,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); //DEBUG_ECHOPGM(" ✓ "); } char buf[32]; // G1 X9999.99 F12345 @@ -878,8 +878,8 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { //DEBUG_ECHOLNPGM(" ✓ "); if (!old_relative_mode) { //DEBUG_ECHOPGM("G90"); - //queue.enqueue_now_P(PSTR("G90")); - queue.enqueue_now_P(PSTR("G90")); + //queue.enqueue_now(F("G90")); + queue.enqueue_now(F("G90")); //DEBUG_ECHOPGM(" ✓ "); } } @@ -1133,30 +1133,30 @@ void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr switch (flag) { case 0: if (step == 0.01) - queue.inject_P(PSTR("M290 Z-0.01")); + queue.inject(F("M290 Z-0.01")); else if (step == 0.1) - queue.inject_P(PSTR("M290 Z-0.1")); + queue.inject(F("M290 Z-0.1")); else if (step == 0.5) - queue.inject_P(PSTR("M290 Z-0.5")); + queue.inject(F("M290 Z-0.5")); else if (step == 1) - queue.inject_P(PSTR("M290 Z-1")); + queue.inject(F("M290 Z-1")); else - queue.inject_P(PSTR("M290 Z-0.01")); + queue.inject(F("M290 Z-0.01")); z_offset_add = z_offset_add - ZOffset_distance; break; case 1: if (step == 0.01) - queue.inject_P(PSTR("M290 Z0.01")); + queue.inject(F("M290 Z0.01")); else if (step == 0.1) - queue.inject_P(PSTR("M290 Z0.1")); + queue.inject(F("M290 Z0.1")); else if (step == 0.5) - queue.inject_P(PSTR("M290 Z0.5")); + queue.inject(F("M290 Z0.5")); else if (step == 1) - queue.inject_P(PSTR("M290 Z1")); + queue.inject(F("M290 Z1")); else - queue.inject_P(PSTR("M290 Z-0.01")); + queue.inject(F("M290 Z-0.01")); z_offset_add = z_offset_add + ZOffset_distance; break; @@ -1486,7 +1486,7 @@ void DGUSScreenHandler::DGUS_Runout_Idle(void) { case RUNOUT_STATUS: runout_mks.runout_status = RUNOUT_BEGIN_STATUS; - queue.inject_P(PSTR("M25")); + queue.inject(F("M25")); GotoScreen(MKSLCD_SCREEN_PAUSE); sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please change filament!"), nullptr, true, true, true, true); diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index db467d7b34..82404ead94 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -205,7 +205,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); - queue.enqueue_now_P(PSTR("G91")); + queue.enqueue_now(F("G91")); //DEBUG_ECHOPGM(" ✓ "); } char buf[32]; // G1 X9999.99 F12345 @@ -227,7 +227,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { //DEBUG_ECHOLNPGM(" ✓ "); if (!old_relative_mode) { //DEBUG_ECHOPGM("G90"); - queue.enqueue_now_P(PSTR("G90")); + queue.enqueue_now(F("G90")); //DEBUG_ECHOPGM(" ✓ "); } } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 8567e5c0e7..f7d8da69fc 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -523,9 +523,9 @@ void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { dgus_screen_handler.TriggerScreenChange(DGUS_Screen::LEVELING_PROBING); #if ENABLED(AUTO_BED_LEVELING_UBL) - queue.enqueue_now_P(PSTR("G29P1\nG29P3\nG29P5C")); + queue.enqueue_now(F("G29P1\nG29P3\nG29P5C")); #else - queue.enqueue_now_P(PSTR("G29")); + queue.enqueue_now(F("G29")); #endif queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); } @@ -634,13 +634,13 @@ void DGUSRxHandler::Home(DGUS_VP &vp, void *data_ptr) { switch (axis) { case DGUS_Data::Axis::X_Y_Z: - queue.enqueue_now_P(PSTR("G28XYZ")); + queue.enqueue_now(F("G28XYZ")); break; case DGUS_Data::Axis::X_Y: - queue.enqueue_now_P(PSTR("G28XY")); + queue.enqueue_now(F("G28XY")); break; case DGUS_Data::Axis::Z: - queue.enqueue_now_P(PSTR("G28Z")); + queue.enqueue_now(F("G28Z")); break; } } @@ -784,7 +784,7 @@ void DGUSRxHandler::ResetEEPROM(DGUS_VP &vp, void *data_ptr) { return; } - queue.enqueue_now_P(PSTR("M502")); + queue.enqueue_now(F("M502")); queue.enqueue_now_P(DGUS_CMD_EEPROM_SAVE); } @@ -802,7 +802,7 @@ void DGUSRxHandler::SettingsExtra(DGUS_VP &vp, void *data_ptr) { return; } - queue.enqueue_now_P(PSTR(DGUS_RESET_BLTOUCH)); + queue.enqueue_now(F(DGUS_RESET_BLTOUCH)); #else dgus_screen_handler.TriggerScreenChange(DGUS_Screen::INFOS); #endif @@ -942,7 +942,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { dgus_screen_handler.TriggerScreenChange(DGUS_Screen::HOME); - queue.enqueue_now_P(PSTR("M1000C")); + queue.enqueue_now(F("M1000C")); } void DGUSRxHandler::PowerLossResume(DGUS_VP &vp, void *data_ptr) { @@ -966,7 +966,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); - queue.enqueue_now_P(PSTR("M1000")); + queue.enqueue_now(F("M1000")); } #endif // POWER_LOSS_RECOVERY diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp index 0d94751fc2..e93eb766ce 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -74,7 +74,7 @@ bool DGUSSetupHandler::LevelingMenu() { if (ExtUI::isPositionKnown()) { if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 10.0f) { - queue.enqueue_now_P(PSTR("G0Z10")); + queue.enqueue_now(F("G0Z10")); } return true; @@ -124,14 +124,14 @@ bool DGUSSetupHandler::LevelingOffset() { if (ExtUI::isPositionKnown()) { if (ExtUI::getAxisPosition_mm(ExtUI::Z) < 4.0f) { - queue.enqueue_now_P(PSTR("G0Z4")); + queue.enqueue_now(F("G0Z4")); } char buffer[20]; snprintf_P(buffer, sizeof(buffer), PSTR("G0X%dY%d"), DGUS_LEVEL_CENTER_X, DGUS_LEVEL_CENTER_Y); queue.enqueue_one_now(buffer); - queue.enqueue_now_P(PSTR("G0Z0")); + queue.enqueue_now(F("G0Z0")); return true; } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index a390bd92e3..3cdb07b608 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -201,7 +201,7 @@ static void btn_cancel_event_cb(lv_obj_t *btn, lv_event_t event) { draw_return_ui(); } else if (DIALOG_IS(TYPE_FILAMENT_LOADING, TYPE_FILAMENT_UNLOADING)) { - queue.enqueue_one_P(PSTR("M410")); + queue.enqueue_one(F("M410")); uiCfg.filament_rate = 0; uiCfg.filament_loading_completed = false; uiCfg.filament_unloading_completed = false; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index b18bd28339..f3204eb962 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -74,11 +74,11 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (ENABLED(HAS_MULTI_EXTRUDER)) { if (uiCfg.extruderIndex == 0) { uiCfg.extruderIndex = 1; - queue.inject_P(PSTR("T1")); + queue.inject(F("T1")); } else { uiCfg.extruderIndex = 0; - queue.inject_P(PSTR("T0")); + queue.inject(F("T0")); } } else diff --git a/Marlin/src/lcd/extui/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp index 8dba33756a..04ebd95a09 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_home.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.cpp @@ -52,19 +52,19 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { queue.inject_P(G28_STR); break; case ID_H_X: - queue.inject_P(PSTR("G28X")); + queue.inject(F("G28X")); break; case ID_H_Y: - queue.inject_P(PSTR("G28Y")); + queue.inject(F("G28Y")); break; case ID_H_Z: - queue.inject_P(PSTR("G28Z")); + queue.inject(F("G28Z")); break; case ID_H_OFF_ALL: - queue.inject_P(PSTR("M84")); + queue.inject(F("M84")); break; case ID_H_OFF_XY: - queue.inject_P(PSTR("M84XY")); + queue.inject(F("M84XY")); break; case ID_H_RETURN: clear_cur_ui(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp index 6c5fa2fa3d..a9c1dc1ec6 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -62,22 +62,22 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_GCODE: lv_clear_more(); lv_draw_gcode(true); break; #if HAS_USER_ITEM(1) - case ID_CUSTOM_1: queue.inject_P(PSTR(MAIN_MENU_ITEM_1_GCODE)); break; + case ID_CUSTOM_1: queue.inject(F(MAIN_MENU_ITEM_1_GCODE)); break; #endif #if HAS_USER_ITEM(2) - case ID_CUSTOM_2: queue.inject_P(PSTR(MAIN_MENU_ITEM_2_GCODE)); break; + case ID_CUSTOM_2: queue.inject(F(MAIN_MENU_ITEM_2_GCODE)); break; #endif #if HAS_USER_ITEM(3) - case ID_CUSTOM_3: queue.inject_P(PSTR(MAIN_MENU_ITEM_3_GCODE)); break; + case ID_CUSTOM_3: queue.inject(F(MAIN_MENU_ITEM_3_GCODE)); break; #endif #if HAS_USER_ITEM(4) - case ID_CUSTOM_4: queue.inject_P(PSTR(MAIN_MENU_ITEM_4_GCODE)); break; + case ID_CUSTOM_4: queue.inject(F(MAIN_MENU_ITEM_4_GCODE)); break; #endif #if HAS_USER_ITEM(5) - case ID_CUSTOM_5: queue.inject_P(PSTR(MAIN_MENU_ITEM_5_GCODE)); break; + case ID_CUSTOM_5: queue.inject(F(MAIN_MENU_ITEM_5_GCODE)); break; #endif #if HAS_USER_ITEM(6) - case ID_CUSTOM_6: queue.inject_P(PSTR(MAIN_MENU_ITEM_6_GCODE)); break; + case ID_CUSTOM_6: queue.inject(F(MAIN_MENU_ITEM_6_GCODE)); break; #endif case ID_M_RETURN: lv_clear_more(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index 322d0581ca..be596c8740 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -308,7 +308,7 @@ void setProBarRate() { #if HAS_SUICIDE if (gCfgItems.finish_power_off) { gcode.process_subcommands_now(F("M1001")); - queue.inject_P(PSTR("M81")); + queue.inject(F("M81")); marlin_state = MF_RUNNING; } #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp index 2dd3a9dfd9..aadf0d98f0 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp @@ -57,7 +57,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; if (obj->mks_obj_id == ID_S_CONTINUE) return; if (obj->mks_obj_id == ID_S_MOTOR_OFF) { - TERN(HAS_SUICIDE, suicide(), queue.enqueue_now_P(PSTR("M84"))); + TERN(HAS_SUICIDE, suicide(), queue.enqueue_now(F("M84"))); return; } lv_clear_set(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp index 9a0462f148..66b30342b2 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.cpp @@ -62,7 +62,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) get_gcode_command(AUTO_LEVELING_COMMAND_ADDR, (uint8_t *)public_buf_m); public_buf_m[sizeof(public_buf_m) - 1] = 0; - queue.inject_P(PSTR(public_buf_m)); + queue.inject(public_buf_m); #else uiCfg.leveling_first_time = true; lv_draw_manualLevel(); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index e4140edc79..f0d0156151 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -1169,7 +1169,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { } send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - queue.enqueue_one_P(PSTR("M105")); + queue.enqueue_one(F("M105")); break; case 992: @@ -2035,7 +2035,7 @@ void get_wifi_commands() { #endif // Add the command to the queue - queue.enqueue_one_P(wifi_line_buffer); + queue.enqueue_one(wifi_line_buffer); } else if (wifi_read_count >= MAX_CMD_SIZE - 1) { diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 14d0e182c0..c8384fce31 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1542,7 +1542,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if BOTH(PSU_CONTROL, PS_OFF_CONFIRM) void MarlinUI::poweroff() { - queue.inject_P(PSTR("M81")); + queue.inject(F("M81")); goto_previous_screen(); } #endif @@ -1570,9 +1570,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if ENABLED(PARK_HEAD_ON_PAUSE) pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress - queue.inject_P(PSTR("M25 P\nM24")); + queue.inject(F("M25 P\nM24")); #elif ENABLED(SDSUPPORT) - queue.inject_P(PSTR("M25")); + queue.inject(F("M25")); #elif defined(ACTION_ON_PAUSE) host_action_pause(); #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 8d87a876b9..9d424feb75 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -557,7 +557,7 @@ void menu_advanced_settings() { // // Set Home Offsets // - ACTION_ITEM(MSG_SET_HOME_OFFSETS, []{ queue.inject_P(PSTR("M428")); ui.return_to_status(); }); + ACTION_ITEM(MSG_SET_HOME_OFFSETS, []{ queue.inject(F("M428")); ui.return_to_status(); }); #endif // M203 / M205 - Feedrate items diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index ea9ef75aa1..1c7ab35e44 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -212,7 +212,7 @@ static void _lcd_level_bed_corners_get_next_position() { void _lcd_draw_level_prompt() { if (!ui.should_draw()) return; MenuItem_confirm::confirm_screen( - []{ queue.inject_P(TERN(HAS_LEVELING, PSTR("G29N"), G28_STR)); ui.return_to_status(); } + []{ queue.inject(TERN(HAS_LEVELING, F("G29N"), FPSTR(G28_STR))); ui.return_to_status(); } , []{ ui.goto_previous_screen_no_defer(); } , GET_TEXT(MSG_BED_TRAMMING_IN_RANGE) , (const char*)nullptr, PSTR("?") diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index f01c7899fb..eb286f96b9 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -103,9 +103,9 @@ ui.wait_for_move = true; ui.goto_screen(_lcd_level_bed_done); #if ENABLED(MESH_BED_LEVELING) - queue.inject_P(PSTR("G29S2")); + queue.inject(F("G29S2")); #elif ENABLED(PROBE_MANUALLY) - queue.inject_P(PSTR("G29V1")); + queue.inject(F("G29V1")); #endif } else @@ -155,9 +155,9 @@ // G29 Records Z, moves, and signals when it pauses ui.wait_for_move = true; #if ENABLED(MESH_BED_LEVELING) - queue.inject_P(manual_probe_index ? PSTR("G29S2") : PSTR("G29S1")); + queue.inject(manual_probe_index ? F("G29S2") : F("G29S1")); #elif ENABLED(PROBE_MANUALLY) - queue.inject_P(PSTR("G29V1")); + queue.inject(F("G29V1")); #endif } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 7021a0e667..0e11cd211a 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -341,8 +341,8 @@ void menu_advanced_settings(); #if ENABLED(CUSTOM_MENU_CONFIG) - void _lcd_custom_menus_configuration_gcode(PGM_P const cmd) { - queue.inject_P(cmd); + void _lcd_custom_menus_configuration_gcode(FSTR_P const fstr) { + queue.inject(fstr); TERN_(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); TERN_(CUSTOM_MENU_CONFIG_SCRIPT_RETURN, ui.return_to_status()); } @@ -358,7 +358,7 @@ void menu_advanced_settings(); #else #define _DONE_SCRIPT "" #endif - #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(PSTR(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(F(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } #define _CUSTOM_ITEM_CONF(N) ACTION_ITEM_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_CONF(N)); #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ SUBMENU_P(PSTR(CONFIG_MENU_ITEM_##N##_DESC), []{ \ diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 53fd67dbb2..7d0d2dc72c 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -209,7 +209,7 @@ void menu_change_filament() { #else if (thermalManager.targetHotEnoughToExtrude(active_extruder)) - queue.inject_P(PSTR("M600B0")); + queue.inject(F("M600B0")); else ui.goto_screen([]{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, 0); }); diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index a2f7c5bec2..56138a15bd 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -23,7 +23,7 @@ #include "menu.h" #include "../marlinui.h" -#include "../../gcode/queue.h" // for inject_P +#include "../../gcode/queue.h" // for inject #include "../../inc/MarlinConfigPre.h" @@ -64,8 +64,8 @@ class MenuItem_gcode : public MenuItem_button { FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', ' '); } - static void action(PGM_P const, PGM_P const pgcode) { queue.inject_P(pgcode); } - static inline void action(PGM_P const pstr, const uint8_t, const char * const pgcode) { action(pstr, pgcode); } + static void action(PGM_P const, PGM_P const pgcode) { queue.inject(FPSTR(pgcode)); } + static inline void action(PGM_P const pstr, const uint8_t, PGM_P const pgcode) { action(pstr, pgcode); } }; //////////////////////////////////////////// diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp index 7cd2949d62..963806b1d6 100644 --- a/Marlin/src/lcd/menu/menu_job_recovery.cpp +++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp @@ -35,7 +35,7 @@ static void lcd_power_loss_recovery_resume() { ui.return_to_status(); - queue.inject_P(PSTR("M1000")); + queue.inject(F("M1000")); } void lcd_power_loss_recovery_cancel() { diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 1bf6645e2e..f39e008cd7 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -106,8 +106,8 @@ void menu_configuration(); #if ENABLED(CUSTOM_MENU_MAIN) - void _lcd_custom_menu_main_gcode(PGM_P const cmd) { - queue.inject_P(cmd); + void _lcd_custom_menu_main_gcode(FSTR_P const fstr) { + queue.inject(fstr); TERN_(CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); TERN_(CUSTOM_MENU_MAIN_SCRIPT_RETURN, ui.return_to_status()); } @@ -123,7 +123,7 @@ void menu_configuration(); #else #define _DONE_SCRIPT "" #endif - #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_main_gcode(PSTR(MAIN_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_main_gcode(F(MAIN_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } #define _CUSTOM_ITEM_MAIN(N) ACTION_ITEM_P(PSTR(MAIN_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_MAIN(N)); #define _CUSTOM_ITEM_MAIN_CONFIRM(N) \ SUBMENU_P(PSTR(MAIN_MENU_ITEM_##N##_DESC), []{ \ diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 5ed217131a..12b55969a3 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -111,7 +111,7 @@ void probe_offset_wizard_menu() { // If wizard-homing was done by probe with PROBE_OFFSET_WIZARD_START_Z #if HOMING_Z_WITH_PROBE && defined(PROBE_OFFSET_WIZARD_START_Z) set_axis_never_homed(Z_AXIS); // On cancel the Z position needs correction - queue.inject_P(PSTR("G28Z")); + queue.inject(F("G28Z")); #else // Otherwise do a Z clearance move like after Homing z_clearance_move(); #endif diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index 9bc799129e..5cdcf75c1e 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -96,7 +96,7 @@ void goto_tramming_wizard() { // Inject G28, wait for homing to complete, set_all_unhomed(); - queue.inject_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); + queue.inject(TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR))); ui.goto_screen([]{ _lcd_draw_homing(); diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 456bd32758..3f0c70ab4c 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -785,7 +785,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void disable_steppers() { quick_feedback(); - queue.inject_P(PSTR("M84")); + queue.inject(F("M84")); } static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 15d477c485..1ef4c5881c 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -770,7 +770,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void disable_steppers() { quick_feedback(); - queue.inject_P(PSTR("M84")); + queue.inject(F("M84")); } static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 424f29a182..f6591d682d 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -772,7 +772,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } static void disable_steppers() { quick_feedback(); - queue.inject_P(PSTR("M84")); + queue.inject(F("M84")); } static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { From 520b97083e52efdd47ab434b97823e48d85ade62 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Sep 2021 11:03:07 -0500 Subject: [PATCH 0755/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20ser?= =?UTF-8?q?ial=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp | 8 +- Marlin/src/core/debug_out.h | 8 +- Marlin/src/core/debug_section.h | 16 +-- Marlin/src/core/serial.cpp | 24 ++-- Marlin/src/core/serial.h | 126 ++++++++++++------ Marlin/src/core/utility.cpp | 6 +- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 8 +- Marlin/src/feature/encoder_i2c.cpp | 2 +- Marlin/src/feature/meatpack.cpp | 5 +- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/feature/probe_temp_comp.cpp | 6 +- Marlin/src/feature/runout.h | 4 +- Marlin/src/feature/tmc_util.cpp | 15 +-- Marlin/src/gcode/bedlevel/G35.cpp | 2 +- Marlin/src/gcode/bedlevel/M420.cpp | 8 +- Marlin/src/gcode/config/M217.cpp | 4 +- Marlin/src/gcode/config/M302.cpp | 2 +- Marlin/src/gcode/control/M211.cpp | 4 +- Marlin/src/gcode/control/M80_M81.cpp | 2 +- Marlin/src/gcode/feature/L6470/M122.cpp | 6 +- Marlin/src/gcode/feature/L6470/M906.cpp | 2 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 4 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 2 +- Marlin/src/gcode/geometry/G17-G19.cpp | 8 +- Marlin/src/gcode/parser.h | 4 +- Marlin/src/gcode/units/M149.cpp | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 10 +- Marlin/src/module/temperature.cpp | 38 +++--- Marlin/src/sd/cardreader.cpp | 4 +- docs/Serial.md | 2 +- 30 files changed, 187 insertions(+), 147 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index 6570a599a4..1991d79719 100644 --- a/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -90,15 +90,15 @@ bool PersistentStore::access_finish() { // to see errors that are happening in read_data / write_data static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) { #if ENABLED(DEBUG_SD_EEPROM_EMULATION) - PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); + FSTR_P const rw_str = write ? F("write") : F("read"); SERIAL_CHAR(' '); - SERIAL_ECHOPGM_P(rw_str); + SERIAL_ECHOF(rw_str); SERIAL_ECHOLNPGM("_data(", pos, ",", *value, ",", size, ", ...)"); if (total) { SERIAL_ECHOPGM(" f_"); - SERIAL_ECHOPGM_P(rw_str); + SERIAL_ECHOF(rw_str); SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_"); - SERIAL_ECHOLNPGM_P(write ? PSTR("written=") : PSTR("read="), total); + SERIAL_ECHOLNF(write ? F("written=") : F("read="), total); } else SERIAL_ECHOLNPGM(" f_lseek()=", s); diff --git a/Marlin/src/core/debug_out.h b/Marlin/src/core/debug_out.h index 4e30a5306e..eb1c91e507 100644 --- a/Marlin/src/core/debug_out.h +++ b/Marlin/src/core/debug_out.h @@ -36,6 +36,8 @@ #undef DEBUG_ECHOLN #undef DEBUG_ECHOPGM #undef DEBUG_ECHOLNPGM +#undef DEBUG_ECHOF +#undef DEBUG_ECHOLNF #undef DEBUG_ECHOPGM_P #undef DEBUG_ECHOLNPGM_P #undef DEBUG_ECHOPAIR_F @@ -54,7 +56,7 @@ #if DEBUG_OUT #include "debug_section.h" - #define DEBUG_SECTION(N,S,D) SectionLog N(PSTR(S),D) + #define DEBUG_SECTION(N,S,D) SectionLog N(F(S),D) #define DEBUG_ECHO_START SERIAL_ECHO_START #define DEBUG_ERROR_START SERIAL_ERROR_START @@ -65,6 +67,8 @@ #define DEBUG_ECHOLN SERIAL_ECHOLN #define DEBUG_ECHOPGM SERIAL_ECHOPGM #define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM + #define DEBUG_ECHOF SERIAL_ECHOF + #define DEBUG_ECHOLNF SERIAL_ECHOLNF #define DEBUG_ECHOPGM SERIAL_ECHOPGM #define DEBUG_ECHOPGM_P SERIAL_ECHOPGM_P #define DEBUG_ECHOPAIR_F SERIAL_ECHOPAIR_F @@ -94,6 +98,8 @@ #define DEBUG_ECHOLN(...) NOOP #define DEBUG_ECHOPGM(...) NOOP #define DEBUG_ECHOLNPGM(...) NOOP + #define DEBUG_ECHOF(...) NOOP + #define DEBUG_ECHOLNF(...) NOOP #define DEBUG_ECHOPGM_P(...) NOOP #define DEBUG_ECHOLNPGM_P(...) NOOP #define DEBUG_ECHOPAIR_F(...) NOOP diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h index ef1511e6f0..6e23d9e4ed 100644 --- a/Marlin/src/core/debug_section.h +++ b/Marlin/src/core/debug_section.h @@ -26,22 +26,22 @@ class SectionLog { public: - SectionLog(PGM_P const msg=nullptr, bool inbug=true) { - the_msg = msg; - if ((debug = inbug)) echo_msg(PSTR(">>>")); + SectionLog(FSTR_P const fmsg=nullptr, bool inbug=true) { + the_msg = fmsg; + if ((debug = inbug)) echo_msg(F(">>>")); } - ~SectionLog() { if (debug) echo_msg(PSTR("<<<")); } + ~SectionLog() { if (debug) echo_msg(F("<<<")); } private: - PGM_P the_msg; + FSTR_P the_msg; bool debug; - void echo_msg(PGM_P const pre) { - SERIAL_ECHOPGM_P(pre); + void echo_msg(FSTR_P const fpre) { + SERIAL_ECHOF(fpre); if (the_msg) { SERIAL_CHAR(' '); - SERIAL_ECHOPGM_P(the_msg); + SERIAL_ECHOF(the_msg); } SERIAL_CHAR(' '); print_pos(current_position); diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 8c9f4a8e4d..9cd862df70 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -69,23 +69,23 @@ PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR #endif -void serialprintPGM(PGM_P str) { +void serial_print_P(PGM_P str) { while (const char c = pgm_read_byte(str++)) SERIAL_CHAR(c); } -void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); } -void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); } +void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serial_print_P(echomagic); } +void serial_error_start() { static PGMSTR(errormagic, "Error:"); serial_print_P(errormagic); } void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } -void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post/*=nullptr*/) { - if (pre) serialprintPGM(pre); - serialprintPGM(onoff ? on : off); - if (post) serialprintPGM(post); +void serial_ternary(const bool onoff, FSTR_P const pre, FSTR_P const on, FSTR_P const off, FSTR_P const post/*=nullptr*/) { + if (pre) serial_print(pre); + serial_print(onoff ? on : off); + if (post) serial_print(post); } -void serialprint_onoff(const bool onoff) { serialprintPGM(onoff ? PSTR(STR_ON) : PSTR(STR_OFF)); } +void serialprint_onoff(const bool onoff) { serial_print(onoff ? F(STR_ON) : F(STR_OFF)); } void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); } -void serialprint_truefalse(const bool tf) { serialprintPGM(tf ? PSTR("true") : PSTR("false")); } +void serialprint_truefalse(const bool tf) { serial_print(tf ? F("true") : F("false")); } void print_bin(uint16_t val) { for (uint8_t i = 16; i--;) { @@ -94,10 +94,10 @@ void print_bin(uint16_t val) { } } -void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { - if (prefix) serialprintPGM(prefix); +void print_pos(LINEAR_AXIS_ARGS(const_float_t), FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) { + if (prefix) serial_print(prefix); SERIAL_ECHOPGM_P( LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k) ); - if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); + if (suffix) serial_print(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 05d80a4829..e058f1e5cd 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -167,13 +167,10 @@ inline void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); } #define AS_CHAR(C) serial_char_t(C) #define AS_DIGIT(C) AS_CHAR('0' + (C)) -// SERIAL_ECHO_F prints a floating point value with optional precision -inline void SERIAL_ECHO_F(EnsureDouble x, int digit=2) { SERIAL_IMPL.print(x, digit); } - template void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } -// SERIAL_PRINT works like SERIAL_ECHO but allow to specify the encoding base of the number printed +// SERIAL_PRINT works like SERIAL_ECHO but also takes the numeric base template void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); } @@ -184,8 +181,20 @@ void SERIAL_PRINTLN(T x, PrintBase y) { SERIAL_IMPL.println(x, y); } inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); } inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); } -// Print a single PROGMEM string to serial -void serialprintPGM(PGM_P str); +// Serial echo and error prefixes +#define SERIAL_ECHO_START() serial_echo_start() +#define SERIAL_ERROR_START() serial_error_start() + +// Serial end-of-line +#define SERIAL_EOL() SERIAL_CHAR('\n') + +// Print a single PROGMEM, PGM_P, or PSTR() string. +void serial_print_P(PGM_P str); +inline void serial_println_P(PGM_P str) { serial_print_P(str); SERIAL_EOL(); } + +// Print a single FSTR_P, F(), or FPSTR() string. +inline void serial_print(FSTR_P const fstr) { serial_print_P(FTOP(fstr)); } +inline void serial_println(FSTR_P const fstr) { serial_println_P(FTOP(fstr)); } // // SERIAL_ECHOPGM... macros are used to output string-value pairs. @@ -195,8 +204,8 @@ void serialprintPGM(PGM_P str); #define __SEP_N(N,V...) _SEP_##N(V) #define _SEP_N(N,V...) __SEP_N(N,V) #define _SEP_N_REF() _SEP_N -#define _SEP_1(s) serialprintPGM(PSTR(s)); -#define _SEP_2(s,v) serial_echopair_PGM(PSTR(s),v); +#define _SEP_1(s) serial_print(F(s)); +#define _SEP_2(s,v) serial_echopair(F(s),v); #define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOPGM(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0) @@ -204,8 +213,8 @@ void serialprintPGM(PGM_P str); #define __SELP_N(N,V...) _SELP_##N(V) #define _SELP_N(N,V...) __SELP_N(N,V) #define _SELP_N_REF() _SELP_N -#define _SELP_1(s) serialprintPGM(PSTR(s "\n")); -#define _SELP_2(s,v) serial_echopair_PGM(PSTR(s),v); SERIAL_EOL(); +#define _SELP_1(s) serial_print(F(s "\n")); +#define _SELP_2(s,v) serial_echolnpair(F(s),v); #define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOLNPGM(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0) @@ -213,8 +222,8 @@ void serialprintPGM(PGM_P str); #define __SEP_N_P(N,V...) _SEP_##N##_P(V) #define _SEP_N_P(N,V...) __SEP_N_P(N,V) #define _SEP_N_P_REF() _SEP_N_P -#define _SEP_1_P(p) serialprintPGM(p); -#define _SEP_2_P(p,v) serial_echopair_PGM(p,v); +#define _SEP_1_P(p) serial_print_P(p); +#define _SEP_2_P(p,v) serial_echopair_P(p,v); #define _SEP_3_P(p,v,V...) _SEP_2_P(p,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V); #define SERIAL_ECHOPGM_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0) @@ -222,11 +231,29 @@ void serialprintPGM(PGM_P str); #define __SELP_N_P(N,V...) _SELP_##N##_P(V) #define _SELP_N_P(N,V...) __SELP_N_P(N,V) #define _SELP_N_P_REF() _SELP_N_P -#define _SELP_1_P(p) { serialprintPGM(p); SERIAL_EOL(); } -#define _SELP_2_P(p,v) { serial_echopair_PGM(p,v); SERIAL_EOL(); } +#define _SELP_1_P(p) serial_println_P(p) +#define _SELP_2_P(p,v) serial_echolnpair_P(p,v) #define _SELP_3_P(p,v,V...) { _SEP_2_P(p,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); } #define SERIAL_ECHOLNPGM_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0) +// Print up to 20 pairs of values. Odd elements must be FSTR_P, F(), or FPSTR(). +#define __SEP_N_F(N,V...) _SEP_##N##_F(V) +#define _SEP_N_F(N,V...) __SEP_N_F(N,V) +#define _SEP_N_F_REF() _SEP_N_F +#define _SEP_1_F(p) serial_print(p); +#define _SEP_2_F(p,v) serial_echopair(p,v); +#define _SEP_3_F(p,v,V...) _SEP_2_F(p,v); DEFER2(_SEP_N_F_REF)()(TWO_ARGS(V),V); +#define SERIAL_ECHOF(V...) do{ EVAL(_SEP_N_F(TWO_ARGS(V),V)); }while(0) + +// Print up to 20 pairs of values followed by newline. Odd elements must be FSTR_P, F(), or FPSTR(). +#define __SELP_N_F(N,V...) _SELP_##N##_F(V) +#define _SELP_N_F(N,V...) __SELP_N_F(N,V) +#define _SELP_N_F_REF() _SELP_N_F +#define _SELP_1_F(p) serial_println(p) +#define _SELP_2_F(p,v) serial_echolnpair(p,v) +#define _SELP_3_F(p,v,V...) { _SEP_2_F(p,v); DEFER2(_SELP_N_F_REF)()(TWO_ARGS(V),V); } +#define SERIAL_ECHOLNF(V...) do{ EVAL(_SELP_N_F(TWO_ARGS(V),V)); }while(0) + #ifdef AllowDifferentTypeInList inline void SERIAL_ECHOLIST_IMPL() {} @@ -236,47 +263,49 @@ void serialprintPGM(PGM_P str); template void SERIAL_ECHOLIST_IMPL(T && t, Args && ... args) { SERIAL_IMPL.print(t); - serialprintPGM(PSTR(", ")); + serial_print(F(", ")); SERIAL_ECHOLIST_IMPL(args...); } template - void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) { - SERIAL_IMPL.print(str); + void SERIAL_ECHOLIST(FSTR_P const str, Args && ... args) { + SERIAL_IMPL.print(FTOP(str)); SERIAL_ECHOLIST_IMPL(args...); } #else // Optimization if the listed type are all the same (seems to be the case in the codebase so use that instead) template - void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) { - serialprintPGM(str); + void SERIAL_ECHOLIST(FSTR_P const fstr, Args && ... args) { + serial_print(fstr); typename Private::first_type_of::type values[] = { args... }; constexpr size_t argsSize = sizeof...(args); for (size_t i = 0; i < argsSize; i++) { - if (i) serialprintPGM(PSTR(", ")); + if (i) serial_print(F(", ")); SERIAL_IMPL.print(values[i]); } } #endif -#define SERIAL_ECHOPAIR_F_P(P,V...) do{ serialprintPGM(P); SERIAL_ECHO_F(V); }while(0) -#define SERIAL_ECHOLNPAIR_F_P(V...) do{ SERIAL_ECHOPAIR_F_P(V); SERIAL_EOL(); }while(0) +// SERIAL_ECHO_F prints a floating point value with optional precision +inline void SERIAL_ECHO_F(EnsureDouble x, int digit=2) { SERIAL_IMPL.print(x, digit); } -#define SERIAL_ECHOPAIR_F(S,V...) SERIAL_ECHOPAIR_F_P(PSTR(S),V) -#define SERIAL_ECHOLNPAIR_F(V...) do{ SERIAL_ECHOPAIR_F(V); SERIAL_EOL(); }while(0) +#define SERIAL_ECHOPAIR_F_P(P,V...) do{ serial_print_P(P); SERIAL_ECHO_F(V); }while(0) +#define SERIAL_ECHOLNPAIR_F_P(P,V...) do{ SERIAL_ECHOPAIR_F_P(P,V); SERIAL_EOL(); }while(0) -#define SERIAL_ECHO_START() serial_echo_start() -#define SERIAL_ERROR_START() serial_error_start() -#define SERIAL_EOL() SERIAL_CHAR('\n') +#define SERIAL_ECHOPAIR_F_F(S,V...) do{ serial_print(S); SERIAL_ECHO_F(V); }while(0) +#define SERIAL_ECHOLNPAIR_F_F(S,V...) do{ SERIAL_ECHOPAIR_F_F(S,V); SERIAL_EOL(); }while(0) -#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) -#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0) +#define SERIAL_ECHOPAIR_F(S,V...) SERIAL_ECHOPAIR_F_F(F(S),V) +#define SERIAL_ECHOLNPAIR_F(V...) do{ SERIAL_ECHOPAIR_F(V); SERIAL_EOL(); }while(0) -#define SERIAL_ECHO_SP(C) serial_spaces(C) +#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) +#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0) -#define SERIAL_ECHO_TERNARY(TF, PRE, ON, OFF, POST) serial_ternary(TF, PSTR(PRE), PSTR(ON), PSTR(OFF), PSTR(POST)) +#define SERIAL_ECHO_SP(C) serial_spaces(C) + +#define SERIAL_ECHO_TERNARY(TF, PRE, ON, OFF, POST) serial_ternary(TF, F(PRE), F(ON), F(OFF), F(POST)) #if SERIAL_FLOAT_PRECISION #define SERIAL_DECIMAL(V) SERIAL_PRINT(V, SERIAL_FLOAT_PRECISION) @@ -287,33 +316,42 @@ void serialprintPGM(PGM_P str); // // Functions for serial printing from PROGMEM. (Saves loads of SRAM.) // -inline void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); } - -inline void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -inline void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } -inline void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } +inline void serial_echopair_P(PGM_P const pstr, serial_char_t v) { serial_print_P(pstr); SERIAL_CHAR(v.c); } +inline void serial_echopair_P(PGM_P const pstr, float v) { serial_print_P(pstr); SERIAL_DECIMAL(v); } +inline void serial_echopair_P(PGM_P const pstr, double v) { serial_print_P(pstr); SERIAL_DECIMAL(v); } +//inline void serial_echopair_P(PGM_P const pstr, const char *v) { serial_print_P(pstr); SERIAL_ECHO(v); } +inline void serial_echopair_P(PGM_P const pstr, FSTR_P v) { serial_print_P(pstr); SERIAL_ECHOF(v); } // Default implementation for types without a specialization. Handles integers. template -void serial_echopair_PGM(PGM_P const s_P, T v) { serialprintPGM(s_P); SERIAL_ECHO(v); } +inline void serial_echopair_P(PGM_P const pstr, T v) { serial_print_P(pstr); SERIAL_ECHO(v); } -inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); } -inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); } +// Add a newline. +template +inline void serial_echolnpair_P(PGM_P const pstr, T v) { serial_echopair_P(pstr, v); SERIAL_EOL(); } + +// Catch-all for __FlashStringHelper * +template +inline void serial_echopair(FSTR_P const fstr, T v) { serial_echopair_P(FTOP(fstr), v); } + +// Add a newline to the serial output +template +inline void serial_echolnpair(FSTR_P const fstr, T v) { serial_echolnpair_P(FTOP(fstr), v); } void serial_echo_start(); void serial_error_start(); -void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=nullptr); +void serial_ternary(const bool onoff, FSTR_P const pre, FSTR_P const on, FSTR_P const off, FSTR_P const post=nullptr); void serialprint_onoff(const bool onoff); void serialprintln_onoff(const bool onoff); void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos(LINEAR_AXIS_ARGS(const_float_t), FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr); -inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { +inline void print_pos(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) { print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix); } -#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) -#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, PSTR(PREFIX), nullptr); }while(0) +#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, F(" " STRINGIFY(VAR) "="), F(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, F(PREFIX)); }while(0) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 8aeec89f02..b70e2fa9a9 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -92,9 +92,9 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM(" (Aligned With"); if (probe.offset_xy.y > 0) - SERIAL_ECHOPGM_P(ENABLED(IS_SCARA) ? PSTR("-Distal") : PSTR("-Back")); + SERIAL_ECHOF(F(TERN(IS_SCARA, "-Distal", "-Back"))); else if (probe.offset_xy.y < 0) - SERIAL_ECHOPGM_P(ENABLED(IS_SCARA) ? PSTR("-Proximal") : PSTR("-Front")); + SERIAL_ECHOF(F(TERN(IS_SCARA, "-Proximal", "-Front"))); else if (probe.offset_xy.x != 0) SERIAL_ECHOPGM("-Center"); @@ -102,7 +102,7 @@ void safe_delay(millis_t ms) { #endif - SERIAL_ECHOPGM_P(probe.offset.z < 0 ? PSTR("Below") : probe.offset.z > 0 ? PSTR("Above") : PSTR("Same Z as")); + SERIAL_ECHOF(probe.offset.z < 0 ? F("Below") : probe.offset.z > 0 ? F("Above") : F("Same Z as")); SERIAL_ECHOLNPGM(" Nozzle)"); #endif diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 7b2280fcde..964f1123fe 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -180,10 +180,8 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { SERIAL_EOL(); serial_echo_column_labels(eachsp - 2); } - else { - SERIAL_ECHOPGM(" for "); - SERIAL_ECHOPGM_P(csv ? PSTR("CSV:\n") : PSTR("LCD:\n")); - } + else + SERIAL_ECHOPGM(" for ", csv ? F("CSV:\n") : F("LCD:\n")); // Add XY probe offset from extruder because probe.probe_at_point() subtracts them when // moving to the XY position to be measured. This ensures better agreement between @@ -213,7 +211,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { // TODO: Display on Graphical LCD } else if (isnan(f)) - SERIAL_ECHOPGM_P(human ? PSTR(" . ") : PSTR("NAN")); + SERIAL_ECHOF(human ? F(" . ") : F("NAN")); else if (human || csv) { if (human && f >= 0.0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) SERIAL_ECHO_F(f, 3); // Positive: 5 digits, Negative: 6 digits diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index bed24f0525..f843011b5d 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -232,7 +232,7 @@ bool I2CPositionEncoder::passes_test(const bool report) { if (report) { if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. "); SERIAL_CHAR(axis_codes[encoderAxis]); - serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder ")); + serial_ternary(H == I2CPE_MAG_SIG_BAD, F(" axis "), F("magnetic strip "), F("encoder ")); switch (H) { case I2CPE_MAG_SIG_GOOD: case I2CPE_MAG_SIG_MID: diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index 2edcd7478a..b2899243b2 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -169,10 +169,9 @@ void MeatPack::handle_command(const MeatPack_Command c) { void MeatPack::report_state() { // NOTE: if any configuration vars are added below, the outgoing sync text for host plugin // should not contain the "PV' substring, as this is used to indicate protocol version - SERIAL_ECHOPGM("[MP] "); - SERIAL_ECHOPGM(MeatPack_ProtocolVersion " "); + SERIAL_ECHOPGM("[MP] " MeatPack_ProtocolVersion " "); serialprint_onoff(TEST(state, MPConfig_Bit_Active)); - SERIAL_ECHOPGM_P(TEST(state, MPConfig_Bit_NoSpaces) ? PSTR(" NSP\n") : PSTR(" ESP\n")); + SERIAL_ECHOF(TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n")); } /** diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index d54326116e..28f5caa3cb 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -486,7 +486,7 @@ void show_continue_prompt(const bool is_reload) { ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); SERIAL_ECHO_START(); - SERIAL_ECHOPGM_P(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); + SERIAL_ECHOF(is_reload ? F(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : F(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); } void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 68984fe756..05b204ae6b 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -69,11 +69,11 @@ void ProbeTempComp::print_offsets() { LOOP_L_N(s, TSI_COUNT) { celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { - SERIAL_ECHOPGM_P(s == TSI_BED ? PSTR("Bed") : + SERIAL_ECHOF(s == TSI_BED ? F("Bed") : #if ENABLED(USE_TEMP_EXT_COMPENSATION) - s == TSI_EXT ? PSTR("Extruder") : + s == TSI_EXT ? F("Extruder") : #endif - PSTR("Probe") + F("Probe") ); SERIAL_ECHOLNPGM( " temp: ", temp, diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 918e65bb22..8065e51555 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -317,7 +317,7 @@ class FilamentSensorBase { static uint8_t was_out; // = 0 if (out != TEST(was_out, s)) { TBI(was_out, s); - SERIAL_ECHOLNPGM_P(PSTR("Filament Sensor "), '0' + s, out ? PSTR(" OUT") : PSTR(" IN")); + SERIAL_ECHOLNF(F("Filament Sensor "), AS_DIGIT(s), out ? F(" OUT") : F(" IN")); } #endif } @@ -352,7 +352,7 @@ class FilamentSensorBase { if (ELAPSED(ms, t)) { t = millis() + 1000UL; LOOP_L_N(i, NUM_RUNOUT_SENSORS) - SERIAL_ECHOPGM_P(i ? PSTR(", ") : PSTR("Remaining mm: "), runout_mm_countdown[i]); + SERIAL_ECHOF(i ? F(", ") : F("Remaining mm: "), runout_mm_countdown[i]); SERIAL_EOL(); } #endif diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 97fedf13c5..6848d81003 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -561,7 +561,7 @@ }; template - static void print_vsense(TMC &st) { SERIAL_ECHOPGM_P(st.vsense() ? PSTR("1=.18") : PSTR("0=.325")); } + static void print_vsense(TMC &st) { SERIAL_ECHOF(st.vsense() ? F("1=.18") : F("0=.325")); } #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130) static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) { @@ -732,7 +732,7 @@ SERIAL_ECHO(st.cs()); SERIAL_ECHOPGM("/31"); break; - case TMC_VSENSE: SERIAL_ECHOPGM_P(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break; + case TMC_VSENSE: SERIAL_ECHOF(st.vsense() ? F("1=.165") : F("0=.310")); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; //case TMC_OTPW: serialprint_truefalse(st.otpw()); break; //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; @@ -1256,15 +1256,14 @@ static bool test_connection(TMC &st) { if (test_result > 0) SERIAL_ECHOPGM("Error: All "); - const char *stat; + FSTR_P stat; switch (test_result) { default: - case 0: stat = PSTR("OK"); break; - case 1: stat = PSTR("HIGH"); break; - case 2: stat = PSTR("LOW"); break; + case 0: stat = F("OK"); break; + case 1: stat = F("HIGH"); break; + case 2: stat = F("LOW"); break; } - SERIAL_ECHOPGM_P(stat); - SERIAL_EOL(); + SERIAL_ECHOLNF(stat); return test_result; } diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index cb634d973b..e45e18b7fb 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -116,7 +116,7 @@ void GcodeSuite::G35() { if (DEBUGGING(LEVELING)) { DEBUG_ECHOPGM("Probing point ", i + 1, " ("); - DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); + DEBUG_ECHOF(FPSTR(pgm_read_ptr(&tramming_point_name[i]))); DEBUG_CHAR(')'); DEBUG_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height); } diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index d76e08dee6..1240b14fd2 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -246,12 +246,12 @@ void GcodeSuite::M420_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR( TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) )); - SERIAL_ECHOPGM_P( - PSTR(" M420 S"), planner.leveling_active + SERIAL_ECHOF( + F(" M420 S"), planner.leveling_active #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) + , FPSTR(SP_Z_STR), LINEAR_UNIT(planner.z_fade_height) #endif - , PSTR(" ; Leveling ") + , F(" ; Leveling ") ); serialprintln_onoff(planner.leveling_active); } diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 923a27d7df..1299259b53 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -138,8 +138,8 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) SERIAL_ECHOPGM(" S", LINEAR_UNIT(toolchange_settings.swap_length)); SERIAL_ECHOPGM_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume), - SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), - SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); + SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime), + SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed)); SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed), " U", LINEAR_UNIT(toolchange_settings.unretract_speed), " F", toolchange_settings.fan_speed, diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index 57c049e194..e271dcd469 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -55,7 +55,7 @@ void GcodeSuite::M302() { // Report current state SERIAL_ECHO_START(); SERIAL_ECHOPGM("Cold extrudes are "); - SERIAL_ECHOPGM_P(thermalManager.allow_cold_extrude ? PSTR("en") : PSTR("dis")); + SERIAL_ECHOF(thermalManager.allow_cold_extrude ? F("en") : F("dis")); SERIAL_ECHOLNPGM("abled (min temp ", thermalManager.extrude_min_temp, "C)"); } } diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index a837d79533..d108070279 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -47,8 +47,8 @@ void GcodeSuite::M211_report(const bool forReplay/*=true*/) { report_echo_start(forReplay); const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(), l_soft_max = soft_endstop.max.asLogical(); - print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); - print_pos(l_soft_max, PSTR(STR_SOFT_MAX)); + print_pos(l_soft_min, F(STR_SOFT_MIN), F(" ")); + print_pos(l_soft_max, F(STR_SOFT_MAX)); } #endif // HAS_SOFTWARE_ENDSTOPS diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 149613ee15..c11acb4380 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -48,7 +48,7 @@ // S: Report the current power supply state and exit if (parser.seen('S')) { - SERIAL_ECHOPGM_P(powerManager.psu_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); + SERIAL_ECHOF(powerManager.psu_on ? F("PS:1\n") : F("PS:0\n")); return; } diff --git a/Marlin/src/gcode/feature/L6470/M122.cpp b/Marlin/src/gcode/feature/L6470/M122.cpp index 1e5b37e4b7..4a5629b049 100644 --- a/Marlin/src/gcode/feature/L6470/M122.cpp +++ b/Marlin/src/gcode/feature/L6470/M122.cpp @@ -47,10 +47,10 @@ inline void L6470_say_status(const L64XX_axis_t axis) { } #endif SERIAL_ECHOPGM("\n...OUTPUT: "); - SERIAL_ECHOPGM_P(sh.STATUS_AXIS & STATUS_HIZ ? PSTR("OFF") : PSTR("ON ")); + SERIAL_ECHOF(sh.STATUS_AXIS & STATUS_HIZ ? F("OFF") : F("ON ")); SERIAL_ECHOPGM(" BUSY: "); echo_yes_no((sh.STATUS_AXIS & STATUS_BUSY) == 0); SERIAL_ECHOPGM(" DIR: "); - SERIAL_ECHOPGM_P((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? PSTR("FORWARD") : PSTR("REVERSE")); + SERIAL_ECHOF((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? F("FORWARD") : F("REVERSE")); if (sh.STATUS_AXIS_LAYOUT == L6480_STATUS_LAYOUT) { SERIAL_ECHOPGM(" Last Command: "); if (sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD) SERIAL_ECHOPGM("VALID"); @@ -67,7 +67,7 @@ inline void L6470_say_status(const L64XX_axis_t axis) { SERIAL_ECHOPGM(" Last Command: "); if (!(sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD)) SERIAL_ECHOPGM("IN"); SERIAL_ECHOPGM("VALID "); - SERIAL_ECHOPGM_P(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? PSTR("COMPLETED ") : PSTR("Not PERFORMED")); + SERIAL_ECHOF(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? F("COMPLETED ") : F("Not PERFORMED")); SERIAL_ECHOPGM("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK "); } SERIAL_ECHOPGM(" OVERCURRENT:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_OCD) == 0); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 2ab13f5b5d..a74365e84d 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -107,7 +107,7 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps, " ADC_OUT: ", L6470_ADC_out); SERIAL_ECHOPGM(" Vs_compensation: "); - SERIAL_ECHOPGM_P((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? PSTR("ENABLED ") : PSTR("DISABLED")); + SERIAL_ECHOF((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? F("ENABLED ") : F("DISABLED")); SERIAL_ECHOLNPGM(" Compensation coefficient: ~", comp_coef * 0.01f); SERIAL_ECHOPGM("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD), diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 7c714dad25..9bf109559f 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -51,8 +51,8 @@ void GcodeSuite::M413() { #if PIN_EXISTS(POWER_LOSS) if (parser.seen_test('O')) recovery._outage(); #endif - if (parser.seen_test('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n")); - if (parser.seen_test('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n")); + if (parser.seen_test('E')) SERIAL_ECHOF(recovery.exists() ? F("PLR Exists\n") : F("No PLR\n")); + if (parser.seen_test('V')) SERIAL_ECHOF(recovery.valid() ? F("Valid\n") : F("Invalid\n")); #endif } diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 5cadd2d45e..e8e3205358 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -32,7 +32,7 @@ template void tmc_say_stealth_status(TMC &st) { st.printLabel(); SERIAL_ECHOPGM(" driver mode:\t"); - SERIAL_ECHOLNPGM_P(st.get_stealthChop() ? PSTR("stealthChop") : PSTR("spreadCycle")); + SERIAL_ECHOLNF(st.get_stealthChop() ? F("stealthChop") : F("spreadCycle")); } template void tmc_set_stealthChop(TMC &st, const bool enable) { diff --git a/Marlin/src/gcode/geometry/G17-G19.cpp b/Marlin/src/gcode/geometry/G17-G19.cpp index 0154598ccb..fbac7470ca 100644 --- a/Marlin/src/gcode/geometry/G17-G19.cpp +++ b/Marlin/src/gcode/geometry/G17-G19.cpp @@ -29,10 +29,10 @@ inline void report_workspace_plane() { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Workspace Plane "); - SERIAL_ECHOPGM_P( - gcode.workspace_plane == GcodeSuite::PLANE_YZ ? PSTR("YZ\n") - : gcode.workspace_plane == GcodeSuite::PLANE_ZX ? PSTR("ZX\n") - : PSTR("XY\n") + SERIAL_ECHOF( + gcode.workspace_plane == GcodeSuite::PLANE_YZ ? F("YZ\n") + : gcode.workspace_plane == GcodeSuite::PLANE_ZX ? F("ZX\n") + : F("XY\n") ); } diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index ad550765ec..83fda54836 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -351,8 +351,8 @@ public: static inline char temp_units_code() { return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'; } - static inline PGM_P temp_units_name() { - return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius"); + static inline FSTR_P temp_units_name() { + return input_temp_units == TEMPUNIT_K ? F("Kelvin") : input_temp_units == TEMPUNIT_F ? F("Fahrenheit") : F("Celsius"); } #if HAS_LCD_MENU && DISABLED(DISABLE_M503) diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index 20b3781ead..b1cfbb2511 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -39,7 +39,7 @@ void GcodeSuite::M149() { void GcodeSuite::M149_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, PSTR(STR_TEMPERATURE_UNITS)); SERIAL_ECHOPGM(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); - SERIAL_ECHOLNPGM_P(parser.temp_units_name()); + SERIAL_ECHOLNF(parser.temp_units_name()); } #endif // TEMPERATURE_UNITS_SUPPORT diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 1b572367f2..e7b3941928 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -306,7 +306,7 @@ void ChironTFT::PowerLossRecovery() { printer_state = AC_printer_resuming_from_power_outage; // Play tune to notify user we can recover. last_error = AC_error_powerloss; PlayTune(BEEPER_PIN, SOS, 1); - SERIAL_ECHOLNPGM_P(AC_msg_powerloss_recovery); + SERIAL_ECHOLNF(AC_msg_powerloss_recovery); } void ChironTFT::PrintComplete() { @@ -488,7 +488,7 @@ void ChironTFT::ProcessPanelRequest() { if (tpos != -1) { if (panel_command[tpos+1]== 'X' && panel_command[tpos+2]=='Y') { panel_type = AC_panel_standard; - SERIAL_ECHOLNPGM_P(AC_msg_old_panel_detected); + SERIAL_ECHOLNF(AC_msg_old_panel_detected); } } else { @@ -496,7 +496,7 @@ void ChironTFT::ProcessPanelRequest() { if (tpos != -1) { if (panel_command[tpos+1]== '0' && panel_command[tpos+2]==']') { panel_type = AC_panel_new; - SERIAL_ECHOLNPGM_P(AC_msg_new_panel_detected); + SERIAL_ECHOLNF(AC_msg_new_panel_detected); } } } @@ -825,7 +825,7 @@ void ChironTFT::PanelProcess(uint8_t req) { if (!isPrinting()) { injectCommands_P(PSTR("M501\nM420 S1")); selectedmeshpoint.x = selectedmeshpoint.y = 99; - SERIAL_ECHOLNPGM_P(AC_msg_mesh_changes_abandoned); + SERIAL_ECHOLNF(AC_msg_mesh_changes_abandoned); } } @@ -833,7 +833,7 @@ void ChironTFT::PanelProcess(uint8_t req) { if (!isPrinting()) { setAxisPosition_mm(1.0,Z); // Lift nozzle before any further movements are made injectCommands_P(PSTR("M500")); - SERIAL_ECHOLNPGM_P(AC_msg_mesh_changes_saved); + SERIAL_ECHOLNF(AC_msg_mesh_changes_saved); selectedmeshpoint.x = selectedmeshpoint.y = 99; } } diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index d59ebe5695..fbf8481c03 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -755,10 +755,10 @@ volatile bool Temperature::raw_temps_ready = false; SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); #if EITHER(PIDTEMPBED, PIDTEMPCHAMBER) - PGM_P const estring = GHV(PSTR("chamber"), PSTR("bed"), NUL_STR); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Kp ", tune_pid.Kp); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Ki ", tune_pid.Ki); - say_default_(); SERIAL_ECHOPGM_P(estring); SERIAL_ECHOLNPGM("Kd ", tune_pid.Kd); + FSTR_P const estring = GHV(F("chamber"), F("bed"), FPSTR(NUL_STR)); + say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Kp ", tune_pid.Kp); + say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Ki ", tune_pid.Ki); + say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Kd ", tune_pid.Kd); #else say_default_(); SERIAL_ECHOLNPGM("Kp ", tune_pid.Kp); say_default_(); SERIAL_ECHOLNPGM("Ki ", tune_pid.Ki); @@ -1737,21 +1737,21 @@ void Temperature::manage_heater() { SERIAL_ECHOPAIR_F_P(SP_B_STR, t.beta, 1); SERIAL_ECHOPAIR_F_P(SP_C_STR, t.sh_c_coeff, 9); SERIAL_ECHOPGM(" ; "); - SERIAL_ECHOPGM_P( - TERN_(TEMP_SENSOR_0_IS_CUSTOM, t_index == CTI_HOTEND_0 ? PSTR("HOTEND 0") :) - TERN_(TEMP_SENSOR_1_IS_CUSTOM, t_index == CTI_HOTEND_1 ? PSTR("HOTEND 1") :) - TERN_(TEMP_SENSOR_2_IS_CUSTOM, t_index == CTI_HOTEND_2 ? PSTR("HOTEND 2") :) - TERN_(TEMP_SENSOR_3_IS_CUSTOM, t_index == CTI_HOTEND_3 ? PSTR("HOTEND 3") :) - TERN_(TEMP_SENSOR_4_IS_CUSTOM, t_index == CTI_HOTEND_4 ? PSTR("HOTEND 4") :) - TERN_(TEMP_SENSOR_5_IS_CUSTOM, t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") :) - TERN_(TEMP_SENSOR_6_IS_CUSTOM, t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") :) - TERN_(TEMP_SENSOR_7_IS_CUSTOM, t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") :) - TERN_(TEMP_SENSOR_BED_IS_CUSTOM, t_index == CTI_BED ? PSTR("BED") :) - TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) - TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? PSTR("COOLER") :) - TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? PSTR("PROBE") :) - TERN_(TEMP_SENSOR_BOARD_IS_CUSTOM, t_index == CTI_BOARD ? PSTR("BOARD") :) - TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? PSTR("REDUNDANT") :) + SERIAL_ECHOF( + TERN_(TEMP_SENSOR_0_IS_CUSTOM, t_index == CTI_HOTEND_0 ? F("HOTEND 0") :) + TERN_(TEMP_SENSOR_1_IS_CUSTOM, t_index == CTI_HOTEND_1 ? F("HOTEND 1") :) + TERN_(TEMP_SENSOR_2_IS_CUSTOM, t_index == CTI_HOTEND_2 ? F("HOTEND 2") :) + TERN_(TEMP_SENSOR_3_IS_CUSTOM, t_index == CTI_HOTEND_3 ? F("HOTEND 3") :) + TERN_(TEMP_SENSOR_4_IS_CUSTOM, t_index == CTI_HOTEND_4 ? F("HOTEND 4") :) + TERN_(TEMP_SENSOR_5_IS_CUSTOM, t_index == CTI_HOTEND_5 ? F("HOTEND 5") :) + TERN_(TEMP_SENSOR_6_IS_CUSTOM, t_index == CTI_HOTEND_6 ? F("HOTEND 6") :) + TERN_(TEMP_SENSOR_7_IS_CUSTOM, t_index == CTI_HOTEND_7 ? F("HOTEND 7") :) + TERN_(TEMP_SENSOR_BED_IS_CUSTOM, t_index == CTI_BED ? F("BED") :) + TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? F("CHAMBER") :) + TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? F("COOLER") :) + TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? F("PROBE") :) + TERN_(TEMP_SENSOR_BOARD_IS_CUSTOM, t_index == CTI_BOARD ? F("BOARD") :) + TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? F("REDUNDANT") :) nullptr ); SERIAL_EOL(); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9f8aac634b..26a6d736eb 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -614,7 +614,7 @@ void announceOpen(const uint8_t doing, const char * const path) { PORT_REDIRECT(SerialMask::All); SERIAL_ECHO_START(); SERIAL_ECHOPGM("Now "); - SERIAL_ECHOPGM_P(doing == 1 ? PSTR("doing") : PSTR("fresh")); + SERIAL_ECHOF(doing == 1 ? F("doing") : F("fresh")); SERIAL_ECHOLNPGM(" file: ", path); } } @@ -1325,7 +1325,7 @@ void CardReader::fileHasFinished() { removeFile(recovery.filename); #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) SERIAL_ECHOPGM("Power-loss file delete"); - SERIAL_ECHOPGM_P(jobRecoverFileExists() ? PSTR(" failed.\n") : PSTR("d.\n")); + SERIAL_ECHOF(jobRecoverFileExists() ? F(" failed.\n") : F("d.\n")); #endif } } diff --git a/docs/Serial.md b/docs/Serial.md index ff8f84ef99..be3b23e87d 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -62,7 +62,7 @@ The following macros are defined (in `serial.h`) to output data to the serial po | `SERIAL_ECHOLNPGM` | Same as `SERIAL_ECHOPGM` | Do `SERIAL_ECHOPGM`, adding a newline | `SERIAL_ECHOPGM("Alice", 56);` | `alice56` | | `SERIAL_ECHOPGM_P` | Like `SERIAL_ECHOPGM` but takes PGM strings | Print a series of PGM strings and values alternately | `SERIAL_ECHOPGM_P(GET_TEXT(MSG_HELLO), 123);` | `Hello123` | | `SERIAL_ECHOLNPGM_P` | Same as `SERIAL_ECHOPGM_P` | Do `SERIAL_ECHOPGM_P`, adding a newline | `SERIAL_ECHOLNPGM_P(PSTR("Alice"), 78);` | `alice78\n` | -| `SERIAL_ECHOLIST` | String literal, values | Print a string literal and a list of values | `SERIAL_ECHOLIST("Key ", 1, 2, 3);` | `Key 1, 2, 3` | +| `SERIAL_ECHOLIST` | String literal, values | Print a string literal and a list of values | `SERIAL_ECHOLIST(F("Key "), 1, 2, 3);` | `Key 1, 2, 3` | | `SERIAL_ECHO_START` | None | Prefix an echo line | `SERIAL_ECHO_START();` | `echo:` | | `SERIAL_ECHO_MSG` | Same as `SERIAL_ECHOLN_PAIR` | Print a full echo line | `SERIAL_ECHO_MSG("Count is ", count);` | `echo:Count is 3` | | `SERIAL_ERROR_START`| None | Prefix an error line | `SERIAL_ERROR_START();` | `Error:` | From 7f1286a11f87065c4e666985e679cf9c77d668bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 17:05:11 -0500 Subject: [PATCH 0756/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20sta?= =?UTF-8?q?tus=20message?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 10 +-- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 38 +++++------ Marlin/src/feature/cancel_object.cpp | 2 +- Marlin/src/feature/hotend_idle.cpp | 2 +- Marlin/src/feature/mmu/mmu2.cpp | 24 +++---- Marlin/src/feature/pause.cpp | 4 +- Marlin/src/feature/stepper_driver_safety.cpp | 2 +- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/gcode/bedlevel/G26.cpp | 14 ++-- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 4 +- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/gcode/calibrate/G33.cpp | 6 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 8 +-- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 2 +- Marlin/src/gcode/calibrate/M48.cpp | 6 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 2 +- Marlin/src/gcode/control/M80_M81.cpp | 4 +- Marlin/src/gcode/geometry/M206_M428.cpp | 4 +- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/gcode/motion/G4.cpp | 2 +- Marlin/src/gcode/queue.cpp | 2 +- Marlin/src/gcode/temp/M140_M190.cpp | 2 +- Marlin/src/gcode/temp/M141_M191.cpp | 2 +- Marlin/src/gcode/temp/M143_M193.cpp | 2 +- Marlin/src/gcode/temp/M303.cpp | 2 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 12 ++-- Marlin/src/lcd/e3v2/creality/dwin.h | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 58 ++++++++--------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 6 +- Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 65 ++++++++++--------- Marlin/src/lcd/marlinui.h | 23 +++---- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_mixer.cpp | 2 +- Marlin/src/lcd/menu/menu_mmu2.cpp | 8 +-- Marlin/src/module/endstops.cpp | 4 +- Marlin/src/module/probe.cpp | 12 ++-- Marlin/src/module/settings.cpp | 6 +- Marlin/src/module/temperature.cpp | 14 ++-- Marlin/src/module/tool_change.cpp | 4 +- Marlin/src/sd/cardreader.cpp | 2 +- .../sd/usb_flashdrive/Sd2Card_FlashDrive.cpp | 10 +-- 44 files changed, 194 insertions(+), 196 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 6309f9f0d5..8a15c45f83 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -474,7 +474,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { if (!IS_SD_PRINTING() && !READ(HOME_PIN)) { // HOME_PIN goes LOW when pressed if (ELAPSED(ms, next_home_key_ms)) { next_home_key_ms = ms + HOME_DEBOUNCE_DELAY; - LCD_MESSAGEPGM(MSG_AUTO_HOME); + LCD_MESSAGE(MSG_AUTO_HOME); queue.inject_P(G28_STR); } } @@ -499,8 +499,8 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { } \ }while(0) - #define CHECK_CUSTOM_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, NOOP) - #define CHECK_BETTER_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, if (strlen(BUTTON##N##_DESC)) LCD_MESSAGEPGM_P(PSTR(BUTTON##N##_DESC))) + #define CHECK_CUSTOM_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, NOOP) + #define CHECK_BETTER_USER_BUTTON(N) _CHECK_CUSTOM_USER_BUTTON(N, if (strlen(BUTTON##N##_DESC)) LCD_MESSAGE_F(BUTTON##N##_DESC)) #if HAS_BETTER_USER_BUTTON(1) CHECK_BETTER_USER_BUTTON(1); @@ -935,7 +935,7 @@ void stop() { if (!IsStopped()) { SERIAL_ERROR_MSG(STR_ERR_STOPPED); - LCD_MESSAGEPGM(MSG_STOPPED); + LCD_MESSAGE(MSG_STOPPED); safe_delay(350); // allow enough time for messages to get out before stopping marlin_state = MF_STOPPED; } @@ -1551,7 +1551,7 @@ void setup() { HMI_Init(); HMI_SetLanguageCache(); HMI_StartFrame(true); - DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG)); + DWIN_StatusChanged(GET_TEXT_F(WELCOME_MSG)); #endif #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 9b85b5b972..051cb6a4d6 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -736,7 +736,7 @@ void unified_bed_leveling::shift_mesh_height() { const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); #if HAS_LCD_MENU if (ui.button_pressed()) { @@ -789,12 +789,12 @@ void unified_bed_leveling::shift_mesh_height() { #endif // HAS_BED_PROBE -void set_message_with_feedback(PGM_P const msg_P) { +void set_message_with_feedback(FSTR_P const fstr) { #if HAS_LCD_MENU - ui.set_status_P(msg_P); + ui.set_status(fstr); ui.quick_feedback(); #else - UNUSED(msg_P); + UNUSED(fstr); #endif } @@ -850,7 +850,7 @@ void set_message_with_feedback(PGM_P const msg_P) { planner.synchronize(); SERIAL_ECHOPGM("Place shim under nozzle"); - LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); + LCD_MESSAGE(MSG_UBL_BC_INSERT); ui.return_to_status(); echo_and_take_a_measurement(); @@ -859,7 +859,7 @@ void set_message_with_feedback(PGM_P const msg_P) { planner.synchronize(); SERIAL_ECHOPGM("Remove shim"); - LCD_MESSAGEPGM(MSG_UBL_BC_REMOVE); + LCD_MESSAGE(MSG_UBL_BC_REMOVE); echo_and_take_a_measurement(); const float z2 = measure_point_with_encoder(); @@ -905,7 +905,7 @@ void set_message_with_feedback(PGM_P const msg_P) { if (!position_is_reachable(ppos)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) - LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT); + LCD_MESSAGE(MSG_UBL_MOVING_TO_NEXT); do_blocking_move_to(ppos); do_z_clearance(z_clearance); @@ -917,11 +917,11 @@ void set_message_with_feedback(PGM_P const msg_P) { if (parser.seen_test('B')) { SERIAL_ECHOPGM("Place Shim & Measure"); - LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); + LCD_MESSAGE(MSG_UBL_BC_INSERT); } else { SERIAL_ECHOPGM("Measure"); - LCD_MESSAGEPGM(MSG_UBL_BC_INSERT2); + LCD_MESSAGE(MSG_UBL_BC_INSERT2); } const float z_step = 0.01f; // 0.01mm per encoder tick, occasionally step @@ -974,7 +974,7 @@ void set_message_with_feedback(PGM_P const msg_P) { save_ubl_active_state_and_disable(); - LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); + LCD_MESSAGE(MSG_UBL_FINE_TUNE_MESH); ui.capture(); // Take over control of the LCD encoder do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance @@ -1039,7 +1039,7 @@ void set_message_with_feedback(PGM_P const msg_P) { if (_click_and_hold([]{ ui.return_to_status(); do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - set_message_with_feedback(GET_TEXT(MSG_EDITING_STOPPED)); + set_message_with_feedback(GET_TEXT_F(MSG_EDITING_STOPPED)); })) break; // TODO: Disable leveling here so the Z value becomes the 'native' Z value. @@ -1060,7 +1060,7 @@ void set_message_with_feedback(PGM_P const msg_P) { do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); + LCD_MESSAGE(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); if (lcd_map_control) @@ -1077,7 +1077,7 @@ void set_message_with_feedback(PGM_P const msg_P) { bool unified_bed_leveling::G29_parse_parameters() { bool err_flag = false; - set_message_with_feedback(GET_TEXT(MSG_UBL_DOING_G29)); + set_message_with_feedback(GET_TEXT_F(MSG_UBL_DOING_G29)); param.C_constant = 0; param.R_repetition = 0; @@ -1200,7 +1200,7 @@ void unified_bed_leveling::save_ubl_active_state_and_disable() { ubl_state_recursion_chk++; if (ubl_state_recursion_chk != 1) { SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); - set_message_with_feedback(GET_TEXT(MSG_UBL_SAVE_ERROR)); + set_message_with_feedback(GET_TEXT_F(MSG_UBL_SAVE_ERROR)); return; } #endif @@ -1213,7 +1213,7 @@ void unified_bed_leveling::restore_ubl_active_state_and_leave() { #if ENABLED(UBL_DEVEL_DEBUGGING) if (--ubl_state_recursion_chk) { SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); - set_message_with_feedback(GET_TEXT(MSG_UBL_RESTORE_ERROR)); + set_message_with_feedback(GET_TEXT_F(MSG_UBL_RESTORE_ERROR)); return; } #endif @@ -1438,7 +1438,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (do_3_pt_leveling) { SERIAL_ECHOLNPGM("Tilting mesh (1/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 1/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[0], PROBE_PT_RAISE, param.V_verbosity); if (isnan(measured_z)) @@ -1457,7 +1457,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (!abort_flag) { SERIAL_ECHOLNPGM("Tilting mesh (2/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 2/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[1], PROBE_PT_RAISE, param.V_verbosity); #ifdef VALIDATE_MESH_TILT @@ -1477,7 +1477,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (!abort_flag) { SERIAL_ECHOLNPGM("Tilting mesh (3/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH))); measured_z = probe.probe_at_point(points[2], PROBE_PT_LAST_STOW, param.V_verbosity); #ifdef VALIDATE_MESH_TILT @@ -1518,7 +1518,7 @@ void unified_bed_leveling::smart_fill_mesh() { if (!abort_flag) { SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index 9d50bfc0d4..bffd2bb720 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -46,7 +46,7 @@ void CancelObject::set_active_object(const int8_t obj) { #if BOTH(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) if (active_object >= 0) - ui.status_printf_P(0, PSTR(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); + ui.status_printf(0, F(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); else ui.reset_status(); #endif diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp index b962743ed0..4b137f42da 100644 --- a/Marlin/src/feature/hotend_idle.cpp +++ b/Marlin/src/feature/hotend_idle.cpp @@ -77,7 +77,7 @@ void HotendIdleProtection::check() { void HotendIdleProtection::timed_out() { next_protect_ms = 0; SERIAL_ECHOLNPGM("Hotend Idle Timeout"); - LCD_MESSAGEPGM(MSG_HOTEND_IDLE_TIMEOUT); + LCD_MESSAGE(MSG_HOTEND_IDLE_TIMEOUT); HOTEND_LOOP() { if ((HOTEND_IDLE_NOZZLE_TARGET) < thermalManager.degTargetHotend(e)) thermalManager.setTargetHotend(HOTEND_IDLE_NOZZLE_TARGET, e); diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index d9a4c07d57..7362530e35 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -451,7 +451,7 @@ void MMU2::check_version() { } static void mmu2_not_responding() { - LCD_MESSAGEPGM(MSG_MMU2_NOT_RESPONDING); + LCD_MESSAGE(MSG_MMU2_NOT_RESPONDING); BUZZ(100, 659); BUZZ(200, 698); BUZZ(100, 659); @@ -487,7 +487,7 @@ static void mmu2_not_responding() { if (index != extruder) { stepper.disable_extruder(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); command(MMU_CMD_T0 + index); manage_response(true, true); @@ -573,7 +573,7 @@ static void mmu2_not_responding() { command(MMU_CMD_U0); manage_response(true, true); } - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); mmu_loading_flag = true; command(MMU_CMD_T0 + index); manage_response(true, true); @@ -671,7 +671,7 @@ static void mmu2_not_responding() { if (index != extruder) { stepper.disable_extruder(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); command(MMU_CMD_T0 + index); manage_response(true, true); command(MMU_CMD_C0); @@ -808,14 +808,14 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (turn_off_nozzle && resume_hotend_temp) { thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); - LCD_MESSAGEPGM(MSG_HEATING); + LCD_MESSAGE(MSG_HEATING); BUZZ(200, 40); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); } if (move_axes && all_axes_homed()) { - LCD_MESSAGEPGM(MSG_MMU2_RESUMING); + LCD_MESSAGE(MSG_MMU2_RESUMING); BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); // Move XY to starting position, then Z @@ -826,7 +826,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { } else { BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); - LCD_MESSAGEPGM(MSG_MMU2_RESUMING); + LCD_MESSAGE(MSG_MMU2_RESUMING); } } } @@ -908,7 +908,7 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } @@ -944,11 +944,11 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } - LCD_MESSAGEPGM(MSG_MMU2_EJECTING_FILAMENT); + LCD_MESSAGE(MSG_MMU2_EJECTING_FILAMENT); stepper.enable_extruder(); current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; @@ -958,7 +958,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { manage_response(false, false); if (recover) { - LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); + LCD_MESSAGE(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); @@ -993,7 +993,7 @@ bool MMU2::unload() { if (thermalManager.tooColdToExtrude(active_extruder)) { BUZZ(200, 404); - LCD_ALERTMESSAGEPGM(MSG_HOTEND_TOO_COLD); + LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 28f5caa3cb..75255d87ac 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -538,7 +538,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status_P(GET_TEXT(MSG_REHEATING))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATING)); // Re-enable the heaters if they timed out HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e); @@ -556,7 +556,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status_P(GET_TEXT(MSG_REHEATDONE))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATDONE)); IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); diff --git a/Marlin/src/feature/stepper_driver_safety.cpp b/Marlin/src/feature/stepper_driver_safety.cpp index c7da5d2ff7..8ba0968cd2 100644 --- a/Marlin/src/feature/stepper_driver_safety.cpp +++ b/Marlin/src/feature/stepper_driver_safety.cpp @@ -32,7 +32,7 @@ void stepper_driver_backward_error(PGM_P str) { SERIAL_ERROR_START(); SERIAL_ECHOPGM_P(str); SERIAL_ECHOLNPGM(" driver is backward!"); - ui.status_printf_P(2, PSTR(S_FMT S_FMT), str, GET_TEXT(MSG_DRIVER_BACKWARD)); + ui.status_printf(2, F(S_FMT S_FMT), str, GET_TEXT(MSG_DRIVER_BACKWARD)); } void stepper_driver_backward_check() { diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 6848d81003..c11d2e5f6d 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -1341,7 +1341,7 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { #endif } - if (axis_connection) LCD_MESSAGEPGM(MSG_ERROR_TMC); + if (axis_connection) LCD_MESSAGE(MSG_ERROR_TMC); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index ba14e6f0b4..e111bcd8aa 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -163,7 +163,7 @@ float g26_random_deviation = 0.0; */ bool user_canceled() { if (!ui.button_pressed()) return false; // Return if the button isn't pressed - ui.set_status_P(GET_TEXT(MSG_G26_CANCELED), 99); + ui.set_status(GET_TEXT_F(MSG_G26_CANCELED), 99); TERN_(HAS_LCD_MENU, ui.quick_feedback()); ui.wait_for_release(); return true; @@ -323,7 +323,7 @@ typedef struct { if (bed_temp > 25) { #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99); + ui.set_status(GET_TEXT_F(MSG_G26_HEATING_BED), 99); ui.quick_feedback(); TERN_(HAS_LCD_MENU, ui.capture()); #endif @@ -342,7 +342,7 @@ typedef struct { // Start heating the active nozzle #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_HEATING_NOZZLE), 99); + ui.set_status(GET_TEXT_F(MSG_G26_HEATING_NOZZLE), 99); ui.quick_feedback(); #endif thermalManager.setTargetHotend(hotend_temp, active_extruder); @@ -372,7 +372,7 @@ typedef struct { if (prime_flag == -1) { // The user wants to control how much filament gets purged ui.capture(); - ui.set_status_P(GET_TEXT(MSG_G26_MANUAL_PRIME), 99); + ui.set_status(GET_TEXT_F(MSG_G26_MANUAL_PRIME), 99); ui.chirp(); destination = current_position; @@ -399,7 +399,7 @@ typedef struct { ui.wait_for_release(); - ui.set_status_P(GET_TEXT(MSG_G26_PRIME_DONE), 99); + ui.set_status(GET_TEXT_F(MSG_G26_PRIME_DONE), 99); ui.quick_feedback(); ui.release(); } @@ -407,7 +407,7 @@ typedef struct { #endif { #if HAS_WIRED_LCD - ui.set_status_P(GET_TEXT(MSG_G26_FIXED_LENGTH), 99); + ui.set_status(GET_TEXT_F(MSG_G26_FIXED_LENGTH), 99); ui.quick_feedback(); #endif destination = current_position; @@ -854,7 +854,7 @@ void GcodeSuite::G26() { } while (--g26_repeats && location.valid()); LEAVE: - ui.set_status_P(GET_TEXT(MSG_G26_LEAVING), -1); + ui.set_status(GET_TEXT_F(MSG_G26_LEAVING), -1); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, ExtUI::G26_FINISH)); g26.retract_filament(destination); diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 03b0450c6b..07aefe8aed 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -636,7 +636,7 @@ G29_TYPE GcodeSuite::G29() { if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue; if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); @@ -681,7 +681,7 @@ G29_TYPE GcodeSuite::G29() { LOOP_L_N(i, 3) { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); // Retain the last probe position abl.probePos = xy_pos_t(points[i]); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 930953ea14..eec89f73ac 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -152,7 +152,7 @@ void GcodeSuite::G29() { // After recording the last point, activate home and activate mbl_probe_index = -1; SERIAL_ECHOLNPGM("Mesh probing done."); - TERN_(HAS_STATUS_MESSAGE, ui.set_status(GET_TEXT(MSG_MESH_DONE))); + TERN_(HAS_STATUS_MESSAGE, LCD_MESSAGE(MSG_MESH_DONE)); BUZZ(100, 659); BUZZ(100, 698); @@ -214,7 +214,7 @@ void GcodeSuite::G29() { if (state == MeshNext) { SERIAL_ECHOLNPGM("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); - if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); + if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); } report_current_position(); diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index dc93ba3d2f..cd6a3a760d 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -156,7 +156,7 @@ homeaxis(Z_AXIS); } else { - LCD_MESSAGEPGM(MSG_ZPROBE_OUT); + LCD_MESSAGE(MSG_ZPROBE_OUT); SERIAL_ECHO_MSG(STR_ZPROBE_OUT_SER); } } diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 8867c168d2..39494cde24 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -477,11 +477,11 @@ void GcodeSuite::G33() { SERIAL_ECHOLNPGM("G33 Auto Calibrate"); // Report settings - PGM_P const checkingac = PSTR("Checking... AC"); - SERIAL_ECHOPGM_P(checkingac); + FSTR_P const checkingac = F("Checking... AC"); + SERIAL_ECHOF(checkingac); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); - ui.set_status_P(checkingac); + ui.set_status(checkingac); print_calibration_settings(_endstop_results, _angle_results); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 63d839c847..25855e6a4e 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -31,7 +31,7 @@ #include "../../module/stepper.h" #include "../../module/planner.h" #include "../../module/probe.h" -#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM +#include "../../lcd/marlinui.h" // for LCD_MESSAGE #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" @@ -229,7 +229,7 @@ void GcodeSuite::G34() { 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"); - LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED); + LCD_MESSAGE(MSG_LCD_PROBING_FAILED); err_break = true; break; } @@ -328,7 +328,7 @@ void GcodeSuite::G34() { auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) { if (v1 < v2 * 0.7f) { SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); - LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY); + LCD_MESSAGE(MSG_DECREASING_ACCURACY); return true; } return false; @@ -411,7 +411,7 @@ void GcodeSuite::G34() { if (success_break) { SERIAL_ECHOLNPGM("Target accuracy achieved."); - LCD_MESSAGEPGM(MSG_ACCURACY_ACHIEVED); + LCD_MESSAGE(MSG_ACCURACY_ACHIEVED); break; } diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index a6c4ed0287..2408f44ac4 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -351,7 +351,7 @@ void GcodeSuite::M192() { } const celsius_t target_temp = parser.value_celsius(); - ui.set_status_P(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT(MSG_PROBE_HEATING) : GET_TEXT(MSG_PROBE_COOLING)); + ui.set_status(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT_F(MSG_PROBE_HEATING) : GET_TEXT_F(MSG_PROBE_COOLING)); thermalManager.wait_for_probe(target_temp, no_wait_for_cooling); } diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 9db90c76ac..913ffe30d4 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M48() { }; if (!probe.can_reach(test_position)) { - ui.set_status_P(GET_TEXT(MSG_M48_OUT_OF_BOUNDS), 99); + ui.set_status(GET_TEXT_F(MSG_M48_OUT_OF_BOUNDS), 99); SERIAL_ECHOLNPGM("? (X,Y) out of bounds."); return; } @@ -144,7 +144,7 @@ void GcodeSuite::M48() { LOOP_L_N(n, n_samples) { #if HAS_STATUS_MESSAGE // 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)); + ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); #endif // When there are "legs" of movement move around the point before probing @@ -260,7 +260,7 @@ void GcodeSuite::M48() { #if HAS_STATUS_MESSAGE // Display M48 results in the status bar char sigma_str[8]; - ui.status_printf_P(0, PSTR(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); + ui.status_printf(0, F(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); #endif } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 82df20ac45..4683786f1f 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -136,7 +136,7 @@ void GcodeSuite::M17() { } } else { - LCD_MESSAGEPGM(MSG_NO_MOVE); + LCD_MESSAGE(MSG_NO_MOVE); stepper.enable_all_steppers(); } } diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index c11acb4380..2a1b3b34b9 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -25,7 +25,7 @@ #include "../../module/temperature.h" #include "../../module/planner.h" // for planner.finish_and_disable #include "../../module/printcounter.h" // for print_job_timer.stop -#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM_P +#include "../../lcd/marlinui.h" // for LCD_MESSAGE_F #include "../../inc/MarlinConfig.h" @@ -95,5 +95,5 @@ void GcodeSuite::M81() { powerManager.power_off_soon(); #endif - LCD_MESSAGEPGM_P(PSTR(MACHINE_NAME " " STR_OFF ".")); + LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 416b3f7634..8dba238d09 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -91,7 +91,7 @@ void GcodeSuite::M428() { diff[i] = -current_position[i]; if (!WITHIN(diff[i], -20, 20)) { SERIAL_ERROR_MSG(STR_ERR_M428_TOO_FAR); - LCD_ALERTMESSAGEPGM_P(PSTR("Err: Too far!")); + LCD_ALERTMESSAGE_F("Err: Too far!"); BUZZ(200, 40); return; } @@ -99,7 +99,7 @@ void GcodeSuite::M428() { LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]); report_current_position(); - LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED); + LCD_MESSAGE(MSG_HOME_OFFSETS_APPLIED); BUZZ(100, 659); BUZZ(100, 698); } diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 241f11c813..32df8dd9c3 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -59,7 +59,7 @@ void GcodeSuite::M0_M1() { if (parser.string_arg) ui.set_status(parser.string_arg, true); else { - LCD_MESSAGEPGM(MSG_USERWAIT); + LCD_MESSAGE(MSG_USERWAIT); #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 ui.reset_progress_bar_timeout(); #endif diff --git a/Marlin/src/gcode/motion/G4.cpp b/Marlin/src/gcode/motion/G4.cpp index 724ed7f1ca..df3f5b010e 100644 --- a/Marlin/src/gcode/motion/G4.cpp +++ b/Marlin/src/gcode/motion/G4.cpp @@ -38,7 +38,7 @@ void GcodeSuite::G4() { SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); #endif - if (!ui.has_status()) LCD_MESSAGEPGM(MSG_DWELL); + if (!ui.has_status()) LCD_MESSAGE(MSG_DWELL); dwell(dwell_ms); } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 063f76bd85..5424809699 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -513,7 +513,7 @@ void GCodeQueue::get_serial_commands() { TERN_(BEZIER_CURVE_SUPPORT, case 5:) PORT_REDIRECT(SERIAL_PORTMASK(p)); // Reply to the serial port that sent the command SERIAL_ECHOLNPGM(STR_ERR_STOPPED); - LCD_MESSAGEPGM(MSG_STOPPED); + LCD_MESSAGE(MSG_STOPPED); break; } } diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 857e11dde5..edc15b9cba 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -83,7 +83,7 @@ void GcodeSuite::M140_M190(const bool isM190) { thermalManager.setTargetBed(temp); - ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); + ui.set_status(thermalManager.isHeatingBed() ? GET_TEXT_F(MSG_BED_HEATING) : GET_TEXT_F(MSG_BED_COOLING)); // with PRINTJOB_TIMER_AUTOSTART, M190 can start the timer, and M140 can stop it TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(isM190, !isM190)); diff --git a/Marlin/src/gcode/temp/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp index ed7637c92a..81a078318a 100644 --- a/Marlin/src/gcode/temp/M141_M191.cpp +++ b/Marlin/src/gcode/temp/M141_M191.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M191() { const bool is_heating = thermalManager.isHeatingChamber(); if (is_heating || !no_wait_for_cooling) { - ui.set_status_P(is_heating ? GET_TEXT(MSG_CHAMBER_HEATING) : GET_TEXT(MSG_CHAMBER_COOLING)); + ui.set_status(is_heating ? GET_TEXT_F(MSG_CHAMBER_HEATING) : GET_TEXT_F(MSG_CHAMBER_COOLING)); thermalManager.wait_for_chamber(false); } } diff --git a/Marlin/src/gcode/temp/M143_M193.cpp b/Marlin/src/gcode/temp/M143_M193.cpp index aef4350e60..e4b29bee5f 100644 --- a/Marlin/src/gcode/temp/M143_M193.cpp +++ b/Marlin/src/gcode/temp/M143_M193.cpp @@ -58,7 +58,7 @@ void GcodeSuite::M193() { cooler.enable(); thermalManager.setTargetCooler(parser.value_celsius()); if (thermalManager.isLaserCooling()) { - ui.set_status_P(GET_TEXT(MSG_LASER_COOLING)); + LCD_MESSAGE(MSG_LASER_COOLING); thermalManager.wait_for_cooler(true); } } diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 0d0ce478ee..f823aefbed 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -85,7 +85,7 @@ void GcodeSuite::M303() { KEEPALIVE_STATE(NOT_BUSY); #endif - LCD_MESSAGEPGM(MSG_PID_AUTOTUNE); + LCD_MESSAGE(MSG_PID_AUTOTUNE); thermalManager.PID_autotune(temp, hid, c, u); ui.reset_status(); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 5b1d36fdae..d5abe977e5 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -4287,16 +4287,16 @@ void DWIN_CompletedLeveling() { if (checkkey == Leveling) Goto_MainMenu(); } -void DWIN_StatusChanged(const char *text) { +void DWIN_StatusChanged(const char * const cstr/*=nullptr*/) { DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 24); - const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(text) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 3, F(text)); + const int8_t x = _MAX(0U, DWIN_WIDTH - strlen(cstr) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Blue, x, STATUS_Y + 3, cstr); DWIN_UpdateLCD(); } -void DWIN_StatusChanged_P(PGM_P const pstr) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); +void DWIN_StatusChanged(FSTR_P const fstr) { + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); DWIN_StatusChanged(str); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index d4afe46a7d..d9ac0aa5fa 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -244,8 +244,8 @@ void HMI_Init(); void DWIN_Update(); void EachMomentUpdate(); void DWIN_HandleScreen(); -void DWIN_StatusChanged(const char *text); -void DWIN_StatusChanged_P(PGM_P const pstr); +void DWIN_StatusChanged(const char * const cstr=nullptr); +void DWIN_StatusChanged(FSTR_P const fstr); inline void DWIN_StartHoming() { HMI_flag.home_flag = true; } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 285c23cd2b..85d4400150 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -713,7 +713,7 @@ void Draw_Main_Menu() { void Goto_Main_Menu() { checkkey = MainMenu; - DWIN_StatusChanged(nullptr); + DWIN_StatusChanged(); Draw_Main_Menu(); } @@ -1756,20 +1756,20 @@ void DWIN_Startup() { HMI_SetLanguage(); } -void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text) { +void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char * const text/*=nullptr*/) { DWIN_Draw_Rectangle(1, bgcolor, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); if (text) DWINUI::Draw_CenteredString(color, STATUS_Y + 2, text); DWIN_UpdateLCD(); } // Update Status line -void DWIN_StatusChanged(const char *text) { - DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, text); +void DWIN_StatusChanged(const char * const cstr/*=nullptr*/) { + DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, cstr); } -void DWIN_StatusChanged_P(PGM_P const pstr) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); +void DWIN_StatusChanged(FSTR_P const fstr) { + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); DWIN_StatusChanged(str); } @@ -1804,7 +1804,7 @@ void DWIN_Progress_Update() { #if HAS_FILAMENT_SENSOR // Filament Runout process - void DWIN_FilamentRunout(const uint8_t extruder) { ui.set_status_P(GET_TEXT(MSG_RUNOUT_SENSOR)); } + void DWIN_FilamentRunout(const uint8_t extruder) { LCD_MESSAGE(MSG_RUNOUT_SENSOR); } #endif void DWIN_SetColorDefaults() { @@ -1889,7 +1889,7 @@ void DWIN_Redraw_screen() { case PAUSE_MESSAGE_OPTION: DWIN_Popup_FilamentPurge(); break; case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); break; case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT), ICON_Continue_E); break; - case PAUSE_MESSAGE_HEATING: ui.set_status_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); break; + case PAUSE_MESSAGE_HEATING: LCD_MESSAGE(MSG_FILAMENT_CHANGE_HEATING); break; case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; default: break; } @@ -2181,7 +2181,7 @@ void SetMoveZto0() { ); gcode.process_subcommands_now(cmd); planner.synchronize(); - ui.set_status_P(PSTR("Now adjust Z Offset")); + LCD_MESSAGE_F("Now adjust Z Offset"); HMI_AudioFeedback(true); } @@ -2238,7 +2238,7 @@ void Goto_LockScreen() { DWIN_LockScreen(true); } void SetProbeOffsetY() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } void SetProbeOffsetZ() { SetPFloatOnClick(-10, 10, 2); } void ProbeTest() { - ui.set_status_P(GET_TEXT(MSG_M48_TEST)); + LCD_MESSAGE(MSG_M48_TEST); queue.inject(F("G28O\nM48 P10")); } #endif @@ -2295,7 +2295,7 @@ void DWIN_ApplyColor() { DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); Draw_Status_Area(false); Draw_SelectColors_Menu(); - ui.set_status_P(PSTR("Colors applied")); + LCD_MESSAGE_F("Colors applied"); } void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } @@ -2323,18 +2323,18 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } } void ParkHead(){ - ui.set_status_P(GET_TEXT(MSG_FILAMENT_PARK_ENABLED)); + LCD_MESSAGE(MSG_FILAMENT_PARK_ENABLED); queue.inject(F("G28O\nG27")); } #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) void UnloadFilament(){ - ui.set_status_P(GET_TEXT(MSG_FILAMENTUNLOAD)); + LCD_MESSAGE(MSG_FILAMENTUNLOAD); queue.inject(F("M702 Z20")); } void LoadFilament(){ - ui.set_status_P(GET_TEXT(MSG_FILAMENTLOAD)); + LCD_MESSAGE(MSG_FILAMENTLOAD); queue.inject(F("M701 Z20")); } #endif @@ -2359,23 +2359,23 @@ void LevBed(uint8_t point) { switch (point) { case 0: - ui.set_status_P(GET_TEXT(MSG_LEVBED_FL)); + LCD_MESSAGE(MSG_LEVBED_FL); xpos = ypos = margin; break; case 1: - ui.set_status_P(GET_TEXT(MSG_LEVBED_FR)); + LCD_MESSAGE(MSG_LEVBED_FR); xpos = X_BED_SIZE - margin; ypos = margin; break; case 2: - ui.set_status_P(GET_TEXT(MSG_LEVBED_BR)); + LCD_MESSAGE(MSG_LEVBED_BR); xpos = X_BED_SIZE - margin; ypos = Y_BED_SIZE - margin; break; case 3: - ui.set_status_P(GET_TEXT(MSG_LEVBED_BL)); + LCD_MESSAGE(MSG_LEVBED_BL); xpos = margin; ypos = Y_BED_SIZE - margin; break; case 4: - ui.set_status_P(GET_TEXT(MSG_LEVBED_C)); + LCD_MESSAGE(MSG_LEVBED_C); xpos = X_BED_SIZE / 2; ypos = Y_BED_SIZE / 2; break; } @@ -2390,7 +2390,7 @@ void LevBed(uint8_t point) { dtostrf(ypos, 1, 1, str_2), dtostrf(zval, 1, 2, str_3) ); - ui.set_status_P(cmd); + ui.set_status(cmd); #else planner.synchronize(); sprintf_P(cmd, PSTR(fmt), xpos, ypos); @@ -2407,7 +2407,7 @@ void LevBedC () { LevBed(4); } #if ENABLED(MESH_BED_LEVELING) void ManualMeshStart(){ - ui.set_status_P(GET_TEXT(MSG_UBL_BUILD_MESH_MENU)); + LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU); gcode.process_subcommands_now(F("G28 XYO\nG28 Z\nM211 S0\nG29S1")); planner.synchronize(); #ifdef MANUAL_PROBE_START_Z @@ -2432,7 +2432,7 @@ void LevBedC () { LevBed(4); } } void ManualMeshSave(){ - ui.set_status_P(GET_TEXT(MSG_UBL_STORAGE_MESH_MENU)); + LCD_MESSAGE(MSG_UBL_STORAGE_MESH_MENU); queue.inject(F("M211 S1\nM500")); } @@ -3089,11 +3089,11 @@ void HMI_SetPFloat() { // Menu Creation and Drawing functions ====================================================== -void SetMenuTitle(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { +void SetMenuTitle(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* fstr) { if (HMI_IsChinese() && (cn.w != 0)) CurrentMenu->MenuTitle.SetFrame(cn.x, cn.y, cn.w, cn.h); else - CurrentMenu->MenuTitle.SetCaption(text); + CurrentMenu->MenuTitle.SetCaption(fstr); } void Draw_Prepare_Menu() { @@ -3231,7 +3231,7 @@ void Draw_Move_Menu() { #endif } CurrentMenu->draw(); - if (!all_axes_trusted()) ui.set_status_P(PSTR("WARNING: position is unknow")); + if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: position is unknown"); } #if HAS_HOME_OFFSET @@ -3437,11 +3437,11 @@ void Draw_Motion_Menu() { #if HAS_PREHEAT - void Draw_Preheat_Menu(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* text) { + void Draw_Preheat_Menu(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* fstr) { checkkey = Menu; if (CurrentMenu != PreheatMenu) { CurrentMenu = PreheatMenu; - SetMenuTitle(cn, en, text); + SetMenuTitle(cn, en, fstr); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); #if HAS_HOTEND @@ -3645,7 +3645,7 @@ void Draw_Steps_Menu() { ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } CurrentMenu->draw(); - if (!axis_is_trusted(Z_AXIS)) ui.set_status_P(PSTR("WARNING: Z position is unknow, move Z to home")); + if (!axis_is_trusted(Z_AXIS)) LCD_MESSAGE_F("WARNING: Z position unknown, move Z to home"); } #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index f71d54b482..0908417117 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -179,9 +179,9 @@ void EachMomentUpdate(); void update_variable(); void DWIN_HandleScreen(); void DWIN_Update(); -void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text); -void DWIN_StatusChanged(const char * const text); -void DWIN_StatusChanged_P(PGM_P const text); +void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text=nullptr); +void DWIN_StatusChanged(const char * const cstr=nullptr); +void DWIN_StatusChanged(FSTR_P const fstr); void DWIN_StartHoming(); void DWIN_CompletedHoming(); #if HAS_MESH diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp index 6efc96f21b..d874db79ca 100644 --- a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp @@ -66,7 +66,7 @@ void MeshViewerClass::Draw() { } } char str_1[6], str_2[6] = ""; - ui.status_printf_P(0, PSTR("Mesh minZ: %s, maxZ: %s"), + ui.status_printf(0, F("Mesh minZ: %s, maxZ: %s"), dtostrf((float)minz / 100, 1, 2, str_1), dtostrf((float)maxz / 100, 1, 2, str_2) ); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index f0d0156151..96b0f2a086 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -2018,7 +2018,7 @@ void get_wifi_commands() { TERN_(ARC_SUPPORT, case 2 ... 3:) TERN_(BEZIER_CURVE_SUPPORT, case 5:) SERIAL_ECHOLNPGM(STR_ERR_STOPPED); - LCD_MESSAGEPGM(MSG_STOPPED); + LCD_MESSAGE(MSG_STOPPED); break; } } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index c8384fce31..66e2556b20 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -665,7 +665,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { init(); - status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); + status_printf(1, F(S_FMT ": " S_FMT), lcd_error, lcd_component); TERN_(HAS_LCD_MENU, return_to_status()); // RED ALERT. RED ALERT. @@ -1393,76 +1393,77 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if SERVICE_INTERVAL_3 > 0 static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); #endif - PGM_P msg; + FSTR_P msg; if (printingIsPaused()) - msg = GET_TEXT(MSG_PRINT_PAUSED); + msg = GET_TEXT_F(MSG_PRINT_PAUSED); #if ENABLED(SDSUPPORT) else if (IS_SD_PRINTING()) return set_status(card.longest_filename(), true); #endif else if (print_job_timer.isRunning()) - msg = GET_TEXT(MSG_PRINTING); + msg = GET_TEXT_F(MSG_PRINTING); #if SERVICE_INTERVAL_1 > 0 - else if (print_job_timer.needsService(1)) msg = service1; + else if (print_job_timer.needsService(1)) msg = FPSTR(service1); #endif #if SERVICE_INTERVAL_2 > 0 - else if (print_job_timer.needsService(2)) msg = service2; + else if (print_job_timer.needsService(2)) msg = FPSTR(service2); #endif #if SERVICE_INTERVAL_3 > 0 - else if (print_job_timer.needsService(3)) msg = service3; + else if (print_job_timer.needsService(3)) msg = FPSTR(service3); #endif else if (!no_welcome) - msg = GET_TEXT(WELCOME_MSG); + msg = GET_TEXT_F(WELCOME_MSG); else return; - set_status_P(msg, -1); + set_status(msg, -1); } - void MarlinUI::set_status_P(PGM_P const message, int8_t level) { + void MarlinUI::set_status(FSTR_P const fstr, int8_t level) { + PGM_P const pstr = FTOP(fstr); if (level < 0) level = alert_level = 0; if (level < alert_level) return; alert_level = level; - TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(message)); + TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(pstr)); // Since the message is encoded in UTF8 it must // only be cut on a character boundary. // Get a pointer to the null terminator - PGM_P pend = message + strlen_P(message); + PGM_P pend = pstr + strlen_P(pstr); // If length of supplied UTF8 string is greater than // the buffer size, start cutting whole UTF8 chars - while ((pend - message) > MAX_MESSAGE_LENGTH) { + while ((pend - pstr) > MAX_MESSAGE_LENGTH) { --pend; while (!START_OF_UTF8_CHAR(pgm_read_byte(pend))) --pend; }; // At this point, we have the proper cut point. Use it - uint8_t maxLen = pend - message; - strncpy_P(status_message, message, maxLen); + uint8_t maxLen = pend - pstr; + strncpy_P(status_message, pstr, maxLen); status_message[maxLen] = '\0'; finish_status(level > 0); } - void MarlinUI::set_alert_status_P(PGM_P const message) { - set_status_P(message, 1); + void MarlinUI::set_alert_status(FSTR_P const fstr) { + set_status(fstr, 1); TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); TERN_(HAS_LCD_MENU, return_to_status()); } #include - void MarlinUI::status_printf_P(const uint8_t level, PGM_P const fmt, ...) { + void MarlinUI::status_printf(const uint8_t level, FSTR_P const fmt, ...) { if (level < alert_level) return; alert_level = level; va_list args; - va_start(args, fmt); - vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, fmt, args); + va_start(args, FTOP(fmt)); + vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, FTOP(fmt), args); va_end(args); finish_status(level > 0); } @@ -1536,7 +1537,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif IF_DISABLED(SDSUPPORT, print_job_timer.stop()); TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); - LCD_MESSAGEPGM(MSG_PRINT_ABORTED); + LCD_MESSAGE(MSG_PRINT_ABORTED); TERN_(HAS_LCD_MENU, return_to_status()); } @@ -1548,7 +1549,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif void MarlinUI::flow_fault() { - LCD_ALERTMESSAGEPGM(MSG_FLOWMETER_FAULT); + LCD_ALERTMESSAGE(MSG_FLOWMETER_FAULT); TERN_(HAS_BUZZER, buzz(1000, 440)); TERN_(HAS_LCD_MENU, return_to_status()); } @@ -1566,7 +1567,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); - LCD_MESSAGEPGM(MSG_PRINT_PAUSED); + LCD_MESSAGE(MSG_PRINT_PAUSED); #if ENABLED(PARK_HEAD_ON_PAUSE) pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress @@ -1637,14 +1638,14 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; // // Send the status line as a host notification // - void MarlinUI::set_status(const char * const message, const bool) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify(message), UNUSED(message)); + void MarlinUI::set_status(const char * const cstr, const bool) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify(cstr), UNUSED(cstr)); } - void MarlinUI::set_status_P(PGM_P message, const int8_t) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); + void MarlinUI::set_status(FSTR_P const fstr, const int8_t) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(FTOP(fstr)), UNUSED(fstr)); } - void MarlinUI::status_printf_P(const uint8_t, PGM_P const message, ...) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(message), UNUSED(message)); + void MarlinUI::status_printf(const uint8_t, FSTR_P const fstr, ...) { + TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(FPSTR(fstr)), UNUSED(fstr)); } #endif // !HAS_DISPLAY && !HAS_STATUS_MESSAGE @@ -1670,7 +1671,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; quick_feedback(); goto_screen(MEDIA_MENU_GATEWAY); #else - LCD_MESSAGEPGM(MSG_MEDIA_INSERTED); + LCD_MESSAGE(MSG_MEDIA_INSERTED); #endif } } @@ -1679,7 +1680,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if ENABLED(EXTENSIBLE_UI) ExtUI::onMediaRemoved(); #elif PIN_EXISTS(SD_DETECT) - LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); + LCD_MESSAGE(MSG_MEDIA_REMOVED); #if HAS_LCD_MENU if (!defer_return_to_status) return_to_status(); #endif @@ -1802,7 +1803,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; ); }); #else - set_status_P(eeprom_err(msgid)); + set_status(FPSTR(eeprom_err(msgid))); #endif } diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 02d5bf06bd..bc8442c576 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -342,21 +342,19 @@ public: static bool has_status(); static void reset_status(const bool no_welcome=false); - static void set_status(const char * const message, const bool persist=false); - static void set_status_P(PGM_P const message, const int8_t level=0); - static void status_printf_P(const uint8_t level, PGM_P const fmt, ...); - static void set_alert_status_P(PGM_P const message); + static void set_alert_status(FSTR_P const fstr); static inline void reset_alert_level() { alert_level = 0; } #else static constexpr bool has_status() { return false; } static inline void reset_status(const bool=false) {} - static void set_status(const char *message, const bool=false); - static void set_status_P(PGM_P message, const int8_t=0); - static void status_printf_P(const uint8_t, PGM_P message, ...); - static inline void set_alert_status_P(PGM_P const) {} + static inline void set_alert_status(FSTR_P const) {} static inline void reset_alert_level() {} #endif + static void set_status(const char * const cstr, const bool persist=false); + static void set_status(FSTR_P const fstr, const int8_t level=0); + static void status_printf(const uint8_t level, FSTR_P const fmt, ...); + #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); #else @@ -740,8 +738,7 @@ private: extern MarlinUI ui; -#define LCD_MESSAGEPGM_P(x) ui.set_status_P(x) -#define LCD_ALERTMESSAGEPGM_P(x) ui.set_alert_status_P(x) - -#define LCD_MESSAGEPGM(x) LCD_MESSAGEPGM_P(GET_TEXT(x)) -#define LCD_ALERTMESSAGEPGM(x) LCD_ALERTMESSAGEPGM_P(GET_TEXT(x)) +#define LCD_MESSAGE_F(S) ui.set_status(F(S)) +#define LCD_MESSAGE(M) ui.set_status(GET_TEXT_F(M)) +#define LCD_ALERTMESSAGE_F(S) ui.set_alert_status(F(S)) +#define LCD_ALERTMESSAGE(M) ui.set_alert_status(GET_TEXT_F(M)) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 9d424feb75..8b688ab2ab 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -630,7 +630,7 @@ void menu_advanced_settings() { didset = settings.set_sd_update_status(new_state); ui.completion_feedback(didset); ui.return_to_status(); - if (new_state) LCD_MESSAGEPGM(MSG_RESET_PRINTER); else ui.reset_status(); + if (new_state) LCD_MESSAGE(MSG_RESET_PRINTER); else ui.reset_status(); }); #endif diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index d07b89c7c0..694fd54813 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -253,7 +253,7 @@ void menu_mixer() { MSG_BUTTON_RESET, MSG_BUTTON_CANCEL, []{ mixer.reset_vtools(); - LCD_MESSAGEPGM(MSG_VTOOLS_RESET); + LCD_MESSAGE(MSG_VTOOLS_RESET); ui.return_to_status(); }, nullptr, diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index 425a8ca751..99e5c06245 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -36,14 +36,14 @@ inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) { ui.reset_status(); ui.return_to_status(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(tool + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(tool + 1)); if (mmu2.load_filament_to_nozzle(tool)) ui.reset_status(); ui.return_to_status(); } void _mmu2_load_filament(uint8_t index) { ui.return_to_status(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_LOADING_FILAMENT), int(index + 1)); mmu2.load_filament(index); ui.reset_status(); } @@ -74,14 +74,14 @@ void menu_mmu2_load_to_nozzle() { void _mmu2_eject_filament(uint8_t index) { ui.reset_status(); ui.return_to_status(); - ui.status_printf_P(0, GET_TEXT(MSG_MMU2_EJECTING_FILAMENT), int(index + 1)); + ui.status_printf(0, GET_TEXT_F(MSG_MMU2_EJECTING_FILAMENT), int(index + 1)); if (mmu2.eject_filament(index, true)) ui.reset_status(); } void action_mmu2_unload_filament() { ui.reset_status(); ui.return_to_status(); - LCD_MESSAGEPGM(MSG_MMU2_UNLOADING_FILAMENT); + LCD_MESSAGE(MSG_MMU2_UNLOADING_FILAMENT); idle(); if (mmu2.unload()) ui.reset_status(); } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index d29fd3ecb3..b5f270ee63 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -460,8 +460,8 @@ void Endstops::event_handler() { SERIAL_EOL(); TERN_(HAS_STATUS_MESSAGE, - ui.status_printf_P(0, - PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), + ui.status_printf(0, + F(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), GET_TEXT(MSG_LCD_ENDSTOPS), LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP ) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 638bb6be81..5accbc8edd 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -137,7 +137,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #if ENABLED(TOUCH_MI_MANUAL_DEPLOY) const screenFunc_t prev_screen = ui.currentScreen; - LCD_MESSAGEPGM(MSG_MANUAL_DEPLOY_TOUCHMI); + LCD_MESSAGE(MSG_MANUAL_DEPLOY_TOUCHMI); ui.return_to_status(); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR)); @@ -290,10 +290,10 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { BUZZ(100, 659); BUZZ(100, 698); - PGM_P const ds_str = deploy ? GET_TEXT(MSG_MANUAL_DEPLOY) : GET_TEXT(MSG_MANUAL_STOW); + FSTR_P const ds_str = deploy ? GET_TEXT_F(MSG_MANUAL_DEPLOY) : GET_TEXT_F(MSG_MANUAL_STOW); ui.return_to_status(); // To display the new status message - ui.set_status_P(ds_str, 99); - SERIAL_ECHOLNPGM_P(ds_str); + ui.set_status(ds_str, 99); + SERIAL_ECHOLNF(ds_str); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); @@ -439,7 +439,7 @@ bool Probe::set_deployed(const bool deploy) { if (PROBE_TRIGGERED() == deploy) { // Unchanged after deploy/stow action? if (IsRunning()) { SERIAL_ERROR_MSG("Z-Probe failed"); - LCD_ALERTMESSAGEPGM_P(PSTR("Err: ZPROBE")); + LCD_ALERTMESSAGE_F("Err: ZPROBE"); } stop(); return true; @@ -793,7 +793,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai if (isnan(measured_z)) { stow(); - LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED); + LCD_MESSAGE(MSG_LCD_PROBING_FAILED); #if DISABLED(G29_RETRY_AND_RECOVER) SERIAL_ERROR_MSG(STR_ERR_PROBING_FAILED); #endif diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a4b8bb19e6..4f15dceba8 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1471,7 +1471,7 @@ void MarlinSettings::postprocess() { store_mesh(ubl.storage_slot); #endif - if (!eeprom_error) LCD_MESSAGEPGM(MSG_SETTINGS_STORED); + if (!eeprom_error) LCD_MESSAGE(MSG_SETTINGS_STORED); TERN_(EXTENSIBLE_UI, ExtUI::onConfigurationStoreWritten(!eeprom_error)); @@ -1497,7 +1497,7 @@ void MarlinSettings::postprocess() { stored_ver[1] = '\0'; } DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); - TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status(GET_TEXT(MSG_ERR_EEPROM_VERSION))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_ERR_EEPROM_VERSION)); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); eeprom_error = true; @@ -2362,7 +2362,7 @@ void MarlinSettings::postprocess() { else if (working_crc != stored_crc) { eeprom_error = true; DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); - TERN_(DWIN_CREALITY_LCD_ENHANCED, ui.set_status(GET_TEXT(MSG_ERR_EEPROM_CRC))); + TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_ERR_EEPROM_CRC)); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } else if (!validating) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fbf8481c03..40778ef312 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -635,7 +635,7 @@ volatile bool Temperature::raw_temps_ready = false; // PID Tuning loop wait_for_heatup = true; // Can be interrupted with M108 - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT), "Wait for heat up...")); + TERN_(HAS_STATUS_MESSAGE, ui.set_status(F("Wait for heat up..."))); while (wait_for_heatup) { const millis_t ms = millis(); @@ -696,7 +696,7 @@ volatile bool Temperature::raw_temps_ready = false; } } SHV((bias + d) >> 1); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); + TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); cycles++; minT = target; } @@ -3603,11 +3603,11 @@ void Temperature::isr() { #if HAS_HOTEND && HAS_STATUS_MESSAGE void Temperature::set_heating_message(const uint8_t e) { const bool heating = isHeatingHotend(e); - ui.status_printf_P(0, + ui.status_printf(0, #if HAS_MULTI_HOTEND - PSTR("E%c " S_FMT), '1' + e + F("E%c " S_FMT), '1' + e #else - PSTR("E1 " S_FMT) + F("E1 " S_FMT) #endif , heating ? GET_TEXT(MSG_HEATING) : GET_TEXT(MSG_COOLING) ); @@ -3744,7 +3744,7 @@ void Temperature::isr() { void Temperature::wait_for_hotend_heating(const uint8_t target_extruder) { if (isHeatingHotend(target_extruder)) { SERIAL_ECHOLNPGM("Wait for hotend heating..."); - LCD_MESSAGEPGM(MSG_HEATING); + LCD_MESSAGE(MSG_HEATING); wait_for_hotend(target_extruder); ui.reset_status(); } @@ -3874,7 +3874,7 @@ void Temperature::isr() { void Temperature::wait_for_bed_heating() { if (isHeatingBed()) { SERIAL_ECHOLNPGM("Wait for bed heating..."); - LCD_MESSAGEPGM(MSG_BED_HEATING); + LCD_MESSAGE(MSG_BED_HEATING); wait_for_bed(); ui.reset_status(); } diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index b695c9408c..7ac13e55cf 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -490,12 +490,12 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #endif if (check_tool_sensor_stats(0)) { - ui.set_status_P("TC error"); + LCD_MESSAGE_F("TC error"); switching_toolhead_lock(false); while (check_tool_sensor_stats(0)) { /* nada */ } switching_toolhead_lock(true); } - ui.set_status_P("TC Success"); + LCD_MESSAGE_F("TC Success"); #endif } diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 26a6d736eb..6b8d2338c1 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -457,7 +457,7 @@ void CardReader::mount() { cdroot(); #if ENABLED(USB_FLASH_DRIVE_SUPPORT) || PIN_EXISTS(SD_DETECT) else if (marlin_state != MF_INITIALIZING) - ui.set_status_P(GET_TEXT(MSG_SD_INIT_FAIL), -1); + ui.set_status(GET_TEXT_F(MSG_SD_INIT_FAIL), -1); #endif ui.refresh(); diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index 5991a9fb83..05671167c8 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -126,7 +126,7 @@ bool DiskIODriver_USBFlash::usbStartup() { SERIAL_ECHOPGM("Starting USB host..."); if (!UHS_START) { SERIAL_ECHOLNPGM(" failed."); - LCD_MESSAGEPGM(MSG_MEDIA_USB_FAILED); + LCD_MESSAGE(MSG_MEDIA_USB_FAILED); return false; } @@ -221,7 +221,7 @@ void DiskIODriver_USBFlash::idle() { #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Waiting for media"); #endif - LCD_MESSAGEPGM(MSG_MEDIA_WAITING); + LCD_MESSAGE(MSG_MEDIA_WAITING); GOTO_STATE_AFTER_DELAY(state, 2000); } break; @@ -236,7 +236,7 @@ void DiskIODriver_USBFlash::idle() { SERIAL_ECHOLNPGM("USB device removed"); #endif if (state != MEDIA_READY) - LCD_MESSAGEPGM(MSG_MEDIA_USB_REMOVED); + LCD_MESSAGE(MSG_MEDIA_USB_REMOVED); GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } @@ -245,12 +245,12 @@ void DiskIODriver_USBFlash::idle() { #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Media removed"); #endif - LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); + LCD_MESSAGE(MSG_MEDIA_REMOVED); GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } else if (task_state == UHS_STATE(ERROR)) { - LCD_MESSAGEPGM(MSG_MEDIA_READ_ERROR); + LCD_MESSAGE(MSG_MEDIA_READ_ERROR); GOTO_STATE_AFTER_DELAY(MEDIA_ERROR, 0); } } From 008bf1bcaef181cd1b74638692e2465bb9e07a4d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Sep 2021 11:55:08 -0500 Subject: [PATCH 0757/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20Hos?= =?UTF-8?q?t=20Actions=20strings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/host_actions.cpp | 64 ++++++++++---------- Marlin/src/feature/host_actions.h | 18 +++--- Marlin/src/feature/mmu/mmu2.cpp | 2 +- Marlin/src/feature/pause.cpp | 16 ++--- Marlin/src/feature/runout.cpp | 4 +- Marlin/src/gcode/config/M43.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 6 +- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/gcode/sd/M1001.cpp | 2 +- Marlin/src/gcode/sd/M24_M25.cpp | 4 +- Marlin/src/lcd/marlinui.cpp | 22 +++---- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/module/probe.cpp | 4 +- 13 files changed, 74 insertions(+), 74 deletions(-) diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 62e60320f7..9f5a1481f1 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -37,33 +37,33 @@ #include "runout.h" #endif -void host_action(PGM_P const pstr, const bool eol) { +void host_action(FSTR_P const fstr, const bool eol) { PORT_REDIRECT(SerialMask::All); SERIAL_ECHOPGM("//action:"); - SERIAL_ECHOPGM_P(pstr); + SERIAL_ECHOF(fstr); if (eol) SERIAL_EOL(); } #ifdef ACTION_ON_KILL - void host_action_kill() { host_action(PSTR(ACTION_ON_KILL)); } + void host_action_kill() { host_action(F(ACTION_ON_KILL)); } #endif #ifdef ACTION_ON_PAUSE - void host_action_pause(const bool eol/*=true*/) { host_action(PSTR(ACTION_ON_PAUSE), eol); } + void host_action_pause(const bool eol/*=true*/) { host_action(F(ACTION_ON_PAUSE), eol); } #endif #ifdef ACTION_ON_PAUSED - void host_action_paused(const bool eol/*=true*/) { host_action(PSTR(ACTION_ON_PAUSED), eol); } + void host_action_paused(const bool eol/*=true*/) { host_action(F(ACTION_ON_PAUSED), eol); } #endif #ifdef ACTION_ON_RESUME - void host_action_resume() { host_action(PSTR(ACTION_ON_RESUME)); } + void host_action_resume() { host_action(F(ACTION_ON_RESUME)); } #endif #ifdef ACTION_ON_RESUMED - void host_action_resumed() { host_action(PSTR(ACTION_ON_RESUMED)); } + void host_action_resumed() { host_action(F(ACTION_ON_RESUMED)); } #endif #ifdef ACTION_ON_CANCEL - void host_action_cancel() { host_action(PSTR(ACTION_ON_CANCEL)); } + void host_action_cancel() { host_action(F(ACTION_ON_CANCEL)); } #endif #ifdef ACTION_ON_START - void host_action_start() { host_action(PSTR(ACTION_ON_START)); } + void host_action_start() { host_action(F(ACTION_ON_START)); } #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -77,60 +77,60 @@ void host_action(PGM_P const pstr, const bool eol) { PromptReason host_prompt_reason = PROMPT_NOT_DEFINED; - void host_action_notify(const char * const message) { + void host_action_notify(const char * const cstr) { PORT_REDIRECT(SerialMask::All); - host_action(PSTR("notification "), false); - SERIAL_ECHOLN(message); + host_action(F("notification "), false); + SERIAL_ECHOLN(cstr); } - void host_action_notify_P(PGM_P const message) { + void host_action_notify(FSTR_P const fstr) { PORT_REDIRECT(SerialMask::All); - host_action(PSTR("notification "), false); - SERIAL_ECHOLNPGM_P(message); + host_action(F("notification "), false); + SERIAL_ECHOLNF(fstr); } - void host_action_prompt(PGM_P const ptype, const bool eol=true) { + void host_action_prompt(FSTR_P const ptype, const bool eol=true) { PORT_REDIRECT(SerialMask::All); - host_action(PSTR("prompt_"), false); - SERIAL_ECHOPGM_P(ptype); + host_action(F("prompt_"), false); + SERIAL_ECHOF(ptype); if (eol) SERIAL_EOL(); } - void host_action_prompt_plus(PGM_P const ptype, PGM_P const pstr, const char extra_char='\0') { + void host_action_prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char='\0') { host_action_prompt(ptype, false); PORT_REDIRECT(SerialMask::All); SERIAL_CHAR(' '); - SERIAL_ECHOPGM_P(pstr); + SERIAL_ECHOF(fstr); if (extra_char != '\0') SERIAL_CHAR(extra_char); SERIAL_EOL(); } - void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char/*='\0'*/) { + void host_action_prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char/*='\0'*/) { host_action_prompt_end(); host_prompt_reason = reason; - host_action_prompt_plus(PSTR("begin"), pstr, extra_char); + host_action_prompt_plus(F("begin"), fstr, extra_char); } - void host_action_prompt_button(PGM_P const pstr) { host_action_prompt_plus(PSTR("button"), pstr); } - void host_action_prompt_end() { host_action_prompt(PSTR("end")); } - void host_action_prompt_show() { host_action_prompt(PSTR("show")); } + void host_action_prompt_button(FSTR_P const fstr) { host_action_prompt_plus(F("button"), fstr); } + void host_action_prompt_end() { host_action_prompt(F("end")); } + void host_action_prompt_show() { host_action_prompt(F("show")); } - void _host_prompt_show(PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { + void _host_prompt_show(FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { if (btn1) host_action_prompt_button(btn1); if (btn2) host_action_prompt_button(btn2); host_action_prompt_show(); } - void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { - host_action_prompt_begin(reason, pstr); + void host_prompt_do(const PromptReason reason, FSTR_P const fstr, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { + host_action_prompt_begin(reason, fstr); _host_prompt_show(btn1, btn2); } - void host_prompt_do(const PromptReason reason, PGM_P const pstr, const char extra_char, PGM_P const btn1/*=nullptr*/, PGM_P const btn2/*=nullptr*/) { - host_action_prompt_begin(reason, pstr, extra_char); + void host_prompt_do(const PromptReason reason, FSTR_P const fstr, const char extra_char, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) { + host_action_prompt_begin(reason, fstr, extra_char); _host_prompt_show(btn1, btn2); } void filament_load_host_prompt() { const bool disable_to_continue = TERN0(HAS_FILAMENT_SENSOR, runout.filament_ran_out); - host_prompt_do(PROMPT_FILAMENT_RUNOUT, PSTR("Paused"), PSTR("PurgeMore"), - disable_to_continue ? PSTR("DisableRunout") : CONTINUE_STR + host_prompt_do(PROMPT_FILAMENT_RUNOUT, F("Paused"), F("PurgeMore"), + disable_to_continue ? F("DisableRunout") : FPSTR(CONTINUE_STR) ); } diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 065b59d755..fb19618b1a 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -24,7 +24,7 @@ #include "../inc/MarlinConfigPre.h" #include "../HAL/shared/Marduino.h" -void host_action(PGM_P const pstr, const bool eol=true); +void host_action(FSTR_P const fstr, const bool eol=true); #ifdef ACTION_ON_KILL void host_action_kill(); @@ -64,16 +64,16 @@ void host_action(PGM_P const pstr, const bool eol=true); extern PromptReason host_prompt_reason; void host_response_handler(const uint8_t response); - void host_action_notify(const char * const message); - void host_action_notify_P(PGM_P const message); - void host_action_prompt_begin(const PromptReason reason, PGM_P const pstr, const char extra_char='\0'); - void host_action_prompt_button(PGM_P const pstr); + void host_action_notify(const char * const cstr); + void host_action_notify(FSTR_P const fstr); + void host_action_prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char='\0'); + void host_action_prompt_button(FSTR_P const fstr); void host_action_prompt_end(); void host_action_prompt_show(); - void host_prompt_do(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr); - void host_prompt_do(const PromptReason reason, PGM_P const pstr, const char extra_char, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr); - inline void host_prompt_open(const PromptReason reason, PGM_P const pstr, PGM_P const btn1=nullptr, PGM_P const btn2=nullptr) { - if (host_prompt_reason == PROMPT_NOT_DEFINED) host_prompt_do(reason, pstr, btn1, btn2); + void host_prompt_do(const PromptReason reason, FSTR_P const fstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); + void host_prompt_do(const PromptReason reason, FSTR_P const fstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); + inline void host_prompt_open(const PromptReason reason, FSTR_P const fstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr) { + if (host_prompt_reason == PROMPT_NOT_DEFINED) host_prompt_do(reason, fstr, btn1, btn2); } void filament_load_host_prompt(); diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 7362530e35..14f2623e14 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -960,7 +960,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (recover) { LCD_MESSAGE(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("MMU2 Eject Recover"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 75255d87ac..9b7404d852 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -198,7 +198,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, active_extruder); - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Load Filament T"), tool, CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, F("Load Filament T"), tool, FPSTR(CONTINUE_STR)); #endif while (wait_for_user) { @@ -253,7 +253,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE))); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) @@ -403,7 +403,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool #endif #endif - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, F("Pause"), FPSTR(DISMISS_STR))); // Indicate that the printer is paused ++did_pause_print; @@ -512,7 +512,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_NOZZLE_PARKED), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED))); wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { @@ -528,13 +528,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep ui.pause_show_message(PAUSE_MESSAGE_HEAT); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_HEATER_TIMEOUT), GET_TEXT_F(MSG_REHEAT))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108 - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT_F(MSG_REHEATING))); TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING))); @@ -554,7 +554,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_REHEATDONE), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_REHEATDONE), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATDONE)); @@ -671,7 +671,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ --did_pause_print; - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming"), DISMISS_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, F("Resuming"), FPSTR(DISMISS_STR))); // Resume the print job timer if it was running if (print_job_timer.isPaused()) print_job_timer.start(); diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 85280d7cb1..e53c229e70 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -96,7 +96,7 @@ void event_filament_runout(const uint8_t extruder) { //action:out_of_filament #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_prompt_begin(PROMPT_FILAMENT_RUNOUT, PSTR("FilamentRunout T"), tool); + host_action_prompt_begin(PROMPT_FILAMENT_RUNOUT, F("FilamentRunout T"), tool); host_action_prompt_show(); #endif @@ -115,7 +115,7 @@ void event_filament_runout(const uint8_t extruder) { // Legacy Repetier command for use until newer version supports standard dialog // To be removed later when pause command also triggers dialog #ifdef ACTION_ON_FILAMENT_RUNOUT - host_action(PSTR(ACTION_ON_FILAMENT_RUNOUT " T"), false); + host_action(F(ACTION_ON_FILAMENT_RUNOUT " T"), false); SERIAL_CHAR(tool); SERIAL_EOL(); #endif diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 08b45efa15..ca9f5405ce 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -344,7 +344,7 @@ void GcodeSuite::M43() { #if HAS_RESUME_CONTINUE KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("M43 Wait Called"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called"))); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index e7be0bd37f..c9c80639b5 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -237,9 +237,9 @@ void GcodeSuite::dwell(millis_t time) { #if ENABLED(G29_RETRY_AND_RECOVER) void GcodeSuite::event_probe_recover() { - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, F("G29 Retrying"), FPSTR(DISMISS_STR))); #ifdef ACTION_ON_G29_RECOVER - host_action(PSTR(ACTION_ON_G29_RECOVER)); + host_action(F(ACTION_ON_G29_RECOVER)); #endif #ifdef G29_RECOVER_COMMANDS process_subcommands_now(F(G29_RECOVER_COMMANDS)); @@ -252,7 +252,7 @@ void GcodeSuite::dwell(millis_t time) { void GcodeSuite::event_probe_failure() { #ifdef ACTION_ON_G29_FAILURE - host_action(PSTR(ACTION_ON_G29_FAILURE)); + host_action(F(ACTION_ON_G29_FAILURE)); #endif #ifdef G29_FAILURE_COMMANDS process_subcommands_now(F(G29_FAILURE_COMMANDS)); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 32df8dd9c3..952b24a2d1 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -84,7 +84,7 @@ void GcodeSuite::M0_M1() { #endif - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? F("M1 Stop") : F("M0 Stop"), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(ms)); diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index d436d88817..a9b7e42939 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -96,7 +96,7 @@ void GcodeSuite::M1001() { if (long_print) { printerEventLEDs.onPrintCompleted(); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE))); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_PRINT_DONE), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(SEC_TO_MS(TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)))); printerEventLEDs.onResumeAfterWait(); } diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 4cb040feb3..21e43b033e 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M24() { #ifdef ACTION_ON_RESUME host_action_resume(); #endif - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Resuming SD"), DISMISS_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, F("Resuming SD"), FPSTR(DISMISS_STR))); #endif ui.reset_status(); @@ -116,7 +116,7 @@ void GcodeSuite::M25() { IF_DISABLED(DWIN_CREALITY_LCD, ui.reset_status()); #if ENABLED(HOST_ACTION_COMMANDS) - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume"))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, F("Pause SD"), F("Resume"))); #ifdef ACTION_ON_PAUSE host_action_pause(); #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 66e2556b20..c18a7d46f4 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1352,28 +1352,28 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::has_status() { return (status_message[0] != '\0'); } - void MarlinUI::set_status(const char * const message, const bool persist) { + void MarlinUI::set_status(const char * const cstr, const bool persist) { if (alert_level) return; - TERN_(HOST_PROMPT_SUPPORT, host_action_notify(message)); + TERN_(HOST_PROMPT_SUPPORT, host_action_notify(cstr)); // Here we have a problem. The message is encoded in UTF8, so // arbitrarily cutting it will be a problem. We MUST be sure // that there is no cutting in the middle of a multibyte character! // Get a pointer to the null terminator - const char* pend = message + strlen(message); + const char* pend = cstr + strlen(cstr); // If length of supplied UTF8 string is greater than // our buffer size, start cutting whole UTF8 chars - while ((pend - message) > MAX_MESSAGE_LENGTH) { + while ((pend - cstr) > MAX_MESSAGE_LENGTH) { --pend; while (!START_OF_UTF8_CHAR(*pend)) --pend; }; // At this point, we have the proper cut point. Use it - uint8_t maxLen = pend - message; - strncpy(status_message, message, maxLen); + uint8_t maxLen = pend - cstr; + strncpy(status_message, cstr, maxLen); status_message[maxLen] = '\0'; finish_status(persist); @@ -1427,7 +1427,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; if (level < alert_level) return; alert_level = level; - TERN_(HOST_PROMPT_SUPPORT, host_action_notify_P(pstr)); + TERN_(HOST_PROMPT_SUPPORT, host_action_notify(fstr)); // Since the message is encoded in UTF8 it must // only be cut on a character boundary. @@ -1536,7 +1536,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; host_action_cancel(); #endif IF_DISABLED(SDSUPPORT, print_job_timer.stop()); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, F("UI Aborted"), FPSTR(DISMISS_STR))); LCD_MESSAGE(MSG_PRINT_ABORTED); TERN_(HAS_LCD_MENU, return_to_status()); } @@ -1565,7 +1565,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, F("UI Pause"), F("Resume"))); LCD_MESSAGE(MSG_PRINT_PAUSED); @@ -1642,10 +1642,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN(HOST_PROMPT_SUPPORT, host_action_notify(cstr), UNUSED(cstr)); } void MarlinUI::set_status(FSTR_P const fstr, const int8_t) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(FTOP(fstr)), UNUSED(fstr)); + TERN(HOST_PROMPT_SUPPORT, host_action_notify(fstr), UNUSED(fstr)); } void MarlinUI::status_printf(const uint8_t, FSTR_P const fstr, ...) { - TERN(HOST_PROMPT_SUPPORT, host_action_notify_P(FPSTR(fstr)), UNUSED(fstr)); + TERN(HOST_PROMPT_SUPPORT, host_action_notify(fstr), UNUSED(fstr)); } #endif // !HAS_DISPLAY && !HAS_STATUS_MESSAGE diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index c9bcb895fc..0990ac504d 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -64,7 +64,7 @@ void _man_probe_pt(const xy_pos_t &xy) { float lcd_probe_pt(const xy_pos_t &xy) { _man_probe_pt(xy); ui.defer_status_screen(); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Delta Calibration in progress"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress"))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.goto_previous_screen_no_defer(); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 5accbc8edd..18e72f401c 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -140,7 +140,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() LCD_MESSAGE(MSG_MANUAL_DEPLOY_TOUCHMI); ui.return_to_status(); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Deploy TouchMI"), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); ui.goto_screen(prev_screen); @@ -295,7 +295,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { ui.set_status(ds_str, 99); SERIAL_ECHOLNF(ds_str); - TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR)); + TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Stow Probe"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); From 12b5d997a2cee538e5026a68f8e0cfdd53248986 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 22:11:48 -0500 Subject: [PATCH 0758/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20som?= =?UTF-8?q?e=20ExtUI=20functions?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/mmu/mmu2.cpp | 2 +- Marlin/src/feature/pause.cpp | 12 +-- Marlin/src/gcode/config/M43.cpp | 2 +- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/gcode/sd/M1001.cpp | 2 +- .../extui/anycubic_chiron/FileNavigator.cpp | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 85 ++++++++--------- .../lcd/extui/anycubic_chiron/chiron_tft.h | 10 +- .../extui/anycubic_chiron/chiron_tft_defs.h | 94 +++++++++---------- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 58 ++++++------ .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 68 +++++++------- .../extui/dgus_reloaded/DGUSScreenHandler.cpp | 31 +++--- .../extui/dgus_reloaded/DGUSScreenHandler.h | 2 +- .../extui/dgus_reloaded/DGUSSetupHandler.cpp | 10 +- .../bioprinter/status_screen.cpp | 4 +- .../cocoa_press/leveling_menu.cpp | 2 +- .../cocoa_press/main_menu.cpp | 2 +- .../cocoa_press/preheat_menu.cpp | 12 +-- .../generic/bed_mesh_edit_screen.cpp | 4 +- .../generic/bed_mesh_view_screen.cpp | 4 +- .../confirm_auto_calibration_dialog_box.cpp | 2 +- .../generic/custom_user_menus.cpp | 2 +- .../generic/leveling_menu.cpp | 4 +- .../ftdi_eve_touch_ui/generic/main_menu.cpp | 4 +- .../generic/restore_failsafe_dialog_box.cpp | 2 +- .../generic/save_settings_dialog_box.cpp | 2 +- .../generic/spinner_dialog_box.cpp | 14 +-- .../generic/stress_test_screen.cpp | 4 +- .../src/lcd/extui/nextion/FileNavigator.cpp | 36 +++---- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 14 +-- Marlin/src/lcd/extui/nextion/nextion_tft.h | 6 +- .../src/lcd/extui/nextion/nextion_tft_defs.h | 14 +-- Marlin/src/lcd/extui/ui_api.cpp | 12 +-- Marlin/src/lcd/extui/ui_api.h | 5 +- Marlin/src/lcd/marlinui.cpp | 22 ++--- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/module/probe.cpp | 2 +- 37 files changed, 277 insertions(+), 278 deletions(-) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 14f2623e14..363e4d5505 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -961,7 +961,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { LCD_MESSAGE(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("MMU2 Eject Recover"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("MMU2 Eject Recover"))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); BUZZ(200, 404); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 9b7404d852..8a35a87eeb 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -194,7 +194,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; // LCD click or M108 will clear this - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Load Filament"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Load Filament"))); #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, active_extruder); @@ -252,7 +252,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_PURGE))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); wait_for_user = true; // A click or M108 breaks the purge_length loop @@ -513,7 +513,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_NOZZLE_PARKED), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_NOZZLE_PARKED))); wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { impatient_beep(max_beep_count); @@ -530,13 +530,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_HEATER_TIMEOUT), GET_TEXT_F(MSG_REHEAT))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_HEATER_TIMEOUT))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108 TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, GET_TEXT_F(MSG_REHEATING))); - TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged_P(GET_TEXT(MSG_REHEATING))); + TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(GET_TEXT_F(MSG_REHEATING))); TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATING)); @@ -555,7 +555,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_REHEATDONE), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_REHEATDONE))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_REHEATDONE))); TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATDONE)); IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index ca9f5405ce..82089b7d97 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -345,7 +345,7 @@ void GcodeSuite::M43() { KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("M43 Wait Called"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("M43 Wait Called"))); #endif for (;;) { diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 952b24a2d1..17481f0198 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M0_M1() { if (parser.string_arg) ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? else - ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); + ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) if (parser.string_arg) DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index a9b7e42939..bd1a18734d 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -95,7 +95,7 @@ void GcodeSuite::M1001() { #if HAS_LEDS_OFF_FLAG if (long_print) { printerEventLEDs.onPrintCompleted(); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_PRINT_DONE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_PRINT_DONE), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(SEC_TO_MS(TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)))); printerEventLEDs.onResumeAfterWait(); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp index 1339c39f3f..f49b17acc1 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -157,7 +157,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { // The new panel ignores entries that don't end in .GCO or .gcode so add and pad them. if (paneltype == AC_panel_new) { TFTSer.println("<<.GCO"); - Chiron.SendtoTFTLN(PSTR(".. .gcode")); + Chiron.SendtoTFTLN(F(".. .gcode")); } else { TFTSer.println("<<"); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index e7b3941928..483da200e8 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -99,7 +99,7 @@ void ChironTFT::Startup() { // Enable leveling and Disable end stops during print // as Z home places nozzle above the bed so we need to allow it past the end stops - injectCommands_P(AC_cmnd_enable_leveling); + injectCommands(AC_cmnd_enable_leveling); // Startup tunes are defined in Tunes.h PlayTune(BEEPER_PIN, TERN(AC_DEFAULT_STARTUP_TUNE, Anycubic_PowerOn, GB_PowerOn), 1); @@ -244,7 +244,7 @@ void ChironTFT::StatusChange(const char * const msg) { // If probing completes ok save the mesh and park // Ignore the custom machine name if (strcmp_P(msg + strlen(CUSTOM_MACHINE_NAME), MARLIN_msg_ready) == 0) { - injectCommands_P(PSTR("M500\nG27")); + injectCommands(F("M500\nG27")); SendtoTFTLN(AC_msg_probing_complete); printer_state = AC_printer_idle; msg_matched = true; @@ -252,7 +252,7 @@ void ChironTFT::StatusChange(const char * const msg) { // If probing fails don't save the mesh raise the probe above the bad point if (strcmp_P(msg, MARLIN_msg_probing_failed) == 0) { PlayTune(BEEPER_PIN, BeepBeepBeeep, 1); - injectCommands_P(PSTR("G1 Z50 F500")); + injectCommands(F("G1 Z50 F500")); SendtoTFTLN(AC_msg_probing_complete); printer_state = AC_printer_idle; msg_matched = true; @@ -315,19 +315,20 @@ void ChironTFT::PrintComplete() { setSoftEndstopState(true); // enable endstops } -void ChironTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEM string to the panel +void ChironTFT::SendtoTFT(FSTR_P const fstr) { // A helper to print PROGMEM string to the panel #if ACDEBUG(AC_SOME) - SERIAL_ECHOPGM_P(str); + SERIAL_ECHOF(fstr); #endif + PGM_P str = FTOP(fstr); while (const char c = pgm_read_byte(str++)) TFTSer.write(c); } -void ChironTFT::SendtoTFTLN(PGM_P str = nullptr) { - if (str) { +void ChironTFT::SendtoTFTLN(FSTR_P const fstr) { + if (fstr) { #if ACDEBUG(AC_SOME) SERIAL_ECHOPGM("> "); #endif - SendtoTFT(str); + SendtoTFT(fstr); #if ACDEBUG(AC_SOME) SERIAL_EOL(); #endif @@ -426,9 +427,9 @@ void ChironTFT::SendFileList(int8_t startindex) { #if ACDEBUG(AC_INFO) SERIAL_ECHOLNPGM("## SendFileList ## ", startindex); #endif - SendtoTFTLN(PSTR("FN ")); + SendtoTFTLN(F("FN ")); filenavigator.getFiles(startindex, panel_type, 4); - SendtoTFTLN(PSTR("END")); + SendtoTFTLN(F("END")); } void ChironTFT::SelectFile() { @@ -512,55 +513,55 @@ void ChironTFT::PanelInfo(uint8_t req) { // information requests A0-A8 and A33 switch (req) { case 0: // A0 Get HOTEND Temp - SendtoTFT(PSTR("A0V ")); + SendtoTFT(F("A0V ")); TFTSer.println(getActualTemp_celsius(E0)); break; case 1: // A1 Get HOTEND Target Temp - SendtoTFT(PSTR("A1V ")); + SendtoTFT(F("A1V ")); TFTSer.println(getTargetTemp_celsius(E0)); break; case 2: // A2 Get BED Temp - SendtoTFT(PSTR("A2V ")); + SendtoTFT(F("A2V ")); TFTSer.println(getActualTemp_celsius(BED)); break; case 3: // A3 Get BED Target Temp - SendtoTFT(PSTR("A3V ")); + SendtoTFT(F("A3V ")); TFTSer.println(getTargetTemp_celsius(BED)); break; case 4: // A4 Get FAN Speed - SendtoTFT(PSTR("A4V ")); + SendtoTFT(F("A4V ")); TFTSer.println(getActualFan_percent(FAN0)); break; case 5: // A5 Get Current Coordinates - SendtoTFT(PSTR("A5V X: ")); + SendtoTFT(F("A5V X: ")); TFTSer.print(getAxisPosition_mm(X)); - SendtoTFT(PSTR(" Y: ")); + SendtoTFT(F(" Y: ")); TFTSer.print(getAxisPosition_mm(Y)); - SendtoTFT(PSTR(" Z: ")); + SendtoTFT(F(" Z: ")); TFTSer.println(getAxisPosition_mm(Z)); break; case 6: // A6 Get printing progress if (isPrintingFromMedia()) { - SendtoTFT(PSTR("A6V ")); + SendtoTFT(F("A6V ")); TFTSer.println(ui8tostr2(getProgress_percent())); } else - SendtoTFTLN(PSTR("A6V ---")); + SendtoTFTLN(F("A6V ---")); break; case 7: { // A7 Get Printing Time uint32_t time = getProgress_seconds_elapsed() / 60; - SendtoTFT(PSTR("A7V ")); + SendtoTFT(F("A7V ")); TFTSer.print(ui8tostr2(time / 60)); - SendtoTFT(PSTR(" H ")); + SendtoTFT(F(" H ")); TFTSer.print(ui8tostr2(time % 60)); - SendtoTFT(PSTR(" M")); + SendtoTFT(F(" M")); #if ACDEBUG(AC_ALL) SERIAL_ECHOLNPGM("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); #endif @@ -575,9 +576,9 @@ void ChironTFT::PanelInfo(uint8_t req) { break; case 33: // A33 Get firmware info - SendtoTFT(PSTR("J33 ")); + SendtoTFT(F("J33 ")); // If there is an error recorded, show that instead of the FW version - if (!GetLastError()) SendtoTFTLN(PSTR(SHORT_BUILD_VERSION)); + if (!GetLastError()) SendtoTFTLN(F(SHORT_BUILD_VERSION)); break; } } @@ -608,7 +609,7 @@ void ChironTFT::PanelAction(uint8_t req) { } else { if (printer_state == AC_printer_resuming_from_power_outage) - injectCommands_P(PSTR("M1000 C")); // Cancel recovery + injectCommands(F("M1000 C")); // Cancel recovery SendtoTFTLN(AC_msg_stop); printer_state = AC_printer_idle; } @@ -625,7 +626,7 @@ void ChironTFT::PanelAction(uint8_t req) { case 14: { // A14 Start Printing // Allows printer to restart the job if we don't want to recover if (printer_state == AC_printer_resuming_from_power_outage) { - injectCommands_P(PSTR("M1000 C")); // Cancel recovery + injectCommands(F("M1000 C")); // Cancel recovery printer_state = AC_printer_idle; } #if ACDebugLevel >= 1 @@ -638,8 +639,8 @@ void ChironTFT::PanelAction(uint8_t req) { case 15: // A15 Resuming from outage if (printer_state == AC_printer_resuming_from_power_outage) { // Need to home here to restore the Z position - injectCommands_P(AC_cmnd_power_loss_recovery); - injectCommands_P(PSTR("M1000")); // home and start recovery + injectCommands(AC_cmnd_power_loss_recovery); + injectCommands(F("M1000")); // home and start recovery } break; @@ -675,7 +676,7 @@ void ChironTFT::PanelAction(uint8_t req) { if (panel_command[4] == 'S') setFeedrate_percent(atoi(&panel_command[5])); else { - SendtoTFT(PSTR("A20V ")); + SendtoTFT(F("A20V ")); TFTSer.println(getFeedrate_percent()); } break; @@ -683,9 +684,9 @@ void ChironTFT::PanelAction(uint8_t req) { case 21: // A21 Home Axis A21 X if (!isPrinting()) { switch ((char)panel_command[4]) { - case 'X': injectCommands_P(PSTR("G28X")); break; - case 'Y': injectCommands_P(PSTR("G28Y")); break; - case 'Z': injectCommands_P(PSTR("G28Z")); break; + case 'X': injectCommands(F("G28X")); break; + case 'Y': injectCommands(F("G28Y")); break; + case 'Z': injectCommands(F("G28Z")); break; case 'C': injectCommands_P(G28_STR); break; } } @@ -771,7 +772,7 @@ void ChironTFT::PanelProcess(uint8_t req) { pos.y = atoi(&panel_command[FindToken('Y')+1]); pos_z = getMeshPoint(pos); - SendtoTFT(PSTR("A29V ")); + SendtoTFT(F("A29V ")); TFTSer.println(pos_z * 100); if (!isPrinting()) { setSoftEndstopState(true); // disable endstops @@ -809,7 +810,7 @@ void ChironTFT::PanelProcess(uint8_t req) { SendtoTFTLN(AC_msg_start_probing); - injectCommands_P(PSTR("G28\nG29")); + injectCommands(F("G28\nG29")); printer_state = AC_printer_probing; } } @@ -823,7 +824,7 @@ void ChironTFT::PanelProcess(uint8_t req) { if (FindToken('C') != -1) { // Restore and apply original offsets if (!isPrinting()) { - injectCommands_P(PSTR("M501\nM420 S1")); + injectCommands(F("M501\nM420 S1")); selectedmeshpoint.x = selectedmeshpoint.y = 99; SERIAL_ECHOLNF(AC_msg_mesh_changes_abandoned); } @@ -832,14 +833,14 @@ void ChironTFT::PanelProcess(uint8_t req) { else if (FindToken('D') != -1) { // Save Z Offset tables and restore leveling state if (!isPrinting()) { setAxisPosition_mm(1.0,Z); // Lift nozzle before any further movements are made - injectCommands_P(PSTR("M500")); + injectCommands(F("M500")); SERIAL_ECHOLNF(AC_msg_mesh_changes_saved); selectedmeshpoint.x = selectedmeshpoint.y = 99; } } else if (FindToken('G') != -1) { // Get current offset - SendtoTFT(PSTR("A31V ")); + SendtoTFT(F("A31V ")); // When printing use the live z Offset position // we will use babystepping to move the print head if (isPrinting()) @@ -874,7 +875,7 @@ void ChironTFT::PanelProcess(uint8_t req) { babystepAxis_steps(steps, Z); live_Zoffset += Zshift; } - SendtoTFT(PSTR("A31V ")); + SendtoTFT(F("A31V ")); TFTSer.println(live_Zoffset); } else { @@ -892,7 +893,7 @@ void ChironTFT::PanelProcess(uint8_t req) { #endif setZOffset_mm(currZOffset + Zshift); - SendtoTFT(PSTR("A31V ")); + SendtoTFT(F("A31V ")); TFTSer.println(getZOffset_mm()); if (isAxisPositionKnown(Z)) { @@ -911,7 +912,7 @@ void ChironTFT::PanelProcess(uint8_t req) { case 32: { // A32 clean leveling beep flag // Ignore request if printing //if (isPrinting()) break; - //injectCommands_P(PSTR("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); + //injectCommands(F("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); //TFTSer.println(); } break; @@ -919,7 +920,7 @@ void ChironTFT::PanelProcess(uint8_t req) { case 34: { // A34 Adjust single mesh point A34 C/S X1 Y1 V123 if (panel_command[3] == 'C') { // Restore original offsets - injectCommands_P(PSTR("M501\nM420 S1")); + injectCommands(F("M501\nM420 S1")); selectedmeshpoint.x = selectedmeshpoint.y = 99; //printer_state = AC_printer_idle; } diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h index 7eb0049993..a80763e372 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h @@ -59,16 +59,16 @@ class ChironTFT { public: static void Startup(); static void IdleLoop(); - static void PrinterKilled(PGM_P,PGM_P); + static void PrinterKilled(PGM_P, PGM_P); static void MediaEvent(media_event_t); static void TimerEvent(timer_event_t); static void FilamentRunout(); - static void ConfirmationRequest(const char * const ); - static void StatusChange(const char * const ); + static void ConfirmationRequest(const char * const); + static void StatusChange(const char * const); static void PowerLossRecovery(); static void PrintComplete(); - static void SendtoTFT(PGM_P); - static void SendtoTFTLN(PGM_P); + static void SendtoTFT(FSTR_P const); + static void SendtoTFTLN(FSTR_P const); private: static void DetectPanelType(); static bool ReadTFTCommand(); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h index d9157fc4e6..0fd7770cdd 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h @@ -57,46 +57,46 @@ #define AC_LOWEST_MESHPOINT_VAL -10 // The lowest value you can set for a single mesh point offset // TFT panel commands -#define AC_msg_sd_card_inserted PSTR("J00") -#define AC_msg_sd_card_removed PSTR("J01") -#define AC_msg_no_sd_card PSTR("J02") -#define AC_msg_usb_connected PSTR("J03") -#define AC_msg_print_from_sd_card PSTR("J04") -#define AC_msg_pause PSTR("J05") -#define AC_msg_nozzle_heating PSTR("J06") -#define AC_msg_nozzle_heating_done PSTR("J07") -#define AC_msg_bed_heating PSTR("J08") -#define AC_msg_bed_heating_done PSTR("J09") -#define AC_msg_nozzle_temp_abnormal PSTR("J10") -#define AC_msg_kill_lcd PSTR("J11") -#define AC_msg_ready PSTR("J12") -#define AC_msg_low_nozzle_temp PSTR("J13") -#define AC_msg_print_complete PSTR("J14") -#define AC_msg_filament_out_alert PSTR("J15") -#define AC_msg_stop PSTR("J16") -#define AC_msg_main_board_has_reset PSTR("J17") -#define AC_msg_paused PSTR("J18") -#define AC_msg_j19_unknown PSTR("J19") -#define AC_msg_sd_file_open_success PSTR("J20") -#define AC_msg_sd_file_open_failed PSTR("J21") -#define AC_msg_level_monitor_finished PSTR("J22") -#define AC_msg_filament_out_block PSTR("J23") -#define AC_msg_probing_not_allowed PSTR("J24") -#define AC_msg_probing_complete PSTR("J25") -#define AC_msg_start_probing PSTR("J26") -#define AC_msg_version PSTR("J27") -#define AC_msg_mesh_changes_abandoned PSTR("Mesh changes abandoned, previous mesh restored.") -#define AC_msg_mesh_changes_saved PSTR("Mesh changes saved.") -#define AC_msg_old_panel_detected PSTR("Standard TFT panel detected!") -#define AC_msg_new_panel_detected PSTR("New TFT panel detected!") -#define AC_msg_powerloss_recovery PSTR("Resuming from power outage! select the same SD file then press resume") +#define AC_msg_sd_card_inserted F("J00") +#define AC_msg_sd_card_removed F("J01") +#define AC_msg_no_sd_card F("J02") +#define AC_msg_usb_connected F("J03") +#define AC_msg_print_from_sd_card F("J04") +#define AC_msg_pause F("J05") +#define AC_msg_nozzle_heating F("J06") +#define AC_msg_nozzle_heating_done F("J07") +#define AC_msg_bed_heating F("J08") +#define AC_msg_bed_heating_done F("J09") +#define AC_msg_nozzle_temp_abnormal F("J10") +#define AC_msg_kill_lcd F("J11") +#define AC_msg_ready F("J12") +#define AC_msg_low_nozzle_temp F("J13") +#define AC_msg_print_complete F("J14") +#define AC_msg_filament_out_alert F("J15") +#define AC_msg_stop F("J16") +#define AC_msg_main_board_has_reset F("J17") +#define AC_msg_paused F("J18") +#define AC_msg_j19_unknown F("J19") +#define AC_msg_sd_file_open_success F("J20") +#define AC_msg_sd_file_open_failed F("J21") +#define AC_msg_level_monitor_finished F("J22") +#define AC_msg_filament_out_block F("J23") +#define AC_msg_probing_not_allowed F("J24") +#define AC_msg_probing_complete F("J25") +#define AC_msg_start_probing F("J26") +#define AC_msg_version F("J27") +#define AC_msg_mesh_changes_abandoned F("Mesh changes abandoned, previous mesh restored.") +#define AC_msg_mesh_changes_saved F("Mesh changes saved.") +#define AC_msg_old_panel_detected F("Standard TFT panel detected!") +#define AC_msg_new_panel_detected F("New TFT panel detected!") +#define AC_msg_powerloss_recovery F("Resuming from power outage! select the same SD file then press resume") // Error messages must not contain spaces -#define AC_msg_error_bed_temp PSTR("Abnormal_bed_temp") -#define AC_msg_error_hotend_temp PSTR("Abnormal_hotend_temp") -#define AC_msg_error_sd_card PSTR("SD_card_error") -#define AC_msg_filament_out PSTR("Filament_runout") -#define AC_msg_power_loss PSTR("Power_failure") -#define AC_msg_eeprom_version PSTR("EEPROM_ver_wrong") +#define AC_msg_error_bed_temp F("Abnormal_bed_temp") +#define AC_msg_error_hotend_temp F("Abnormal_hotend_temp") +#define AC_msg_error_sd_card F("SD_card_error") +#define AC_msg_filament_out F("Filament_runout") +#define AC_msg_power_loss F("Power_failure") +#define AC_msg_eeprom_version F("EEPROM_ver_wrong") #define MARLIN_msg_start_probing PSTR("Probing Point 1/25") #define MARLIN_msg_probing_failed PSTR("Probing Failed") @@ -113,16 +113,16 @@ #define MARLIN_msg_filament_purging PSTR("Filament Purging...") #define MARLIN_msg_special_pause PSTR("PB") -#define AC_cmnd_auto_unload_filament PSTR("M701") // Use Marlin unload routine -#define AC_cmnd_auto_load_filament PSTR("M702 M0 PB") // Use Marlin load routing then pause for user to clean nozzle +#define AC_cmnd_auto_unload_filament F("M701") // Use Marlin unload routine +#define AC_cmnd_auto_load_filament F("M702 M0 PB") // Use Marlin load routing then pause for user to clean nozzle -#define AC_cmnd_manual_load_filament PSTR("M83\nG1 E50 F700\nM82") // replace the manual panel commands with something a little faster -#define AC_cmnd_manual_unload_filament PSTR("M83\nG1 E-50 F1200\nM82") -#define AC_cmnd_enable_leveling PSTR("M420SV") -#define AC_cmnd_power_loss_recovery PSTR("G28XYR5\nG28Z") // Lift, home X and Y then home Z when in 'safe' position +#define AC_cmnd_manual_load_filament F("M83\nG1 E50 F700\nM82") // replace the manual panel commands with something a little faster +#define AC_cmnd_manual_unload_filament F("M83\nG1 E-50 F1200\nM82") +#define AC_cmnd_enable_leveling F("M420SV") +#define AC_cmnd_power_loss_recovery F("G28XYR5\nG28Z") // Lift, home X and Y then home Z when in 'safe' position -#define AC_Test_for_OldPanel PSTR("SIZE") // An old panel will respond with 'SXY 480 320' a new panel wont respond. -#define AC_Test_for_NewPanel PSTR("J200") // A new panel will respond with '[0]=0 [1]=0' to '[19]=0 ' an old panel wont respond +#define AC_Test_for_OldPanel F("SIZE") // An old panel will respond with 'SXY 480 320' a new panel wont respond. +#define AC_Test_for_NewPanel F("J200") // A new panel will respond with '[0]=0 [1]=0' to '[19]=0 ' an old panel wont respond namespace Anycubic { enum heater_state_t : uint8_t { diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index e07e377dfc..5bbcfd0b5e 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -104,7 +104,7 @@ void AnycubicTFTClass::OnSetup() { SelectedFile[0] = 0; #if ENABLED(STARTUP_CHIME) - injectCommands_P(PSTR("M300 P250 S554\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P500 S831")); + injectCommands(F("M300 P250 S554\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P250 S740\nM300 P250 S554\nM300 P500 S831")); #endif #if ENABLED(ANYCUBIC_LCD_DEBUG) SERIAL_ECHOLNPGM("TFT Serial Debug: Finished startup"); @@ -122,7 +122,7 @@ void AnycubicTFTClass::OnCommandScan() { #endif mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; mediaPauseState = AMPAUSESTATE_NOT_PAUSED; - injectCommands_P(PSTR("M84\nM27")); // disable stepper motors and force report of SD status + injectCommands(F("M84\nM27")); // disable stepper motors and force report of SD status delay_ms(200); // tell printer to release resources of print to indicate it is done SENDLINE_DBG_PGM("J14", "TFT Serial Debug: SD Print Stopped... J14"); @@ -249,48 +249,48 @@ void AnycubicTFTClass::HandleSpecialMenu() { switch (SelectedDirectory[2]) { case '1': // "<01ZUp0.1>" SERIAL_ECHOLNPGM("Special Menu: Z Up 0.1"); - injectCommands_P(PSTR("G91\nG1 Z+0.1\nG90")); + injectCommands(F("G91\nG1 Z+0.1\nG90")); break; case '2': // "<02ZUp0.02>" SERIAL_ECHOLNPGM("Special Menu: Z Up 0.02"); - injectCommands_P(PSTR("G91\nG1 Z+0.02\nG90")); + injectCommands(F("G91\nG1 Z+0.02\nG90")); break; case '3': // "<03ZDn0.02>" SERIAL_ECHOLNPGM("Special Menu: Z Down 0.02"); - injectCommands_P(PSTR("G91\nG1 Z-0.02\nG90")); + injectCommands(F("G91\nG1 Z-0.02\nG90")); break; case '4': // "<04ZDn0.1>" SERIAL_ECHOLNPGM("Special Menu: Z Down 0.1"); - injectCommands_P(PSTR("G91\nG1 Z-0.1\nG90")); + injectCommands(F("G91\nG1 Z-0.1\nG90")); break; case '5': // "<05PrehtBed>" SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); - injectCommands_P(PSTR("M140 S65")); + injectCommands(F("M140 S65")); break; case '6': // "<06SMeshLvl>" SERIAL_ECHOLNPGM("Special Menu: Start Mesh Leveling"); - injectCommands_P(PSTR("G29S1")); + injectCommands(F("G29S1")); break; case '7': // "<07MeshNPnt>" SERIAL_ECHOLNPGM("Special Menu: Next Mesh Point"); - injectCommands_P(PSTR("G29S2")); + injectCommands(F("G29S2")); break; case '8': // "<08HtEndPID>" SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); // need to dwell for half a second to give the fan a chance to start before the pid tuning starts - injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); + injectCommands(F("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); break; case '9': // "<09HtBedPID>" SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); - injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); + injectCommands(F("M303 E-1 S65 C6 U1")); break; default: @@ -302,12 +302,12 @@ void AnycubicTFTClass::HandleSpecialMenu() { switch (SelectedDirectory[2]) { case '0': // "<10FWDeflts>" SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); - injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); + injectCommands(F("M502\nM300 P105 S1661\nM300 P210 S1108")); break; case '1': // "<11SvEEPROM>" SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); - injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); + injectCommands(F("M500\nM300 P105 S1108\nM300 P210 S1661")); break; default: @@ -319,38 +319,38 @@ void AnycubicTFTClass::HandleSpecialMenu() { switch (SelectedDirectory[2]) { case '1': // "<01PrehtBed>" SERIAL_ECHOLNPGM("Special Menu: Preheat Bed"); - injectCommands_P(PSTR("M140 S65")); + injectCommands(F("M140 S65")); break; case '2': // "<02ABL>" SERIAL_ECHOLNPGM("Special Menu: Auto Bed Leveling"); - injectCommands_P(PSTR("G29N")); + injectCommands(F("G29N")); break; case '3': // "<03HtendPID>" SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotend PID"); // need to dwell for half a second to give the fan a chance to start before the pid tuning starts - injectCommands_P(PSTR("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); + injectCommands(F("M106 S204\nG4 P500\nM303 E0 S215 C15 U1")); break; case '4': // "<04HtbedPID>" SERIAL_ECHOLNPGM("Special Menu: Auto Tune Hotbed Pid"); - injectCommands_P(PSTR("M303 E-1 S65 C6 U1")); + injectCommands(F("M303 E-1 S65 C6 U1")); break; case '5': // "<05FWDeflts>" SERIAL_ECHOLNPGM("Special Menu: Load FW Defaults"); - injectCommands_P(PSTR("M502\nM300 P105 S1661\nM300 P210 S1108")); + injectCommands(F("M502\nM300 P105 S1661\nM300 P210 S1108")); break; case '6': // "<06SvEEPROM>" SERIAL_ECHOLNPGM("Special Menu: Save EEPROM"); - injectCommands_P(PSTR("M500\nM300 P105 S1108\nM300 P210 S1661")); + injectCommands(F("M500\nM300 P105 S1108\nM300 P210 S1661")); break; case '7': // <07SendM108> SERIAL_ECHOLNPGM("Special Menu: Send User Confirmation"); - injectCommands_P(PSTR("M108")); + injectCommands(F("M108")); break; default: @@ -705,7 +705,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { } else if (CodeSeen('C') && !isPrinting()) { if (getAxisPosition_mm(Z) < 10) - injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + injectCommands(F("G1 Z10")); // RASE Z AXIS tempvalue = constrain(CodeValue(), 0, 275); setTargetTemp_celsius(tempvalue, (extruder_t)E0); } @@ -756,11 +756,11 @@ void AnycubicTFTClass::GetCommandFromTFT() { if (!isPrinting() && !isPrintingFromMediaPaused()) { if (CodeSeen('X') || CodeSeen('Y') || CodeSeen('Z')) { if (CodeSeen('X')) - injectCommands_P(PSTR("G28X")); + injectCommands(F("G28X")); if (CodeSeen('Y')) - injectCommands_P(PSTR("G28Y")); + injectCommands(F("G28Y")); if (CodeSeen('Z')) - injectCommands_P(PSTR("G28Z")); + injectCommands(F("G28Z")); } else if (CodeSeen('C')) { injectCommands_P(G28_STR); @@ -831,7 +831,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { case 23: // A23 preheat pla if (!isPrinting()) { if (getAxisPosition_mm(Z) < 10) - injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + injectCommands(F("G1 Z10")); // RASE Z AXIS setTargetTemp_celsius(PREHEAT_1_TEMP_BED, (heater_t)BED); setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, (extruder_t)E0); @@ -842,7 +842,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { case 24:// A24 preheat abs if (!isPrinting()) { if (getAxisPosition_mm(Z) < 10) - injectCommands_P(PSTR("G1 Z10")); // RASE Z AXIS + injectCommands(F("G1 Z10")); // RASE Z AXIS setTargetTemp_celsius(PREHEAT_2_TEMP_BED, (heater_t)BED); setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, (extruder_t)E0); @@ -933,7 +933,7 @@ void AnycubicTFTClass::DoFilamentRunoutCheck() { if (READ(FIL_RUNOUT1_PIN)) { if (mediaPrintingState == AMPRINTSTATE_PRINTING || mediaPrintingState == AMPRINTSTATE_PAUSED || mediaPrintingState == AMPRINTSTATE_PAUSE_REQUESTED) { // play tone to indicate filament is out - injectCommands_P(PSTR("\nM300 P200 S1567\nM300 P200 S1174\nM300 P200 S1567\nM300 P200 S1174\nM300 P2000 S1567")); + injectCommands(F("\nM300 P200 S1567\nM300 P200 S1174\nM300 P200 S1567\nM300 P200 S1174\nM300 P2000 S1567")); // tell the user that the filament has run out and wait SENDLINE_DBG_PGM("J23", "TFT Serial Debug: Blocking filament prompt... J23"); @@ -969,7 +969,7 @@ void AnycubicTFTClass::PausePrint() { SENDLINE_DBG_PGM("J05", "TFT Serial Debug: SD print pause started... J05"); // J05 printing pause // for some reason pausing the print doesn't retract the extruder so force a manual one here - injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); + injectCommands(F("G91\nG1 E-2 F1800\nG90")); pausePrint(); } #endif @@ -1018,7 +1018,7 @@ void AnycubicTFTClass::StopPrint() { SENDLINE_DBG_PGM("J16", "TFT Serial Debug: SD print stop called... J16"); // for some reason stopping the print doesn't retract the extruder so force a manual one here - injectCommands_P(PSTR("G91\nG1 E-2 F1800\nG90")); + injectCommands(F("G91\nG1 E-2 F1800\nG90")); stopPrint(); #endif } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index f7d8da69fc..58c7baa0b6 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -52,26 +52,26 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { #endif if (!ExtUI::isMediaInserted()) { - dgus_screen_handler.SetStatusMessagePGM(GET_TEXT(MSG_NO_MEDIA)); + dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); return; } card.cdroot(); #else - dgus_screen_handler.SetStatusMessagePGM(GET_TEXT(MSG_NO_MEDIA)); + dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); return; #endif } if (vp.addr == DGUS_Addr::SCREENCHANGE_Idle && (ExtUI::isPrinting() || ExtUI::isPrintingPaused())) { - dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while printing")); + dgus_screen_handler.SetStatusMessage(F("Impossible while printing")); return; } if (vp.addr == DGUS_Addr::SCREENCHANGE_Printing && (!ExtUI::isPrinting() && !ExtUI::isPrintingPaused())) { - dgus_screen_handler.SetStatusMessagePGM(PSTR("Impossible while idle")); + dgus_screen_handler.SetStatusMessage(F("Impossible while idle")); return; } @@ -139,7 +139,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { UNUSED(data_ptr); if (dgus_screen_handler.filelist_selected < 0) { - dgus_screen_handler.SetStatusMessagePGM(PSTR("No file selected")); + dgus_screen_handler.SetStatusMessage(F("No file selected")); return; } @@ -149,7 +149,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -207,7 +207,7 @@ void DGUSRxHandler::PrintResume(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -364,7 +364,7 @@ void DGUSRxHandler::TempCool(DGUS_VP &vp, void *data_ptr) { #endif } - dgus_screen_handler.SetStatusMessagePGM(PSTR("Cooling...")); + dgus_screen_handler.SetStatusMessage(F("Cooling...")); dgus_screen_handler.TriggerFullUpdate(); } @@ -390,12 +390,12 @@ void DGUSRxHandler::ZOffset(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!ExtUI::isAxisPositionKnown(ExtUI::Z)) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -414,12 +414,12 @@ void DGUSRxHandler::ZOffsetStep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!ExtUI::isAxisPositionKnown(ExtUI::Z)) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -456,12 +456,12 @@ void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!ExtUI::isPositionKnown()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -506,17 +506,17 @@ void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { UNUSED(data_ptr); #if ENABLED(MESH_BED_LEVELING) - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_ABL_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_ABL_REQUIRED)); return; #endif if (!ExtUI::isPositionKnown()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -535,7 +535,7 @@ void DGUSRxHandler::DisableABL(DGUS_VP &vp, void *data_ptr) { UNUSED(data_ptr); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -576,7 +576,7 @@ void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -600,7 +600,7 @@ void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { } if (ExtUI::getActualTemp_celsius(extruder) < (float)EXTRUDE_MINTEMP) { - dgus_screen_handler.SetStatusMessagePGM(PSTR("Temperature too low")); + dgus_screen_handler.SetStatusMessage(F("Temperature too low")); return; } @@ -620,7 +620,7 @@ void DGUSRxHandler::Home(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -664,7 +664,7 @@ void DGUSRxHandler::Move(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isAxisPositionKnown(axis)) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } @@ -720,7 +720,7 @@ void DGUSRxHandler::MoveStep(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isAxisPositionKnown(axis)) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_HOMING_REQUIRED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_HOMING_REQUIRED)); return; } @@ -757,7 +757,7 @@ void DGUSRxHandler::GcodeExecute(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -780,7 +780,7 @@ void DGUSRxHandler::ResetEEPROM(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -798,7 +798,7 @@ void DGUSRxHandler::SettingsExtra(DGUS_VP &vp, void *data_ptr) { case DGUS_Data::Extra::BUTTON1: #if ENABLED(BLTOUCH) if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -844,7 +844,7 @@ void DGUSRxHandler::PIDSetTemp(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -875,7 +875,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { UNUSED(data_ptr); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -889,7 +889,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { heater = H_BED; break; #else - dgus_screen_handler.SetStatusMessagePGM(PSTR("Bed PID disabled")); + dgus_screen_handler.SetStatusMessage(F("Bed PID disabled")); return; #endif case DGUS_Data::Heater::H0: @@ -897,7 +897,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { heater = H_E0; break; #else - dgus_screen_handler.SetStatusMessagePGM(PSTR("PID disabled")); + dgus_screen_handler.SetStatusMessage(F("PID disabled")); return; #endif #if HOTENDS > 1 @@ -906,7 +906,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { heater = H_E1; break; #else - dgus_screen_handler.SetStatusMessagePGM(PSTR("PID disabled")); + dgus_screen_handler.SetStatusMessage(F("PID disabled")); return; #endif #endif @@ -936,7 +936,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } @@ -955,12 +955,12 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return; } if (!recovery.valid()) { - dgus_screen_handler.SetStatusMessagePGM(PSTR("Invalid recovery data")); + dgus_screen_handler.SetStatusMessage(F("Invalid recovery data")); return; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index 6316f1194b..b2189f1c82 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -135,20 +135,17 @@ void DGUSScreenHandler::Loop() { return; } - if (current_screen == DGUS_Screen::LEVELING_PROBING - && IsPrinterIdle()) { + if (current_screen == DGUS_Screen::LEVELING_PROBING && IsPrinterIdle()) { dgus_display.PlaySound(3); - SetStatusMessagePGM(ExtUI::getMeshValid() ? - PSTR("Probing successful") - : PSTR("Probing failed")); + SetStatusMessage(ExtUI::getMeshValid() ? F("Probing successful") : F("Probing failed")); MoveToScreen(DGUS_Screen::LEVELING_AUTOMATIC); return; } if (status_expire > 0 && ELAPSED(ms, status_expire)) { - SetStatusMessagePGM(NUL_STR, 0); + SetStatusMessage(FPSTR(NUL_STR), 0); return; } @@ -194,7 +191,7 @@ void DGUSScreenHandler::SettingsReset() { Ready(); } - SetStatusMessagePGM(PSTR("EEPROM reset")); + SetStatusMessage(F("EEPROM reset")); } void DGUSScreenHandler::StoreSettings(char *buff) { @@ -229,13 +226,13 @@ void DGUSScreenHandler::LoadSettings(const char *buff) { void DGUSScreenHandler::ConfigurationStoreWritten(bool success) { if (!success) { - SetStatusMessagePGM(PSTR("EEPROM write failed")); + SetStatusMessage(F("EEPROM write failed")); } } void DGUSScreenHandler::ConfigurationStoreRead(bool success) { if (!success) { - SetStatusMessagePGM(PSTR("EEPROM read failed")); + SetStatusMessage(F("EEPROM read failed")); } else if (!settings_ready) { settings_ready = true; @@ -324,7 +321,7 @@ void DGUSScreenHandler::FilamentRunout(const ExtUI::extruder_t extruder) { } void DGUSScreenHandler::SDCardError() { - SetStatusMessagePGM(GET_TEXT(MSG_MEDIA_READ_ERROR)); + SetStatusMessage(GET_TEXT_F(MSG_MEDIA_READ_ERROR)); if (current_screen == DGUS_Screen::PRINT) { TriggerScreenChange(DGUS_Screen::HOME); @@ -346,19 +343,19 @@ void DGUSScreenHandler::FilamentRunout(const ExtUI::extruder_t extruder) { void DGUSScreenHandler::PidTuning(const ExtUI::result_t rst) { switch (rst) { case ExtUI::PID_STARTED: - SetStatusMessagePGM(GET_TEXT(MSG_PID_AUTOTUNE)); + SetStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); break; case ExtUI::PID_BAD_EXTRUDER_NUM: - SetStatusMessagePGM(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + SetStatusMessage(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); break; case ExtUI::PID_TEMP_TOO_HIGH: - SetStatusMessagePGM(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + SetStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); break; case ExtUI::PID_TUNING_TIMEOUT: - SetStatusMessagePGM(GET_TEXT(MSG_PID_TIMEOUT)); + SetStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); break; case ExtUI::PID_DONE: - SetStatusMessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + SetStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); break; default: return; @@ -411,8 +408,8 @@ void DGUSScreenHandler::SetStatusMessage(const char* msg, const millis_t duratio status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); } -void DGUSScreenHandler::SetStatusMessagePGM(PGM_P msg, const millis_t duration) { - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Status, msg, DGUS_STATUS_LEN, false, true); +void DGUSScreenHandler::SetStatusMessage(FSTR_P const fmsg, const millis_t duration) { + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Status, FTOP(msg), DGUS_STATUS_LEN, false, true); status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index 402d8d3d38..ea1289dd67 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -73,7 +73,7 @@ public: static void SetMessageLinePGM(PGM_P msg, uint8_t line); static void SetStatusMessage(const char* msg, const millis_t duration = DGUS_STATUS_EXPIRATION_MS); - static void SetStatusMessagePGM(PGM_P msg, const millis_t duration = DGUS_STATUS_EXPIRATION_MS); + static void SetStatusMessage(FSTR_P const msg, const millis_t duration = DGUS_STATUS_EXPIRATION_MS); static void ShowWaitScreen(DGUS_Screen return_screen, bool has_continue = false); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp index e93eb766ce..6ab2b004e5 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -68,7 +68,7 @@ bool DGUSSetupHandler::LevelingMenu() { ExtUI::setLevelingActive(dgus_screen_handler.leveling_active); if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return false; } @@ -99,7 +99,7 @@ bool DGUSSetupHandler::LevelingManual() { } if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return false; } @@ -118,7 +118,7 @@ bool DGUSSetupHandler::LevelingOffset() { dgus_screen_handler.offset_steps = DGUS_Data::StepSize::MMP1; if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return false; } @@ -175,7 +175,7 @@ bool DGUSSetupHandler::Move() { dgus_screen_handler.move_steps = DGUS_Data::StepSize::MM10; if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_BUSY); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_BUSY)); return false; } @@ -186,7 +186,7 @@ bool DGUSSetupHandler::Gcode() { ZERO(dgus_screen_handler.gcode); if (dgus_display.gui_version < 0x30 || dgus_display.os_version < 0x21) { - dgus_screen_handler.SetStatusMessagePGM(DGUS_MSG_FW_OUTDATED); + dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_FW_OUTDATED)); return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp index cdc303a89e..6e4668eb36 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -52,7 +52,7 @@ bool StatusScreen::jog_xy; bool StatusScreen::fine_motion; void StatusScreen::unlockMotors() { - injectCommands_P(PSTR("M84 XY")); + injectCommands(F("M84 XY")); jog_xy = false; } @@ -305,7 +305,7 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { case 12: if (!jog_xy) { jog_xy = true; - injectCommands_P(PSTR("M17")); + injectCommands(F("M17")); } jog({ 0, 0, 0 }); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index 3636b5da6c..5ea9eed037 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -81,7 +81,7 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { case 2: BedMeshViewScreen::doProbe(); break; case 3: BedMeshViewScreen::show(); break; case 4: BedMeshEditScreen::show(); break; - case 5: injectCommands_P(PSTR("M280 P0 S60")); break; + case 5: injectCommands(F("M280 P0 S60")); break; case 6: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index 3fe17b72d5..2d404aff6c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -86,7 +86,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 6: GOTO_SCREEN(FeedratePercentScreen); break; case 7: GOTO_SCREEN(FlowPercentScreen); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - case 9: injectCommands_P(PSTR("M84")); break; + case 9: injectCommands(F("M84")); break; #if HAS_LEVELING case 10: GOTO_SCREEN(LevelingMenu); break; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp index 424e0afa76..b5ce108106 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -74,37 +74,37 @@ bool PreheatMenu::onTouchEnd(uint8_t tag) { case 1: GOTO_PREVIOUS(); break; case 2: #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 3: #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 4: #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 5: #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 6: #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 7: #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT)); + injectCommands(F(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index c7d0cc3f73..37eb29a99d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -174,11 +174,11 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { case 1: // On Cancel, reload saved mesh, discarding changes GOTO_PREVIOUS(); - injectCommands_P(PSTR("G29 L1")); + injectCommands(F("G29 L1")); return true; case 2: saveAdjustedHighlightedValue(); - injectCommands_P(PSTR("G29 S1")); + injectCommands(F("G29 S1")); mydata.needSave = false; return true; case 3: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 8db2d2ef70..7b4195ff5c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -154,11 +154,11 @@ void BedMeshViewScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI void BedMeshViewScreen::doProbe() { GOTO_SCREEN(BedMeshViewScreen); mydata.count = 0; - injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); + injectCommands(F(BED_LEVELING_COMMANDS)); } void BedMeshViewScreen::show() { - injectCommands_P(PSTR("G29 L1")); + injectCommands(F("G29 L1")); GOTO_SCREEN(BedMeshViewScreen); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp index 748cc1d7ef..5c43ed34ea 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/confirm_auto_calibration_dialog_box.cpp @@ -37,7 +37,7 @@ bool ConfirmAutoCalibrationDialogBox::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("G425")); + injectCommands(F("G425")); return true; default: return DialogBoxBaseClass::onTouchEnd(tag); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp index 8807480897..bcdcad17be 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -33,7 +33,7 @@ using namespace Theme; #define _USER_DESC(N) MAIN_MENU_ITEM_##N##_DESC #define _USER_GCODE(N) MAIN_MENU_ITEM_##N##_GCODE #define _USER_ITEM(N) .tag(_ITEM_TAG(N)).button(USER_ITEM_POS(N), _USER_DESC(N)) -#define _USER_ACTION(N) case _ITEM_TAG(N): injectCommands_P(PSTR(_USER_GCODE(N))); TERN_(USER_SCRIPT_RETURN, GOTO_SCREEN(StatusScreen)); break; +#define _USER_ACTION(N) case _ITEM_TAG(N): injectCommands(F(_USER_GCODE(N))); TERN_(USER_SCRIPT_RETURN, GOTO_SCREEN(StatusScreen)); break; void CustomUserMenus::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 05845a9755..11db21aca9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -125,11 +125,11 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { #if ENABLED(G26_MESH_VALIDATION) case 6: GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("G28\nM117 Heating...\nG26 R X0 Y0\nG27")); + injectCommands(F("G28\nM117 Heating...\nG26 R X0 Y0\nG27")); break; #endif #if ENABLED(BLTOUCH) - case 7: injectCommands_P(PSTR("M280 P0 S60")); break; + case 7: injectCommands(F("M280 P0 S60")); break; case 8: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index a6c39db796..6ccda405fc 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -106,10 +106,10 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: SpinnerDialogBox::enqueueAndWait(F("G28")); break; #if ENABLED(NOZZLE_CLEAN_FEATURE) - case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; + case 3: injectCommands(F("G12")); GOTO_SCREEN(StatusScreen); break; #endif case 4: GOTO_SCREEN(MoveAxisScreen); break; - case 5: injectCommands_P(PSTR("M84")); break; + case 5: injectCommands(F("M84")); break; case 6: GOTO_SCREEN(TemperatureScreen); break; case 7: GOTO_SCREEN(ChangeFilamentScreen); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp index 2dfd64fa5b..f82ba1d5c8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/restore_failsafe_dialog_box.cpp @@ -35,7 +35,7 @@ void RestoreFailsafeDialogBox::onRedraw(draw_mode_t) { bool RestoreFailsafeDialogBox::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - ExtUI::injectCommands_P(PSTR("M502")); + ExtUI::injectCommands(F("M502")); AlertDialogBox::show(GET_TEXT_F(MSG_EEPROM_RESET)); // Remove RestoreFailsafeDialogBox from the stack // so the alert box doesn't return to it. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp index 5d92052ace..496d004a20 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/save_settings_dialog_box.cpp @@ -38,7 +38,7 @@ bool SaveSettingsDialogBox::onTouchEnd(uint8_t tag) { needs_save = false; switch (tag) { case 1: - injectCommands_P(PSTR("M500")); + injectCommands(F("M500")); AlertDialogBox::show(GET_TEXT_F(MSG_EEPROM_SAVED)); // Remove SaveSettingsDialogBox from the stack // so the alert box doesn't return to me. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 2493de795a..3928bf3297 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -60,7 +60,7 @@ void SpinnerDialogBox::onRefresh() { void SpinnerDialogBox::onRedraw(draw_mode_t) { } -void SpinnerDialogBox::show(FSTR_P message) { +void SpinnerDialogBox::show(FSTR_P fstr) { CommandProcessor cmd; if (AT_SCREEN(SpinnerDialogBox)) cmd.stop().execute(); cmd.cmd(CMD_DLSTART) @@ -68,7 +68,7 @@ void SpinnerDialogBox::show(FSTR_P message) { .cmd(CLEAR(true,true,true)) .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,3), message, OPT_CENTER, font_large); + draw_text_box(cmd, BTN_POS(1,1), BTN_SIZE(2,3), fstr, OPT_CENTER, font_large); DLCache dlcache(SPINNER_CACHE); if (!dlcache.store(SPINNER_DL_SIZE)) { SERIAL_ECHO_MSG("CachedScreen::storeBackground() failed: not enough DL cache space"); @@ -86,14 +86,14 @@ void SpinnerDialogBox::hide() { GOTO_PREVIOUS(); } -void SpinnerDialogBox::enqueueAndWait(FSTR_P message, FSTR_P commands) { - show(message); - ExtUI::injectCommands_P((const char*)commands); +void SpinnerDialogBox::enqueueAndWait(FSTR_P fstr, FSTR_P commands) { + show(fstr); + ExtUI::injectCommands(commands); mydata.auto_hide = true; } -void SpinnerDialogBox::enqueueAndWait(FSTR_P message, char *commands) { - show(message); +void SpinnerDialogBox::enqueueAndWait(FSTR_P fstr, char *commands) { + show(fstr); ExtUI::injectCommands(commands); mydata.auto_hide = true; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp index ab1f96a399..ea4b872303 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/stress_test_screen.cpp @@ -84,7 +84,7 @@ void StressTestScreen::runTestOnBootup(bool enable) { // whether or not we need to re-run the test // at startup. LockScreen::set_hash(enable ? 0xDEAD : 0); - injectCommands_P(PSTR("M500")); + injectCommands(F("M500")); } void StressTestScreen::startupCheck() { @@ -122,7 +122,7 @@ void StressTestScreen::onIdle() { injectCommands_P(G28_STR); } else { - injectCommands_P(PSTR( + injectCommands(F( "G0 X100 Y100 Z100 F6000\n" "T0\nG4 S1" E_TERN_("\nT1\nG4 S1") diff --git a/Marlin/src/lcd/extui/nextion/FileNavigator.cpp b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp index 07f1256ded..6730370a94 100644 --- a/Marlin/src/lcd/extui/nextion/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/nextion/FileNavigator.cpp @@ -83,46 +83,46 @@ void FileNavigator::getFiles(uint16_t index) { #endif if (currentindex == 0 && folderdepth > 0) { // Add a link to go up a folder - nextion.SendtoTFT(PSTR("vis p0,1")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("vis p0,1")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); SEND_VAL("tmpUP", "0"); files--; } else { - nextion.SendtoTFT(PSTR("vis p0,0")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("vis p0,0")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); } for (uint16_t seek = currentindex; seek < currentindex + files; seek++) { if (filelist.seek(seek)) { - nextion.SendtoTFT(PSTR("s")); + nextion.SendtoTFT(F("s")); LCD_SERIAL.print(fcnt); - nextion.SendtoTFT(PSTR(".txt=\"")); + nextion.SendtoTFT(F(".txt=\"")); if (filelist.isDir()) { LCD_SERIAL.print(filelist.shortFilename()); - nextion.SendtoTFT(PSTR("/\"")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("/\"")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); - nextion.SendtoTFT(PSTR("l")); + nextion.SendtoTFT(F("l")); LCD_SERIAL.print(fcnt); - nextion.SendtoTFT(PSTR(".txt=\"")); + nextion.SendtoTFT(F(".txt=\"")); LCD_SERIAL.print(filelist.filename()); - nextion.SendtoTFT(PSTR("\"")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("\"")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); SEND_PCO2("l", fcnt, "1055"); } else { LCD_SERIAL.print(currentfoldername); LCD_SERIAL.print(filelist.shortFilename()); - nextion.SendtoTFT(PSTR("\"")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("\"")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); - nextion.SendtoTFT(PSTR("l")); + nextion.SendtoTFT(F("l")); LCD_SERIAL.print(fcnt); - nextion.SendtoTFT(PSTR(".txt=\"")); + nextion.SendtoTFT(F(".txt=\"")); LCD_SERIAL.print(filelist.longFilename()); - nextion.SendtoTFT(PSTR("\"")); - nextion.SendtoTFT(PSTR("\xFF\xFF\xFF")); + nextion.SendtoTFT(F("\"")); + nextion.SendtoTFT(F("\xFF\xFF\xFF")); } fcnt++; fseek = seek; diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index c4e0e66a39..64e909779d 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -110,12 +110,12 @@ void NextionTFT::StatusChange(const char * const msg) { SEND_VALasTXT("tmppage.M117", msg); } -void NextionTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEM string to the panel +void NextionTFT::SendtoTFT(FSTR_P fstr) { // A helper to print PROGMEM string to the panel #if NEXDEBUG(N_SOME) - DEBUG_ECHOPGM_P(str); + DEBUG_ECHOF(fstr); #endif - while (const char c = pgm_read_byte(str++)) - LCD_SERIAL.write(c); + PGM_P str = FTOP(fstr); + while (const char c = pgm_read_byte(str++)) LCD_SERIAL.write(c); } bool NextionTFT::ReadTFTCommand() { @@ -522,7 +522,7 @@ void NextionTFT::PanelAction(uint8_t req) { case 66: // Refresh SD if (!isPrinting()) { - injectCommands_P(PSTR("M21")); + injectCommands(F("M21")); filenavigator.reset(); } break; @@ -546,8 +546,8 @@ void NextionTFT::PanelAction(uint8_t req) { #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) if (canMove(getActiveTool())) { switch (nextion_command[4]) { - case 'L': injectCommands_P(PSTR("M701")); break; - case 'U': injectCommands_P(PSTR("M702")); break; + case 'L': injectCommands(F("M701")); break; + case 'U': injectCommands(F("M702")); break; } } else { diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.h b/Marlin/src/lcd/extui/nextion/nextion_tft.h index 4eb5fbe0b7..f32e5d4ef1 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.h @@ -43,9 +43,9 @@ class NextionTFT { static void Startup(); static void IdleLoop(); static void PrinterKilled(PGM_P, PGM_P); - static void ConfirmationRequest(const char * const ); - static void StatusChange(const char * const ); - static void SendtoTFT(PGM_P); + static void ConfirmationRequest(const char * const); + static void StatusChange(const char * const); + static void SendtoTFT(FSTR_P const); static void UpdateOnChange(); static void PrintFinished(); static void PanelInfo(uint8_t); diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h index 32d3ea3295..4570e9bba4 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h @@ -54,10 +54,10 @@ // TFT panel commands #define msg_welcome MACHINE_NAME " Ready." -#define SEND_TEMP(x,y,t,z) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR(t)), LCD_SERIAL.print(z), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) -#define SEND_VAL(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".val=")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) -#define SEND_TXT(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), nextion.SendtoTFT(PSTR(y)), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) -#define SEND_TXT_P(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), nextion.SendtoTFT(y), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) -#define SEND_VALasTXT(x,y) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR("\"\xFF\xFF\xFF"))) -#define SEND_TXT_END(x) (nextion.SendtoTFT(PSTR(x)), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) -#define SEND_PCO2(x,y,z) (nextion.SendtoTFT(PSTR(x)), LCD_SERIAL.print(y), nextion.SendtoTFT(PSTR(".pco=")), nextion.SendtoTFT(PSTR(z)), nextion.SendtoTFT(PSTR("\xFF\xFF\xFF"))) +#define SEND_TEMP(x,y,t,z) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(F(t)), LCD_SERIAL.print(z), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_VAL(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".val=")), LCD_SERIAL.print(y), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) +#define SEND_TXT(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(F(y)), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_TXT_P(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(y), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_VALasTXT(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_TXT_END(x) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) +#define SEND_PCO2(x,y,z) (nextion.SendtoTFT(F(x)), LCD_SERIAL.print(y), nextion.SendtoTFT(F(".pco=")), nextion.SendtoTFT(F(z)), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index d37b277110..afd762a470 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1077,15 +1077,15 @@ namespace ExtUI { void resumePrint() { ui.resume_print(); } void stopPrint() { ui.abort_print(); } - void onUserConfirmRequired_P(PGM_P const pstr) { - char msg[strlen_P(pstr) + 1]; - strcpy_P(msg, pstr); + void onUserConfirmRequired(FSTR_P const fstr) { + char msg[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(msg, FTOP(fstr)); onUserConfirmRequired(msg); } - void onStatusChanged_P(PGM_P const pstr) { - char msg[strlen_P(pstr) + 1]; - strcpy_P(msg, pstr); + void onStatusChanged(FSTR_P const fstr) { + char msg[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(msg, FTOP(fstr)); onStatusChanged(msg); } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 9e1ae3a9c0..4866c5b9d7 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -79,6 +79,7 @@ namespace ExtUI { bool canMove(const axis_t); bool canMove(const extruder_t); void injectCommands_P(PGM_P const); + inline void injectCommands(FSTR_P const fstr) { injectCommands_P(FTOP(fstr)); } void injectCommands(char * const); bool commandsInQueue(); @@ -400,9 +401,9 @@ namespace ExtUI { void onPrintFinished(); void onFilamentRunout(const extruder_t extruder); void onUserConfirmRequired(const char * const msg); - void onUserConfirmRequired_P(PGM_P const pstr); + void onUserConfirmRequired(FSTR_P const fstr); void onStatusChanged(const char * const msg); - void onStatusChanged_P(PGM_P const pstr); + void onStatusChanged(FSTR_P const fstr); void onHomingStart(); void onHomingComplete(); void onSteppersDisabled(); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index c18a7d46f4..1fec14228b 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1741,18 +1741,18 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; pause_mode = mode; ExtUI::pauseModeStatus = message; switch (message) { - case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PAUSE_PRINT_PARKING)); - case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INIT)); - case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_UNLOAD)); - case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_ADVANCED_PAUSE_WAITING)); - case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_INSERT)); - case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_LOAD)); + case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); + case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); + case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); + case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING)); + case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); + case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); case PAUSE_MESSAGE_PURGE: - ExtUI::onUserConfirmRequired_P(GET_TEXT(TERN(ADVANCED_PAUSE_CONTINUOUS_PURGE, MSG_FILAMENT_CHANGE_CONT_PURGE, MSG_FILAMENT_CHANGE_PURGE))); - case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_RESUME)); - case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEAT)); - case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_HEATING)); - case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_FILAMENT_CHANGE_OPTION_HEADER)); + ExtUI::onUserConfirmRequired(GET_TEXT_F(TERN(ADVANCED_PAUSE_CONTINUOUS_PURGE, MSG_FILAMENT_CHANGE_CONT_PURGE, MSG_FILAMENT_CHANGE_PURGE))); + case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); + case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT)); + case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEATING)); + case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_OPTION_HEADER)); case PAUSE_MESSAGE_STATUS: default: break; } diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 0990ac504d..95103e9bf6 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -65,7 +65,7 @@ void _man_probe_pt(const xy_pos_t &xy) { _man_probe_pt(xy); ui.defer_status_screen(); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Delta Calibration in progress"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Delta Calibration in progress"))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.goto_previous_screen_no_defer(); return current_position.z; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 18e72f401c..f37d2aa03f 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -296,7 +296,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { SERIAL_ECHOLNF(ds_str); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Stow Probe"), FPSTR(CONTINUE_STR))); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe"))); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Stow Probe"))); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, PSTR("Stow Probe"), CONTINUE_STR)); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); From eeffac697c5d7b69e01e38ed1602dbd21a366e93 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Sep 2021 23:52:41 -0500 Subject: [PATCH 0759/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20UTF?= =?UTF-8?q?-8/MMU2=20string=20put?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/progmem.h | 2 +- Marlin/src/feature/mmu/mmu2.cpp | 48 ++++++++++--------- Marlin/src/feature/mmu/mmu2.h | 8 ++-- Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp | 4 +- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 45 ++++++++--------- Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp | 4 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 42 ++++++++-------- Marlin/src/lcd/dogm/lcdprint_u8g.cpp | 4 +- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 10 ++-- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 14 +++--- .../lcd/dogm/status_screen_lite_ST7920.cpp | 12 ++--- .../src/lcd/dogm/status_screen_lite_ST7920.h | 2 +- .../src/lcd/e3v2/marlinui/lcdprint_dwin.cpp | 4 +- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 4 +- Marlin/src/lcd/lcdprint.h | 23 ++++++--- Marlin/src/lcd/menu/game/game.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 4 +- Marlin/src/lcd/menu/menu_mixer.cpp | 4 +- Marlin/src/lcd/menu/menu_tune.cpp | 4 +- Marlin/src/lcd/tft/ui_common.cpp | 4 +- 20 files changed, 129 insertions(+), 115 deletions(-) diff --git a/Marlin/src/HAL/shared/progmem.h b/Marlin/src/HAL/shared/progmem.h index a76b379bb8..4cd7663df9 100644 --- a/Marlin/src/HAL/shared/progmem.h +++ b/Marlin/src/HAL/shared/progmem.h @@ -111,7 +111,7 @@ class __FlashStringHelper; #define strrchr_P(str, c) strrchr((str), (c)) #endif #ifndef strsep_P -#define strsep_P(strp, delim) strsep((strp), (delim)) +#define strsep_P(pstr, delim) strsep((pstr), (delim)) #endif #ifndef strspn_P #define strspn_P(str, chrs) strspn((str), (chrs)) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 363e4d5505..b2835dc3ce 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -54,7 +54,7 @@ MMU2 mmu2; #define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) #define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds -#define MMU2_COMMAND(S) tx_str_P(PSTR(S "\n")) +#define MMU2_COMMAND(S) tx_str(F(S "\n")) #if ENABLED(MMU_EXTRUDER_SENSOR) uint8_t mmu_idl_sens = 0; @@ -229,17 +229,17 @@ void MMU2::mmu_loop() { if (cmd) { if (WITHIN(cmd, MMU_CMD_T0, MMU_CMD_T0 + EXTRUDERS - 1)) { // tool change - int filament = cmd - MMU_CMD_T0; + const int filament = cmd - MMU_CMD_T0; DEBUG_ECHOLNPGM("MMU <= T", filament); - tx_printf_P(PSTR("T%d\n"), filament); + tx_printf(F("T%d\n"), filament); TERN_(MMU_EXTRUDER_SENSOR, mmu_idl_sens = 1); // enable idler sensor, if any state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_L0, MMU_CMD_L0 + EXTRUDERS - 1)) { // load - int filament = cmd - MMU_CMD_L0; + const int filament = cmd - MMU_CMD_L0; DEBUG_ECHOLNPGM("MMU <= L", filament); - tx_printf_P(PSTR("L%d\n"), filament); + tx_printf(F("L%d\n"), filament); state = 3; // wait for response } else if (cmd == MMU_CMD_C0) { @@ -257,9 +257,9 @@ void MMU2::mmu_loop() { } else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E0 + EXTRUDERS - 1)) { // eject filament - int filament = cmd - MMU_CMD_E0; + const int filament = cmd - MMU_CMD_E0; DEBUG_ECHOLNPGM("MMU <= E", filament); - tx_printf_P(PSTR("E%d\n"), filament); + tx_printf(F("E%d\n"), filament); state = 3; // wait for response } else if (cmd == MMU_CMD_R0) { @@ -270,9 +270,9 @@ void MMU2::mmu_loop() { } else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F0 + EXTRUDERS - 1)) { // filament type - int filament = cmd - MMU_CMD_F0; + const int filament = cmd - MMU_CMD_F0; DEBUG_ECHOLNPGM("MMU <= F", filament, " ", cmd_arg); - tx_printf_P(PSTR("F%d %d\n"), filament, cmd_arg); + tx_printf(F("F%d %d\n"), filament, cmd_arg); state = 3; // wait for response } @@ -356,13 +356,15 @@ void MMU2::mmu_loop() { */ bool MMU2::rx_start() { // check for start message - return rx_str_P(PSTR("start\n")); + return rx_str(F("start\n")); } /** * Check if the data received ends with the given string. */ -bool MMU2::rx_str_P(const char *str) { +bool MMU2::rx_str(FSTR_P fstr) { + PGM_P pstr = FTOP(fstr); + uint8_t i = strlen(rx_buffer); while (MMU2_SERIAL.available()) { @@ -375,14 +377,14 @@ bool MMU2::rx_str_P(const char *str) { } rx_buffer[i] = '\0'; - uint8_t len = strlen_P(str); + uint8_t len = strlen_P(pstr); if (i < len) return false; - str += len; + pstr += len; while (len--) { - char c0 = pgm_read_byte(str--), c1 = rx_buffer[i--]; + char c0 = pgm_read_byte(pstr--), c1 = rx_buffer[i--]; if (c0 == c1) continue; if (c0 == '\r' && c1 == '\n') continue; // match cr as lf if (c0 == '\n' && c1 == '\r') continue; // match lf as cr @@ -394,19 +396,19 @@ bool MMU2::rx_str_P(const char *str) { /** * Transfer data to MMU, no argument */ -void MMU2::tx_str_P(const char *str) { +void MMU2::tx_str(FSTR_P fstr) { clear_rx_buffer(); - uint8_t len = strlen_P(str); - LOOP_L_N(i, len) MMU2_SERIAL.write(pgm_read_byte(str++)); + PGM_P pstr = FTOP(fstr); + while (const char c = pgm_read_byte(pstr)) { MMU2_SERIAL.write(c); pstr++; } prev_request = millis(); } /** * Transfer data to MMU, single argument */ -void MMU2::tx_printf_P(const char *format, int argument = -1) { +void MMU2::tx_printf(FSTR_P format, int argument = -1) { clear_rx_buffer(); - uint8_t len = sprintf_P(tx_buffer, format, argument); + const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument); LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -414,9 +416,9 @@ void MMU2::tx_printf_P(const char *format, int argument = -1) { /** * Transfer data to MMU, two arguments */ -void MMU2::tx_printf_P(const char *format, int argument1, int argument2) { +void MMU2::tx_printf(FSTR_P format, int argument1, int argument2) { clear_rx_buffer(); - uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2); + const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument1, argument2); LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -433,7 +435,7 @@ void MMU2::clear_rx_buffer() { * Check if we received 'ok' from MMU */ bool MMU2::rx_ok() { - if (rx_str_P(PSTR("ok\n"))) { + if (rx_str(F("ok\n"))) { prev_P0_request = millis(); return true; } @@ -853,7 +855,7 @@ void MMU2::filament_runout() { if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) { if (present && !mmu2s_triggered) { DEBUG_ECHOLNPGM("MMU <= 'A'"); - tx_str_P(PSTR("A\n")); + tx_str(F("A\n")); } // Slowly spin the extruder during C0 else { diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 95338a5184..9574e2217f 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -57,10 +57,10 @@ public: static bool eject_filament(const uint8_t index, const bool recover); private: - static bool rx_str_P(const char *str); - static void tx_str_P(const char *str); - static void tx_printf_P(const char *format, const int argument); - static void tx_printf_P(const char *format, const int argument1, const int argument2); + static inline bool rx_str(FSTR_P fstr); + static inline void tx_str(FSTR_P fstr); + static inline void tx_printf(FSTR_P ffmt, const int argument); + static inline void tx_printf(FSTR_P ffmt, const int argument1, const int argument2); static void clear_rx_buffer(); static bool rx_ok(); diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 19e3814a6f..31b26aa5bb 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -1063,8 +1063,8 @@ int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { - return lcd_put_u8str_max_cb(utf8_str_P, read_byte_rom, max_length); +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } #if ENABLED(DEBUG_LCDPRINT) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index f4d765e2d3..b450c9c10f 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -409,15 +409,15 @@ void MarlinUI::clear_lcd() { lcd.clear(); } } // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line - void lcd_scroll(const lcd_uint_t col, const lcd_uint_t line, PGM_P const text, const uint8_t len, const int16_t time) { - uint8_t slen = utf8_strlen_P(text); + void lcd_scroll(const lcd_uint_t col, const lcd_uint_t line, FSTR_P const ftxt, const uint8_t len, const int16_t time) { + uint8_t slen = utf8_strlen_P(FTOP(ftxt)); if (slen < len) { - lcd_put_u8str_max_P(col, line, text, len); + lcd_put_u8str_max(col, line, ftxt, len); for (; slen < len; ++slen) lcd_put_wchar(' '); safe_delay(time); } else { - PGM_P p = text; + PGM_P p = FTOP(ftxt); int dly = time / _MAX(slen, 1); LOOP_LE_N(i, slen) { @@ -439,9 +439,9 @@ void MarlinUI::clear_lcd() { lcd.clear(); } static void logo_lines(PGM_P const extra) { int16_t indent = (LCD_WIDTH - 8 - utf8_strlen_P(extra)) / 2; - lcd_put_wchar(indent, 0, '\x00'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x01'); - lcd_put_u8str_P(indent, 1, PSTR("|Marlin|")); lcd_put_u8str_P(extra); - lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str_P(PSTR( "------" )); lcd_put_wchar('\x03'); + lcd_put_wchar(indent, 0, '\x00'); lcd_put_u8str(F( "------" )); lcd_put_wchar('\x01'); + lcd_put_u8str(indent, 1, F("|Marlin|")); lcd_put_u8str_P(extra); + lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str(F( "------" )); lcd_put_wchar('\x03'); } void MarlinUI::show_bootscreen() { @@ -450,15 +450,16 @@ void MarlinUI::clear_lcd() { lcd.clear(); } #define LCD_EXTRA_SPACE (LCD_WIDTH-8) - #define CENTER_OR_SCROLL(STRING,DELAY) \ + #define CENTER_OR_SCROLL(STRING,DELAY) { \ lcd_erase_line(3); \ - if (utf8_strlen(STRING) <= LCD_WIDTH) { \ - lcd_put_u8str_P((LCD_WIDTH - utf8_strlen_P(PSTR(STRING))) / 2, 3, PSTR(STRING)); \ + const int len = utf8_strlen(STRING); \ + if (len <= LCD_WIDTH) { \ + lcd_put_u8str((LCD_WIDTH - len) / 2, 3, F(STRING)); \ safe_delay(DELAY); \ } \ - else { \ - lcd_scroll(0, 3, PSTR(STRING), LCD_WIDTH, DELAY); \ - } + else \ + lcd_scroll(0, 3, F(STRING), LCD_WIDTH, DELAY); \ + } // // Show the Marlin logo with splash line 1 @@ -497,9 +498,9 @@ void MarlinUI::draw_kill_screen() { lcd_put_u8str(0, 0, status_message); lcd_uint_t y = 2; #if LCD_HEIGHT >= 4 - lcd_put_u8str_P(0, y++, GET_TEXT(MSG_HALTED)); + lcd_put_u8str(0, y++, GET_TEXT_F(MSG_HALTED)); #endif - lcd_put_u8str_P(0, y, GET_TEXT(MSG_PLEASE_RESET)); + lcd_put_u8str(0, y, GET_TEXT_F(MSG_PLEASE_RESET)); } // @@ -514,7 +515,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const else if (axis_should_home(axis)) while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); else lcd_put_u8str(value); } @@ -613,11 +614,11 @@ FORCE_INLINE void _draw_bed_status(const bool blink) { FORCE_INLINE void _draw_print_progress() { const uint8_t progress = ui.get_progress_percent(); - lcd_put_u8str_P(PSTR(TERN(SDSUPPORT, "SD", "P:"))); + lcd_put_u8str(F(TERN(SDSUPPORT, "SD", "P:"))); if (progress) lcd_put_u8str(ui8tostr3rj(progress)); else - lcd_put_u8str_P(PSTR("---")); + lcd_put_u8str(F("---")); lcd_put_wchar('%'); } @@ -661,9 +662,9 @@ void MarlinUI::draw_status_message(const bool blink) { // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { - lcd_put_u8str_P(PSTR("Dia ")); + lcd_put_u8str(F("Dia ")); lcd_put_u8str(ftostr12ns(filwidth.measured_mm)); - lcd_put_u8str_P(PSTR(" V")); + lcd_put_u8str(F(" V")); lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); lcd_put_wchar('%'); return; @@ -1473,7 +1474,7 @@ void MarlinUI::draw_status_screen() { if (!isnan(ubl.z_values[x_plot][y_plot])) lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); else - lcd_put_u8str_P(PSTR(" -----")); + lcd_put_u8str(F(" -----")); #else // 16x4 or 20x4 display @@ -1492,7 +1493,7 @@ void MarlinUI::draw_status_screen() { if (!isnan(ubl.z_values[x_plot][y_plot])) lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); else - lcd_put_u8str_P(PSTR(" -----")); + lcd_put_u8str(F(" -----")); #endif // LCD_HEIGHT > 3 } diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp index dddab1f259..106ce76138 100644 --- a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -1061,8 +1061,8 @@ int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { - return lcd_put_u8str_max_cb(utf8_str_P, read_byte_rom, max_length); +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } #if ENABLED(DEBUG_LCDPRINT) diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 9617b3775d..420bd7cd66 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -399,9 +399,9 @@ static void center_text_P(PGM_P pstart, uint8_t y) { uint8_t indent = (LCD_WIDTH - 8) / 2; // symbols 217 (bottom right corner) and 218 (top left corner) are using for letters in some languages // and they should be moved to beginning ASCII table as special symbols - lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str_P(PSTR("------")); lcd.write(TRC); - lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str_P(PSTR("Marlin")); lcd.write(LR); - lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str_P(PSTR("------")); lcd.write(BRC); + lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str(F("------")); lcd.write(TRC); + lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str(F("Marlin")); lcd.write(LR); + lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str(F("------")); lcd.write(BRC); center_text_P(PSTR(SHORT_BUILD_VERSION), 3); center_text_P(PSTR(MARLIN_WEBSITE_URL), 4); picBits = ICON_LOGO; @@ -437,7 +437,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const else if (axis_should_home(axis)) while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); else lcd_put_u8str(value); } @@ -515,7 +515,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const FORCE_INLINE void _draw_cooler_status(const bool blink) { const celsius_t t2 = thermalManager.degTargetCooler(); - lcd.setCursor(0, 5); lcd_put_u8str_P(PSTR("COOL")); + lcd.setCursor(0, 5); lcd_put_u8str(F("COOL")); lcd.setCursor(1, 6); lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler())); lcd.setCursor(1, 7); @@ -543,7 +543,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(LASER_COOLANT_FLOW_METER) FORCE_INLINE void _draw_flowmeter_status() { - lcd.setCursor(5, 5); lcd_put_u8str_P(PSTR("FLOW")); + lcd.setCursor(5, 5); lcd_put_u8str(F("FLOW")); lcd.setCursor(7, 6); lcd_put_wchar('L'); lcd.setCursor(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate)); @@ -556,7 +556,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(I2C_AMMETER) FORCE_INLINE void _draw_ammeter_status() { - lcd.setCursor(10, 5); lcd_put_u8str_P(PSTR("ILAZ")); + lcd.setCursor(10, 5); lcd_put_u8str(F("ILAZ")); ammeter.read(); lcd.setCursor(11, 6); if (ammeter.current <= 0.999f) @@ -580,9 +580,9 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if HAS_CUTTER FORCE_INLINE void _draw_cutter_status() { - lcd.setCursor(15, 5); lcd_put_u8str_P(PSTR("CUTT")); + lcd.setCursor(15, 5); lcd_put_u8str(F("CUTT")); #if CUTTER_UNIT_IS(RPM) - lcd.setCursor(16, 6); lcd_put_u8str_P(PSTR("RPM")); + lcd.setCursor(16, 6); lcd_put_u8str(F("RPM")); lcd.setCursor(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000)); lcd_put_wchar('K'); #elif CUTTER_UNIT_IS(PERCENT) @@ -604,14 +604,14 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const if (!PanelDetected) return; const uint8_t progress = ui._get_progress(); #if ENABLED(SDSUPPORT) - lcd_put_u8str_P(PSTR("SD")); + lcd_put_u8str(F("SD")); #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - lcd_put_u8str_P(PSTR("P:")); + lcd_put_u8str(F("P:")); #endif if (progress) lcd.print(ui8tostr3rj(progress)); else - lcd_put_u8str_P(PSTR("---")); + lcd_put_u8str(F("---")); lcd.write('%'); } @@ -643,9 +643,9 @@ void MarlinUI::draw_status_message(const bool blink) { // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { - lcd_put_u8str_P(PSTR("Dia ")); + lcd_put_u8str(F("Dia ")); lcd.print(ftostr12ns(filament_width_meas)); - lcd_put_u8str_P(PSTR(" V")); + lcd_put_u8str(F(" V")); lcd.print(i16tostr3rj(100.0 * ( parser.volumetric_enabled ? planner.volumetric_area_nominal / planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] @@ -802,7 +802,7 @@ void MarlinUI::draw_status_screen() { // lcd.setCursor(0, 1); - lcd_put_u8str_P(PSTR("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); + lcd_put_u8str(F("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); #if BOTH(SDSUPPORT, HAS_PRINT_PROGRESS) lcd.setCursor(LCD_WIDTH / 2 - 3, 1); @@ -895,7 +895,7 @@ void MarlinUI::draw_status_screen() { #else #define FANX 17 #endif - lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); + lcd.setCursor(FANX, 5); lcd_put_u8str(F("FAN")); lcd.setCursor(FANX + 1, 6); lcd.write('%'); lcd.setCursor(FANX, 7); lcd.print(i16tostr3rj(per)); @@ -931,7 +931,7 @@ void MarlinUI::draw_status_screen() { void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { if (!PanelDetected) return; lcd.setCursor((LCD_WIDTH - 14) / 2, row + 1); - lcd.write(LCD_STR_THERMOMETER[0]); lcd_put_u8str_P(PSTR(" E")); lcd.write('1' + extruder); lcd.write(' '); + lcd.write(LCD_STR_THERMOMETER[0]); lcd_put_u8str(F(" E")); lcd.write('1' + extruder); lcd.write(' '); lcd.print(i16tostr3rj(thermalManager.wholeDegHotend(extruder))); lcd.write(LCD_STR_DEGREE[0]); lcd.write('/'); lcd.print(i16tostr3rj(thermalManager.degTargetHotend(extruder))); lcd.write(LCD_STR_DEGREE[0]); lcd.print_line(); @@ -1064,18 +1064,18 @@ void MarlinUI::draw_status_screen() { *fb++ = ','; lcd.print(i16tostr3left(y_plot)); *fb = ')'; // Show all values - lcd.setCursor(_LCD_W_POS, 1); lcd_put_u8str_P(PSTR("X:")); + lcd.setCursor(_LCD_W_POS, 1); lcd_put_u8str(F("X:")); lcd.print(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - lcd.setCursor(_LCD_W_POS, 2); lcd_put_u8str_P(PSTR("Y:")); + lcd.setCursor(_LCD_W_POS, 2); lcd_put_u8str(F("Y:")); lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); // Show the location value - lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str_P(PSTR("Z:")); + lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str(F("Z:")); if (!isnan(ubl.z_values[x_plot][y_plot])) lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); else - lcd_put_u8str_P(PSTR(" -----")); + lcd_put_u8str(F(" -----")); center_text_P(GET_TEXT(MSG_UBL_FINE_TUNE_MESH), 8); diff --git a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index a85dc9f979..f74a59a08c 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -46,9 +46,9 @@ int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { return ret; } -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), - ret = uxg_DrawUtf8StrP(u8g.getU8g(), x, y, utf8_str_P, max_length); + ret = uxg_DrawUtf8StrP(u8g.getU8g(), x, y, utf8_pstr, max_length); u8g.setPrintPos(x + ret, y); return ret; } diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 4a7e26ae83..5d4c30bbb4 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -217,8 +217,8 @@ bool MarlinUI::detected() { return true; } auto _draw_bootscreen_bmp = [&](const uint8_t *bitmap) { u8g.drawBitmapP(offx, offy, START_BMP_BYTEWIDTH, START_BMPHEIGHT, bitmap); set_font(FONT_MENU); - if (!two_part || !line2) lcd_put_u8str_P(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), PSTR(SHORT_BUILD_VERSION)); - if (!two_part || line2) lcd_put_u8str_P(txt_offx_2, txt_base, PSTR(MARLIN_WEBSITE_URL)); + if (!two_part || !line2) lcd_put_u8str(txt_offx_1, txt_base - (MENU_FONT_HEIGHT), F(SHORT_BUILD_VERSION)); + if (!two_part || line2) lcd_put_u8str(txt_offx_2, txt_base, F(MARLIN_WEBSITE_URL)); }; auto draw_bootscreen_bmp = [&](const uint8_t *bitmap) { @@ -331,8 +331,8 @@ void MarlinUI::draw_kill_screen() { do { set_font(FONT_MENU); lcd_put_u8str(0, h4 * 1, status_message); - lcd_put_u8str_P(0, h4 * 2, GET_TEXT(MSG_HALTED)); - lcd_put_u8str_P(0, h4 * 3, GET_TEXT(MSG_PLEASE_RESET)); + lcd_put_u8str(0, h4 * 2, GET_TEXT_F(MSG_HALTED)); + lcd_put_u8str(0, h4 * 3, GET_TEXT_F(MSG_PLEASE_RESET)); } while (u8g.nextPage()); } @@ -611,7 +611,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (!isnan(ubl.z_values[x_plot][y_plot])) lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); else - lcd_put_u8str_P(PSTR(" -----")); + lcd_put_u8str(F(" -----")); } } diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 8b707ba7c7..847c13d3ac 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -191,7 +191,7 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, const uint8_t ty) { if (temp < 0) - lcd_put_u8str(tx - 3 * (INFO_FONT_WIDTH) / 2 + 1, ty, "err"); + lcd_put_u8str(tx - 3 * (INFO_FONT_WIDTH) / 2 + 1, ty, F("err")); else { const char *str = i16tostr3rj(temp); const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; @@ -436,7 +436,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const else if (axis_should_home(axis)) while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); else lcd_put_u8str(value); } @@ -777,7 +777,7 @@ void MarlinUI::draw_status_screen() { } } else if (progress_state == 2 && estimation_string[0]) { - lcd_put_u8str_P(PROGRESS_BAR_X, EXTRAS_BASELINE, PSTR("R:")); + lcd_put_u8str(PROGRESS_BAR_X, EXTRAS_BASELINE, F("R:")); lcd_put_u8str(estimation_x_pos, EXTRAS_BASELINE, estimation_string); } else if (elapsed_string[0]) { @@ -879,7 +879,7 @@ void MarlinUI::draw_status_screen() { if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) _draw_axis_value(E_AXIS, xstring, true); - lcd_put_u8str_P(PSTR(" ")); + lcd_put_u8str(F(" ")); #endif } else { @@ -918,7 +918,7 @@ void MarlinUI::draw_status_screen() { lcd_put_u8str(102, EXTRAS_2_BASELINE, mstring); lcd_put_wchar('%'); set_font(FONT_MENU); - lcd_put_wchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str_P(PSTR(LCD_STR_FILAM_DIA)); + lcd_put_wchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str(F(LCD_STR_FILAM_DIA)); lcd_put_wchar(93, EXTRAS_2_BASELINE, LCD_STR_FILAM_MUL[0]); #endif } @@ -932,10 +932,10 @@ void MarlinUI::draw_status_screen() { #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { - lcd_put_u8str_P(PSTR(LCD_STR_FILAM_DIA)); + lcd_put_u8str(F(LCD_STR_FILAM_DIA)); lcd_put_wchar(':'); lcd_put_u8str(wstring); - lcd_put_u8str_P(PSTR(" " LCD_STR_FILAM_MUL)); + lcd_put_u8str(F(" " LCD_STR_FILAM_MUL)); lcd_put_wchar(':'); lcd_put_u8str(mstring); 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 be112c8d54..2e6d697488 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -99,9 +99,9 @@ void ST7920_Lite_Status_Screen::write_str(const char *str, uint8_t len) { while (*str && len--) write_byte(*str++); } -void ST7920_Lite_Status_Screen::write_str_P(PGM_P const str) { - PGM_P p_str = (PGM_P)str; - while (char c = pgm_read_byte(p_str++)) write_byte(c); +void ST7920_Lite_Status_Screen::write_str(FSTR_P const fstr) { + PGM_P pstr = FTOP(fstr); + while (char c = pgm_read_byte(pstr++)) write_byte(c); } void ST7920_Lite_Status_Screen::write_number(const int16_t value, const uint8_t digits/*=3*/) { @@ -500,11 +500,11 @@ void ST7920_Lite_Status_Screen::draw_progress_bar(const uint8_t value) { // Draw centered if (value > 9) { write_number(value, 4); - write_str_P(PSTR("% ")); + write_str(F("% ")); } else { write_number(value, 3); - write_str_P(PSTR("% ")); + write_str(F("% ")); } } @@ -559,7 +559,7 @@ void ST7920_Lite_Status_Screen::draw_temps(uint8_t line, const int16_t temp, con }; if (targetStateChange) { - if (!showTarget) write_str_P(PSTR(" ")); + if (!showTarget) write_str(F(" ")); draw_degree_symbol(5, line, !showTarget); draw_degree_symbol(9, line, showTarget); } diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h index b217246484..7fe878356b 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h @@ -46,7 +46,7 @@ class ST7920_Lite_Status_Screen { static void write_str(const char *str); static void write_str(const char *str, const uint8_t len); - static void write_str_P(PGM_P const str); + static void write_str(FSTR_P const fstr); static void write_number(const int16_t value, const uint8_t digits=3); static void _extended_function_set(const bool extended, const bool graphics); diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp index 069272f6c1..5f62459534 100644 --- a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp @@ -101,8 +101,8 @@ int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { - return lcd_put_u8str_max_cb(utf8_str_P, read_byte_rom, max_length); +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 9ad258b3ac..8648401c9c 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -160,11 +160,11 @@ void MarlinUI::draw_kill_screen() { slen = utf8_strlen(S(GET_TEXT_F(MSG_HALTED))); lcd_moveto(cx - (slen / 2), cy); - lcd_put_u8str_P((const char*)GET_TEXT_F(MSG_HALTED)); + lcd_put_u8str(GET_TEXT_F(MSG_HALTED)); slen = utf8_strlen(S(GET_TEXT_F(MSG_HALTED))); lcd_moveto(cx - (slen / 2), cy + 1); - lcd_put_u8str_P((const char*)GET_TEXT_F(MSG_HALTED)); + lcd_put_u8str(GET_TEXT_F(MSG_HALTED)); } // diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index f6ac818ae5..c701a59568 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -152,17 +152,20 @@ void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row); /** * @brief Draw a ROM UTF-8 string * - * @param utf8_str_P : the ROM UTF-8 string + * @param utf8_pstr : the ROM UTF-8 string * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) * * @return the pixel width * * Draw a ROM UTF-8 string */ -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length); -inline int lcd_put_u8str_max_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P utf8_str_P, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length); +inline int lcd_put_u8str_max_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P utf8_pstr, pixel_len_t max_length) { lcd_moveto(col, row); - return lcd_put_u8str_max_P(utf8_str_P, max_length); + return lcd_put_u8str_max_P(utf8_pstr, max_length); +} +inline int lcd_put_u8str_max(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const utf8_fstr, pixel_len_t max_length) { + return lcd_put_u8str_max_P(col, row, FTOP(utf8_fstr), max_length); } void lcd_put_int(const int i); @@ -177,14 +180,22 @@ inline int lcd_put_u8str_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P con return lcd_put_u8str_P(pstr); } +inline int lcd_put_u8str(FSTR_P const fstr) { return lcd_put_u8str_P(FTOP(fstr)); } +inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr) { + return lcd_put_u8str_P(col, row, FTOP(fstr)); +} + lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH); inline lcd_uint_t lcd_put_u8str_ind_P(const lcd_uint_t col, const lcd_uint_t row, PGM_P const pstr, const int8_t ind, PGM_P const inStr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { lcd_moveto(col, row); return lcd_put_u8str_ind_P(pstr, ind, inStr, maxlen); } +inline lcd_uint_t lcd_put_u8str_ind(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr, const int8_t ind, FSTR_P const inFstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { + return lcd_put_u8str_ind_P(col, row, FTOP(fstr), ind, FTOP(inFstr), maxlen); +} -inline int lcd_put_u8str(const char *str) { return lcd_put_u8str_max(str, PIXEL_LEN_NOLIMIT); } -inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, PGM_P const str) { +inline int lcd_put_u8str(const char * const str) { return lcd_put_u8str_max(str, PIXEL_LEN_NOLIMIT); } +inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, const char * const str) { lcd_moveto(col, row); return lcd_put_u8str(str); } diff --git a/Marlin/src/lcd/menu/game/game.cpp b/Marlin/src/lcd/menu/game/game.cpp index c14bd2a68d..d465b00388 100644 --- a/Marlin/src/lcd/menu/game/game.cpp +++ b/Marlin/src/lcd/menu/game/game.cpp @@ -48,7 +48,7 @@ void MarlinGame::draw_game_over() { u8g.setColorIndex(0); u8g.drawBox(lx - 1, ly - gohigh - 1, gowide + 2, gohigh + 2); u8g.setColorIndex(1); - if (ui.get_blink()) lcd_put_u8str_P(lx, ly, PSTR("GAME OVER")); + if (ui.get_blink()) lcd_put_u8str(lx, ly, F("GAME OVER")); } } diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 1c7ab35e44..178d466478 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -179,7 +179,7 @@ static void _lcd_level_bed_corners_get_next_position() { // Display # of good points found vs total needed if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); - lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_GOOD_POINTS)); + lcd_put_u8str_(GET_TEXT_F(MSG_BED_TRAMMING_GOOD_POINTS)); IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, cy)); lcd_put_u8str(GOOD_POINTS_TO_STR(good_points)); lcd_put_wchar('/'); @@ -192,7 +192,7 @@ static void _lcd_level_bed_corners_get_next_position() { // Display the Last Z value if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); - lcd_put_u8str_P(GET_TEXT(MSG_BED_TRAMMING_LAST_Z)); + lcd_put_u8str(GET_TEXT_F(MSG_BED_TRAMMING_LAST_Z)); IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, 2)); lcd_put_u8str(LAST_Z_TO_STR(last_z)); } diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 694fd54813..be4363574b 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -57,7 +57,7 @@ if (ui.should_draw()) { char tmp[16]; SETCURSOR(1, (LCD_HEIGHT - 1) / 2); - lcd_put_u8str_P(isend ? GET_TEXT(MSG_END_Z) : GET_TEXT(MSG_START_Z)); + lcd_put_u8str(isend ? GET_TEXT_F(MSG_END_Z) : GET_TEXT_F(MSG_START_Z)); sprintf_P(tmp, PSTR("%4d.%d mm"), int(zvar), int(zvar * 10) % 10); SETCURSOR_RJ(9, (LCD_HEIGHT - 1) / 2); lcd_put_u8str(tmp); @@ -114,7 +114,7 @@ static uint8_t v_index; void _lcd_draw_mix(const uint8_t y) { char tmp[20]; // "100%_100%" sprintf_P(tmp, PSTR("%3d%% %3d%%"), int(mixer.mix[0]), int(mixer.mix[1])); - SETCURSOR(2, y); lcd_put_u8str_P(GET_TEXT(MSG_MIX)); + SETCURSOR(2, y); lcd_put_u8str(GET_TEXT_F(MSG_MIX)); SETCURSOR_RJ(10, y); lcd_put_u8str(tmp); } #endif diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 37ffb679e9..b3f078d7a0 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -73,12 +73,12 @@ TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); #if ENABLED(TFT_COLOR_UI) lcd_moveto(4, 3); - lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); + lcd_put_u8str(GET_TEXT_F(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); lcd_moveto(10, 3); #else lcd_moveto(0, TERN(HAS_MARLINUI_U8GLIB, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); - lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); + lcd_put_u8str(GET_TEXT_F(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); #endif lcd_put_u8str(BABYSTEP_TO_STR(mps * babystep.axis_total[BS_TOTAL_IND(axis)])); diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index 41862b5ad8..e152ceab50 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -105,9 +105,9 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { return tft_string.width(); } -int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { +int lcd_put_u8str_max_P(PGM_P utf8_pstr, pixel_len_t max_length) { if (max_length < 1) return 0; - tft_string.set(utf8_str_P); + tft_string.set(utf8_pstr); tft_string.trim(); tft_string.truncate(max_length); tft.add_text(MENU_TEXT_X_OFFSET, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); From d7fede3a6324cd6b1ec91a9c8e248fce8f0d7cf2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Sep 2021 13:40:01 -0500 Subject: [PATCH 0760/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20G-c?= =?UTF-8?q?ode=20report=20header?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/M420.cpp | 2 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 2 +- Marlin/src/gcode/calibrate/M425.cpp | 2 +- Marlin/src/gcode/calibrate/M665.cpp | 6 +++--- Marlin/src/gcode/calibrate/M666.cpp | 4 ++-- Marlin/src/gcode/calibrate/M852.cpp | 2 +- Marlin/src/gcode/config/M200-M205.cpp | 10 +++++----- Marlin/src/gcode/config/M217.cpp | 2 +- Marlin/src/gcode/config/M218.cpp | 2 +- Marlin/src/gcode/config/M281.cpp | 2 +- Marlin/src/gcode/config/M301.cpp | 2 +- Marlin/src/gcode/config/M304.cpp | 2 +- Marlin/src/gcode/config/M309.cpp | 2 +- Marlin/src/gcode/config/M92.cpp | 2 +- Marlin/src/gcode/control/M211.cpp | 2 +- Marlin/src/gcode/feature/advance/M900.cpp | 2 +- Marlin/src/gcode/feature/controllerfan/M710.cpp | 2 +- Marlin/src/gcode/feature/digipot/M907-M910.cpp | 2 +- Marlin/src/gcode/feature/fwretract/M207-M209.cpp | 6 +++--- Marlin/src/gcode/feature/pause/M603.cpp | 2 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 2 +- Marlin/src/gcode/feature/runout/M412.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M906.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M911-M914.cpp | 4 ++-- Marlin/src/gcode/gcode.cpp | 6 +++--- Marlin/src/gcode/gcode.h | 6 +++--- Marlin/src/gcode/geometry/M206_M428.cpp | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/gcode/lcd/M250.cpp | 2 +- Marlin/src/gcode/lcd/M256.cpp | 2 +- Marlin/src/gcode/lcd/M414.cpp | 2 +- Marlin/src/gcode/probe/M851.cpp | 2 +- Marlin/src/gcode/units/M149.cpp | 2 +- Marlin/src/module/settings.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- 36 files changed, 50 insertions(+), 50 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 1240b14fd2..5dcef961ee 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -243,7 +243,7 @@ void GcodeSuite::M420() { } void GcodeSuite::M420_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR( + report_heading_etc(forReplay, F( TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) )); SERIAL_ECHOF( diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 25855e6a4e..8f4eab2c97 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -538,7 +538,7 @@ void GcodeSuite::M422() { } void GcodeSuite::M422_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_Z_AUTO_ALIGN)); + report_heading(forReplay, F(STR_Z_AUTO_ALIGN)); LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 1d314a37d3..190af0f71b 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -114,7 +114,7 @@ void GcodeSuite::M425() { } void GcodeSuite::M425_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_BACKLASH_COMPENSATION)); + report_heading_etc(forReplay, F(STR_BACKLASH_COMPENSATION)); SERIAL_ECHOLNPGM_P( PSTR(" M425 F"), backlash.get_correction() #ifdef BACKLASH_SMOOTHING_MM diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 11de1ce434..aa21471b60 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -62,7 +62,7 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_DELTA_SETTINGS)); + report_heading_etc(forReplay, F(STR_DELTA_SETTINGS)); SERIAL_ECHOLNPGM_P( PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod) , PSTR(" R"), LINEAR_UNIT(delta_radius) @@ -132,7 +132,7 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); + report_heading_etc(forReplay, F(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")")); SERIAL_ECHOLNPGM_P( PSTR(" M665 S"), segments_per_second #if HAS_SCARA_OFFSET @@ -162,7 +162,7 @@ } void GcodeSuite::M665_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_POLARGRAPH_SETTINGS " (" STR_S_SEG_PER_SEC ")")); + report_heading_etc(forReplay, F(STR_POLARGRAPH_SETTINGS " (" STR_S_SEG_PER_SEC ")")); SERIAL_ECHOLNPGM(" M665 S", segments_per_second); } diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index c4149c2352..15f8baf109 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -61,7 +61,7 @@ } void GcodeSuite::M666_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); + report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT)); SERIAL_ECHOLNPGM_P( PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a) , SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b) @@ -105,7 +105,7 @@ } void GcodeSuite::M666_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT)); + report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT)); SERIAL_ECHOPGM(" M666"); #if ENABLED(X_DUAL_ENDSTOPS) SERIAL_ECHOLNPGM_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index c4361b89f3..b24a449652 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/Marlin/src/gcode/calibrate/M852.cpp @@ -92,7 +92,7 @@ void GcodeSuite::M852() { } void GcodeSuite::M852_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_SKEW_FACTOR)); + report_heading_etc(forReplay, F(STR_SKEW_FACTOR)); SERIAL_ECHOPAIR_F(" M851 I", planner.skew_factor.xy, 6); #if ENABLED(SKEW_CORRECTION_FOR_Z) SERIAL_ECHOPAIR_F(" J", planner.skew_factor.xz, 6); diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 2880bd9943..7b7ce5e10d 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -76,7 +76,7 @@ void GcodeSuite::M200_report(const bool forReplay/*=true*/) { if (!forReplay) { - report_heading(forReplay, PSTR(STR_FILAMENT_SETTINGS), false); + report_heading(forReplay, F(STR_FILAMENT_SETTINGS), false); if (!parser.volumetric_enabled) SERIAL_ECHOPGM(" (Disabled):"); SERIAL_EOL(); report_echo_start(forReplay); @@ -133,7 +133,7 @@ void GcodeSuite::M201() { } void GcodeSuite::M201_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_MAX_ACCELERATION)); + report_heading_etc(forReplay, F(STR_MAX_ACCELERATION)); SERIAL_ECHOLNPGM_P( LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), @@ -178,7 +178,7 @@ void GcodeSuite::M203() { } void GcodeSuite::M203_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_MAX_FEEDRATES)); + report_heading_etc(forReplay, F(STR_MAX_FEEDRATES)); SERIAL_ECHOLNPGM_P( LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), @@ -224,7 +224,7 @@ void GcodeSuite::M204() { } void GcodeSuite::M204_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_ACCELERATION_P_R_T)); + report_heading_etc(forReplay, F(STR_ACCELERATION_P_R_T)); SERIAL_ECHOLNPGM_P( PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration) , PSTR(" R"), LINEAR_UNIT(planner.settings.retract_acceleration) @@ -285,7 +285,7 @@ void GcodeSuite::M205() { } void GcodeSuite::M205_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR( + report_heading_etc(forReplay, F( "Advanced (B S T" TERN_(HAS_JUNCTION_DEVIATION, " J") TERN_(HAS_CLASSIC_JERK, " X Y Z") diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 1299259b53..7576272a48 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -131,7 +131,7 @@ void GcodeSuite::M217() { } void GcodeSuite::M217_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_TOOL_CHANGING)); + report_heading_etc(forReplay, F(STR_TOOL_CHANGING)); SERIAL_ECHOPGM(" M217"); diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index c95cd6c1b9..c39447a28d 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -57,7 +57,7 @@ void GcodeSuite::M218() { } void GcodeSuite::M218_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_HOTEND_OFFSETS)); + report_heading_etc(forReplay, F(STR_HOTEND_OFFSETS)); LOOP_S_L_N(e, 1, HOTENDS) { report_echo_start(forReplay); SERIAL_ECHOPGM_P( diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index ac91f08cb4..b90de6be30 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -55,7 +55,7 @@ void GcodeSuite::M281() { } void GcodeSuite::M281_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_SERVO_ANGLES)); + report_heading_etc(forReplay, F(STR_SERVO_ANGLES)); LOOP_L_N(i, NUM_SERVOS) { switch (i) { default: break; diff --git a/Marlin/src/gcode/config/M301.cpp b/Marlin/src/gcode/config/M301.cpp index db882b3b65..fc9f1883d6 100644 --- a/Marlin/src/gcode/config/M301.cpp +++ b/Marlin/src/gcode/config/M301.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M301() { } void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t eindex/*=-1*/)) { - report_heading(forReplay, PSTR(STR_HOTEND_PID)); + report_heading(forReplay, F(STR_HOTEND_PID)); IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr int8_t eindex = -1); HOTEND_LOOP() { if (e == eindex || eindex == -1) { diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp index 05ee4bad80..4bd415db1e 100644 --- a/Marlin/src/gcode/config/M304.cpp +++ b/Marlin/src/gcode/config/M304.cpp @@ -42,7 +42,7 @@ void GcodeSuite::M304() { } void GcodeSuite::M304_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_BED_PID)); + report_heading_etc(forReplay, F(STR_BED_PID)); SERIAL_ECHO_MSG( " M304 P", thermalManager.temp_bed.pid.Kp , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) diff --git a/Marlin/src/gcode/config/M309.cpp b/Marlin/src/gcode/config/M309.cpp index 01c4e62347..577023292e 100644 --- a/Marlin/src/gcode/config/M309.cpp +++ b/Marlin/src/gcode/config/M309.cpp @@ -42,7 +42,7 @@ void GcodeSuite::M309() { } void GcodeSuite::M309_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_CHAMBER_PID)); + report_heading_etc(forReplay, F(STR_CHAMBER_PID)); SERIAL_ECHOLNPGM( " M309 P", thermalManager.temp_chamber.pid.Kp , " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki) diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index ef11533114..54fe698f97 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -91,7 +91,7 @@ void GcodeSuite::M92() { } void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) { - report_heading_etc(forReplay, PSTR(STR_STEPS_PER_UNIT)); + report_heading_etc(forReplay, F(STR_STEPS_PER_UNIT)); SERIAL_ECHOPGM_P(LIST_N(DOUBLE(LINEAR_AXES), PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index d108070279..95ae052a7b 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -40,7 +40,7 @@ void GcodeSuite::M211() { } void GcodeSuite::M211_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_SOFT_ENDSTOPS)); + report_heading_etc(forReplay, F(STR_SOFT_ENDSTOPS)); SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); serialprintln_onoff(soft_endstop._enabled); diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 4ed601bbe8..054ea3617f 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -145,7 +145,7 @@ void GcodeSuite::M900() { } void GcodeSuite::M900_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_LINEAR_ADVANCE)); + report_heading(forReplay, F(STR_LINEAR_ADVANCE)); #if EXTRUDERS < 2 report_echo_start(forReplay); SERIAL_ECHOLNPGM(" M900 K", planner.extruder_advance_K[0]); diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index eede16b5bd..b98d88845d 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -67,7 +67,7 @@ void GcodeSuite::M710() { } void GcodeSuite::M710_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_CONTROLLER_FAN)); + report_heading_etc(forReplay, F(STR_CONTROLLER_FAN)); SERIAL_ECHOLNPGM(" M710" " S", int(controllerFan.settings.active_speed), " I", int(controllerFan.settings.idle_speed), diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index a0b5c48e82..757cffd473 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -100,7 +100,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM void GcodeSuite::M907_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_STEPPER_MOTOR_CURRENTS)); + report_heading_etc(forReplay, F(STR_STEPPER_MOTOR_CURRENTS)); #if HAS_MOTOR_CURRENT_PWM SERIAL_ECHOLNPGM_P( // PWM-based has 3 values: PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y diff --git a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp index 040a09a8e0..173c2894dc 100644 --- a/Marlin/src/gcode/feature/fwretract/M207-M209.cpp +++ b/Marlin/src/gcode/feature/fwretract/M207-M209.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M207() { fwretract.M207(); } void GcodeSuite::M207_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_RETRACT_S_F_Z)); + report_heading_etc(forReplay, F(STR_RETRACT_S_F_Z)); fwretract.M207_report(); } @@ -53,7 +53,7 @@ void GcodeSuite::M207_report(const bool forReplay/*=true*/) { void GcodeSuite::M208() { fwretract.M208(); } void GcodeSuite::M208_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_RECOVER_S_F)); + report_heading_etc(forReplay, F(STR_RECOVER_S_F)); fwretract.M208_report(); } @@ -68,7 +68,7 @@ void GcodeSuite::M208_report(const bool forReplay/*=true*/) { void GcodeSuite::M209() { fwretract.M209(); } void GcodeSuite::M209_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_AUTO_RETRACT_S)); + report_heading_etc(forReplay, F(STR_AUTO_RETRACT_S)); fwretract.M209_report(); } diff --git a/Marlin/src/gcode/feature/pause/M603.cpp b/Marlin/src/gcode/feature/pause/M603.cpp index ebb110d2e7..6689749cfb 100644 --- a/Marlin/src/gcode/feature/pause/M603.cpp +++ b/Marlin/src/gcode/feature/pause/M603.cpp @@ -65,7 +65,7 @@ void GcodeSuite::M603() { } void GcodeSuite::M603_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_FILAMENT_LOAD_UNLOAD)); + report_heading(forReplay, F(STR_FILAMENT_LOAD_UNLOAD)); #if EXTRUDERS == 1 report_echo_start(forReplay); diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 9bf109559f..e02bd4bd95 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -57,7 +57,7 @@ void GcodeSuite::M413() { } void GcodeSuite::M413_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_POWER_LOSS_RECOVERY)); + report_heading_etc(forReplay, F(STR_POWER_LOSS_RECOVERY)); SERIAL_ECHOPGM(" M413 S", AS_DIGIT(recovery.enabled), " ; "); serialprintln_onoff(recovery.enabled); } diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 9cbfbade66..bcf1e9f1b1 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -67,7 +67,7 @@ void GcodeSuite::M412() { } void GcodeSuite::M412_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); + report_heading_etc(forReplay, F(STR_FILAMENT_RUNOUT_SENSOR)); SERIAL_ECHOPGM( " M412 S", runout.enabled #if HAS_FILAMENT_RUNOUT_DISTANCE diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index e8e3205358..36a2c50ab2 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -139,7 +139,7 @@ void GcodeSuite::M569() { } void GcodeSuite::M569_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_DRIVER_STEPPING_MODE)); + report_heading(forReplay, F(STR_DRIVER_STEPPING_MODE)); auto say_M569 = [](const bool forReplay, const char * const etc=nullptr, const bool eol=false) { if (!forReplay) SERIAL_ECHO_START(); diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 48db266c72..74596831d3 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -199,7 +199,7 @@ void GcodeSuite::M906() { } void GcodeSuite::M906_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_STEPPER_DRIVER_CURRENT)); + report_heading(forReplay, F(STR_STEPPER_DRIVER_CURRENT)); auto say_M906 = [](const bool forReplay) { report_echo_start(forReplay); diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 58702c603f..6e177960ef 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -311,7 +311,7 @@ } void GcodeSuite::M913_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_HYBRID_THRESHOLD)); + report_heading(forReplay, F(STR_HYBRID_THRESHOLD)); auto say_M913 = [](const bool forReplay) { report_echo_start(forReplay); @@ -512,7 +512,7 @@ } void GcodeSuite::M914_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_STALLGUARD_THRESHOLD)); + report_heading(forReplay, F(STR_STALLGUARD_THRESHOLD)); auto say_M914 = [](const bool forReplay) { report_echo_start(forReplay); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index c9c80639b5..5f84ca3c38 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -103,12 +103,12 @@ axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( #endif void GcodeSuite::report_echo_start(const bool forReplay) { if (!forReplay) SERIAL_ECHO_START(); } -void GcodeSuite::report_heading(const bool forReplay, PGM_P const pstr, const bool eol/*=true*/) { +void GcodeSuite::report_heading(const bool forReplay, FSTR_P const fstr, const bool eol/*=true*/) { if (forReplay) return; - if (pstr) { + if (fstr) { SERIAL_ECHO_START(); SERIAL_ECHOPGM("; "); - SERIAL_ECHOPGM_P(pstr); + SERIAL_ECHOF(fstr); } if (eol) { SERIAL_CHAR(':'); SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index e6e50e8a1c..21f0d3942f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -382,9 +382,9 @@ public: } static void report_echo_start(const bool forReplay); - static void report_heading(const bool forReplay, PGM_P const pstr, const bool eol=true); - static inline void report_heading_etc(const bool forReplay, PGM_P const pstr, const bool eol=true) { - report_heading(forReplay, pstr, eol); + static void report_heading(const bool forReplay, FSTR_P const fstr, const bool eol=true); + static inline void report_heading_etc(const bool forReplay, FSTR_P const fstr, const bool eol=true) { + report_heading(forReplay, fstr, eol); report_echo_start(forReplay); } static void say_units(); diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 8dba238d09..131dbecf33 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -53,7 +53,7 @@ void GcodeSuite::M206() { } void GcodeSuite::M206_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_HOME_OFFSET)); + report_heading_etc(forReplay, F(STR_HOME_OFFSET)); SERIAL_ECHOLNPGM_P( #if IS_CARTESIAN LIST_N(DOUBLE(LINEAR_AXES), diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index 77fd425763..2dba238d3f 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -61,7 +61,7 @@ void GcodeSuite::M145() { } void GcodeSuite::M145_report(const bool forReplay/*=true*/) { - report_heading(forReplay, PSTR(STR_MATERIAL_HEATUP)); + report_heading(forReplay, F(STR_MATERIAL_HEATUP)); LOOP_L_N(i, PREHEAT_COUNT) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( diff --git a/Marlin/src/gcode/lcd/M250.cpp b/Marlin/src/gcode/lcd/M250.cpp index 083fb37f65..25e4232788 100644 --- a/Marlin/src/gcode/lcd/M250.cpp +++ b/Marlin/src/gcode/lcd/M250.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M250() { } void GcodeSuite::M250_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_LCD_CONTRAST)); + report_heading_etc(forReplay, F(STR_LCD_CONTRAST)); SERIAL_ECHOLNPGM(" M250 C", ui.contrast); } diff --git a/Marlin/src/gcode/lcd/M256.cpp b/Marlin/src/gcode/lcd/M256.cpp index ee187cc2e1..9842cc2583 100644 --- a/Marlin/src/gcode/lcd/M256.cpp +++ b/Marlin/src/gcode/lcd/M256.cpp @@ -37,7 +37,7 @@ void GcodeSuite::M256() { } void GcodeSuite::M256_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_LCD_BRIGHTNESS)); + report_heading_etc(forReplay, F(STR_LCD_BRIGHTNESS)); SERIAL_ECHOLNPGM(" M256 B", ui.brightness); } diff --git a/Marlin/src/gcode/lcd/M414.cpp b/Marlin/src/gcode/lcd/M414.cpp index 0eac980e0f..9aa49ea3c2 100644 --- a/Marlin/src/gcode/lcd/M414.cpp +++ b/Marlin/src/gcode/lcd/M414.cpp @@ -44,7 +44,7 @@ void GcodeSuite::M414() { } void GcodeSuite::M414_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_UI_LANGUAGE)); + report_heading_etc(forReplay, F(STR_UI_LANGUAGE)); SERIAL_ECHOLNPGM(" M414 S", ui.language); } diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index 7ec326730f..e66392acb4 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -84,7 +84,7 @@ void GcodeSuite::M851() { } void GcodeSuite::M851_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_Z_PROBE_OFFSET)); + report_heading_etc(forReplay, F(STR_Z_PROBE_OFFSET)); SERIAL_ECHOPGM_P( #if HAS_PROBE_XY_OFFSET PSTR(" M851 X"), LINEAR_UNIT(probe.offset_xy.x), diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index b1cfbb2511..3f1ea3654e 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -37,7 +37,7 @@ void GcodeSuite::M149() { } void GcodeSuite::M149_report(const bool forReplay/*=true*/) { - report_heading_etc(forReplay, PSTR(STR_TEMPERATURE_UNITS)); + report_heading_etc(forReplay, F(STR_TEMPERATURE_UNITS)); SERIAL_ECHOPGM(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); SERIAL_ECHOLNF(parser.temp_units_name()); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 4f15dceba8..6b7143e82a 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3037,7 +3037,7 @@ void MarlinSettings::reset() { #define CONFIG_ECHO_START() gcode.report_echo_start(forReplay) #define CONFIG_ECHO_MSG(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0) #define CONFIG_ECHO_MSG_P(V...) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM_P(V); }while(0) - #define CONFIG_ECHO_HEADING(STR) gcode.report_heading(forReplay, PSTR(STR)) + #define CONFIG_ECHO_HEADING(STR) gcode.report_heading(forReplay, F(STR)) void M92_report(const bool echo=true, const int8_t e=-1); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 40778ef312..e0a35787c6 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1727,7 +1727,7 @@ void Temperature::manage_heater() { } void Temperature::M305_report(const uint8_t t_index, const bool forReplay/*=true*/) { - gcode.report_heading_etc(forReplay, PSTR(STR_USER_THERMISTORS)); + gcode.report_heading_etc(forReplay, F(STR_USER_THERMISTORS)); SERIAL_ECHOPGM(" M305 P", AS_DIGIT(t_index)); const user_thermistor_t &t = user_thermistor[t_index]; From 1dafd1887e40399faf16e3455e3670ed3acfac52 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Sep 2021 13:46:42 -0500 Subject: [PATCH 0761/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20var?= =?UTF-8?q?ious=20reports?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/Delay.cpp | 36 +++++----- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 12 ++-- Marlin/src/feature/max7219.cpp | 41 ++++++----- Marlin/src/feature/max7219.h | 4 +- Marlin/src/feature/powerloss.cpp | 8 +-- Marlin/src/feature/powerloss.h | 4 +- Marlin/src/feature/stepper_driver_safety.cpp | 12 ++-- Marlin/src/feature/twibus.cpp | 46 ++++++------ Marlin/src/feature/twibus.h | 23 +++--- Marlin/src/gcode/bedlevel/M420.cpp | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 30 ++++---- Marlin/src/gcode/calibrate/G28.cpp | 14 ++-- Marlin/src/gcode/calibrate/G33.cpp | 44 ++++++------ Marlin/src/gcode/calibrate/M100.cpp | 14 ++-- Marlin/src/gcode/config/M43.cpp | 6 +- .../src/gcode/feature/network/M552-M554.cpp | 10 +-- Marlin/src/gcode/feature/powerloss/M1000.cpp | 6 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 32 ++++----- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/gcode/host/M115.cpp | 70 +++++++++---------- Marlin/src/gcode/host/M360.cpp | 62 ++++++++-------- Marlin/src/gcode/queue.cpp | 12 ++-- Marlin/src/gcode/queue.h | 2 +- Marlin/src/libs/stopwatch.cpp | 18 ++--- Marlin/src/libs/stopwatch.h | 11 ++- Marlin/src/libs/vector_3.cpp | 24 +++---- Marlin/src/libs/vector_3.h | 4 +- Marlin/src/module/endstops.cpp | 14 ++-- Marlin/src/pins/pinsDebug.h | 8 +-- 30 files changed, 286 insertions(+), 289 deletions(-) diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index 32543c6d0a..c64376d25d 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -108,13 +108,14 @@ #if ENABLED(MARLIN_DEV_MODE) void dump_delay_accuracy_check() { - auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) { + auto report_call_time = [](FSTR_P const name, FSTR_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) { SERIAL_ECHOPGM("Calling "); - SERIAL_ECHOPGM_P(name); + SERIAL_ECHOF(name); SERIAL_ECHOLNPGM(" for ", cycles); - SERIAL_ECHOPGM_P(unit); + SERIAL_ECHOF(unit); SERIAL_ECHOLNPGM(" took: ", total); - SERIAL_ECHOPGM_P(unit); + SERIAL_CHAR(' '); + SERIAL_ECHOF(unit); if (do_flush) SERIAL_FLUSHTX(); }; @@ -126,41 +127,42 @@ constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 }; for (auto i : testValues) { s = micros(); DELAY_US(i); e = micros(); - report_call_time(PSTR("delay"), PSTR("us"), i, e - s); + report_call_time(F("delay"), F("us"), i, e - s); } if (HW_REG(_DWT_CTRL)) { + static FSTR_P cyc = F("cycles"); + static FSTR_P dcd = F("DELAY_CYCLES directly "); + for (auto i : testValues) { s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(i); e = HW_REG(_DWT_CYCCNT); - report_call_time(PSTR("runtime delay"), PSTR("cycles"), i, e - s); + report_call_time(F("runtime delay"), cyc, i, e - s); } // Measure the delay to call a real function compared to a function pointer s = HW_REG(_DWT_CYCCNT); delay_dwt(1); e = HW_REG(_DWT_CYCCNT); - report_call_time(PSTR("delay_dwt"), PSTR("cycles"), 1, e - s); - - static PGMSTR(dcd, "DELAY_CYCLES directly "); + report_call_time(F("delay_dwt"), cyc, 1, e - s); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 1); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 1, e - s, false); + report_call_time(dcd, cyc, 1, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 5); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 5, e - s, false); + report_call_time(dcd, cyc, 5, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(10); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 10, e - s, false); + report_call_time(dcd, cyc, 10, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(20); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 20, e - s, false); + report_call_time(dcd, cyc, 20, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(50); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 50, e - s, false); + report_call_time(dcd, cyc, 50, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(100); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 100, e - s, false); + report_call_time(dcd, cyc, 100, e - s, false); s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(200); e = HW_REG(_DWT_CYCCNT); - report_call_time(dcd, PSTR("cycles"), 200, e - s, false); + report_call_time(dcd, cyc, 200, e - s, false); } } #endif // MARLIN_DEV_MODE @@ -170,7 +172,7 @@ void calibrate_delay_loop() {} #if ENABLED(MARLIN_DEV_MODE) - void dump_delay_accuracy_check() { SERIAL_ECHOPGM_P(PSTR("N/A on this platform")); } + void dump_delay_accuracy_check() { SERIAL_ECHOPGM("N/A on this platform"); } #endif #endif diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 051cb6a4d6..d78a5e2578 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1609,7 +1609,7 @@ void unified_bed_leveling::smart_fill_mesh() { } if (DEBUGGING(LEVELING)) { - rotation.debug(PSTR("rotation matrix:\n")); + rotation.debug(F("rotation matrix:\n")); DEBUG_ECHOPAIR_F("LSF Results A=", lsf_results.A, 7); DEBUG_ECHOPAIR_F(" B=", lsf_results.B, 7); DEBUG_ECHOLNPAIR_F(" D=", lsf_results.D, 7); @@ -1636,14 +1636,14 @@ void unified_bed_leveling::smart_fill_mesh() { auto normed = [&](const xy_pos_t &pos, const_float_t zadd) { return normal.x * pos.x + normal.y * pos.y + zadd; }; - auto debug_pt = [](PGM_P const pre, const xy_pos_t &pos, const_float_t zadd) { - d_from(); SERIAL_ECHOPGM_P(pre); + auto debug_pt = [](FSTR_P const pre, const xy_pos_t &pos, const_float_t zadd) { + d_from(); SERIAL_ECHOF(pre); DEBUG_ECHO_F(normed(pos, zadd), 6); DEBUG_ECHOLNPAIR_F(" Z error = ", zadd - get_z_correction(pos), 6); }; - debug_pt(PSTR("1st point: "), probe_pt[0], normal.z * z1); - debug_pt(PSTR("2nd point: "), probe_pt[1], normal.z * z2); - debug_pt(PSTR("3rd point: "), probe_pt[2], normal.z * z3); + debug_pt(F("1st point: "), probe_pt[0], normal.z * z1); + debug_pt(F("2nd point: "), probe_pt[1], normal.z * z2); + debug_pt(F("3rd point: "), probe_pt[2], normal.z * z3); d_from(); DEBUG_ECHOPGM("safe home with Z="); DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); d_from(); DEBUG_ECHOPGM("safe home with Z="); diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index e13c6f5b97..474933aa19 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -124,11 +124,10 @@ uint8_t Max7219::suspended; // = 0; #define SIG_DELAY() DELAY_NS(250) #endif -void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { +void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/) { #if ENABLED(MAX7219_ERRORS) SERIAL_ECHOPGM("??? Max7219::"); - SERIAL_ECHOPGM_P(func); - SERIAL_CHAR('('); + SERIAL_ECHOF(func, AS_CHAR('(')); SERIAL_ECHO(v1); if (v2 > 0) SERIAL_ECHOPGM(", ", v2); SERIAL_CHAR(')'); @@ -268,24 +267,24 @@ void Max7219::set(const uint8_t line, const uint8_t bits) { // Modify a single LED bit and send the changed line void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on) { - if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(PSTR("led_set"), x, y); + if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_set"), x, y); if (BIT_7219(x, y) == on) return; XOR_7219(x, y); refresh_unit_line(LED_IND(x, y)); } void Max7219::led_on(const uint8_t x, const uint8_t y) { - if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(PSTR("led_on"), x, y); + if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_on"), x, y); led_set(x, y, true); } void Max7219::led_off(const uint8_t x, const uint8_t y) { - if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(PSTR("led_off"), x, y); + if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_off"), x, y); led_set(x, y, false); } void Max7219::led_toggle(const uint8_t x, const uint8_t y) { - if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(PSTR("led_toggle"), x, y); + if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_toggle"), x, y); led_set(x, y, !BIT_7219(x, y)); } @@ -328,13 +327,13 @@ void Max7219::fill() { } void Max7219::clear_row(const uint8_t row) { - if (row >= MAX7219_Y_LEDS) return error(PSTR("clear_row"), row); + if (row >= MAX7219_Y_LEDS) return error(F("clear_row"), 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); + if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); LOOP_L_N(y, MAX7219_Y_LEDS) CLR_7219(col, y); send_column(col); } @@ -345,7 +344,7 @@ void Max7219::clear_column(const uint8_t col) { * 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); + if (row >= MAX7219_Y_LEDS) return error(F("set_row"), row); uint32_t mask = _BV32(MAX7219_X_LEDS - 1); LOOP_L_N(x, MAX7219_X_LEDS) { if (val & mask) SET_7219(x, row); else CLR_7219(x, row); @@ -360,7 +359,7 @@ void Max7219::set_row(const uint8_t row, const uint32_t val) { * 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); + if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); uint32_t mask = _BV32(MAX7219_Y_LEDS - 1); LOOP_L_N(y, MAX7219_Y_LEDS) { if (val & mask) SET_7219(col, y); else CLR_7219(col, y); @@ -371,56 +370,56 @@ void Max7219::set_column(const uint8_t col, const uint32_t val) { void Max7219::set_rows_16bits(const uint8_t y, uint32_t val) { #if MAX7219_X_LEDS == 8 - if (y > MAX7219_Y_LEDS - 2) return error(PSTR("set_rows_16bits"), y, val); + if (y > MAX7219_Y_LEDS - 2) return error(F("set_rows_16bits"), y, val); set_row(y + 1, val); val >>= 8; set_row(y + 0, val); #else // at least 16 bits on each row - if (y > MAX7219_Y_LEDS - 1) return error(PSTR("set_rows_16bits"), y, val); + if (y > MAX7219_Y_LEDS - 1) return error(F("set_rows_16bits"), y, val); set_row(y, val); #endif } void Max7219::set_rows_32bits(const uint8_t y, uint32_t val) { #if MAX7219_X_LEDS == 8 - if (y > MAX7219_Y_LEDS - 4) return error(PSTR("set_rows_32bits"), y, val); + if (y > MAX7219_Y_LEDS - 4) return error(F("set_rows_32bits"), y, val); set_row(y + 3, val); val >>= 8; set_row(y + 2, val); val >>= 8; set_row(y + 1, val); val >>= 8; set_row(y + 0, val); #elif MAX7219_X_LEDS == 16 - if (y > MAX7219_Y_LEDS - 2) return error(PSTR("set_rows_32bits"), y, val); + if (y > MAX7219_Y_LEDS - 2) return error(F("set_rows_32bits"), y, val); set_row(y + 1, val); val >>= 16; set_row(y + 0, val); #else // at least 24 bits on each row. In the 3 matrix case, just display the low 24 bits - if (y > MAX7219_Y_LEDS - 1) return error(PSTR("set_rows_32bits"), y, val); + if (y > MAX7219_Y_LEDS - 1) return error(F("set_rows_32bits"), y, val); set_row(y, val); #endif } void Max7219::set_columns_16bits(const uint8_t x, uint32_t val) { #if MAX7219_Y_LEDS == 8 - if (x > MAX7219_X_LEDS - 2) return error(PSTR("set_columns_16bits"), x, val); + if (x > MAX7219_X_LEDS - 2) return error(F("set_columns_16bits"), x, val); set_column(x + 0, val); val >>= 8; set_column(x + 1, val); #else // at least 16 bits in each column - if (x > MAX7219_X_LEDS - 1) return error(PSTR("set_columns_16bits"), x, val); + if (x > MAX7219_X_LEDS - 1) return error(F("set_columns_16bits"), x, val); set_column(x, val); #endif } void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) { #if MAX7219_Y_LEDS == 8 - if (x > MAX7219_X_LEDS - 4) return error(PSTR("set_rows_32bits"), x, val); + if (x > MAX7219_X_LEDS - 4) return error(F("set_rows_32bits"), x, val); set_column(x + 3, val); val >>= 8; set_column(x + 2, val); val >>= 8; set_column(x + 1, val); val >>= 8; set_column(x + 0, val); #elif MAX7219_Y_LEDS == 16 - if (x > MAX7219_X_LEDS - 2) return error(PSTR("set_rows_32bits"), x, val); + if (x > MAX7219_X_LEDS - 2) return error(F("set_rows_32bits"), x, val); set_column(x + 1, val); val >>= 16; set_column(x + 0, val); #else // at least 24 bits on each row. In the 3 matrix case, just display the low 24 bits - if (x > MAX7219_X_LEDS - 1) return error(PSTR("set_rows_32bits"), x, val); + if (x > MAX7219_X_LEDS - 1) return error(F("set_rows_32bits"), x, val); set_column(x, val); #endif } diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index 3e5b62db2f..c25fef1730 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -42,6 +42,8 @@ * a Max7219_Set_Row(). The opposite is true for rotations of 0 or 180 degrees. */ +#include "../inc/MarlinConfig.h" + #ifndef MAX7219_ROTATE #define MAX7219_ROTATE 0 #endif @@ -140,7 +142,7 @@ public: private: static uint8_t suspended; - static void error(const char * const func, const int32_t v1, const int32_t v2=-1); + static void error(FSTR_P 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); static void send_row(const uint8_t row); diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 9808113ecc..bc19c9b18e 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -130,7 +130,7 @@ void PrintJobRecovery::load() { (void)file.read(&info, sizeof(info)); close(); } - debug(PSTR("Load")); + debug(F("Load")); } /** @@ -311,7 +311,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW */ void PrintJobRecovery::write() { - debug(PSTR("Write")); + debug(F("Write")); open(false); file.seekSet(0); @@ -575,8 +575,8 @@ void PrintJobRecovery::resume() { #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) - void PrintJobRecovery::debug(PGM_P const prefix) { - DEBUG_ECHOPGM_P(prefix); + void PrintJobRecovery::debug(FSTR_P const prefix) { + DEBUG_ECHOF(prefix); DEBUG_ECHOLNPGM(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot); if (info.valid_head) { if (info.valid_head == info.valid_foot) { diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 6a13c92df7..76cb398af2 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -204,9 +204,9 @@ class PrintJobRecovery { static inline bool valid() { return info.valid() && interrupted_file_exists(); } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) - static void debug(PGM_P const prefix); + static void debug(FSTR_P const prefix); #else - static inline void debug(PGM_P const) {} + static inline void debug(FSTR_P const) {} #endif private: diff --git a/Marlin/src/feature/stepper_driver_safety.cpp b/Marlin/src/feature/stepper_driver_safety.cpp index 8ba0968cd2..11b90954b4 100644 --- a/Marlin/src/feature/stepper_driver_safety.cpp +++ b/Marlin/src/feature/stepper_driver_safety.cpp @@ -28,11 +28,11 @@ static uint32_t axis_plug_backward = 0; -void stepper_driver_backward_error(PGM_P str) { +void stepper_driver_backward_error(FSTR_P const fstr) { SERIAL_ERROR_START(); - SERIAL_ECHOPGM_P(str); + SERIAL_ECHOF(fstr); SERIAL_ECHOLNPGM(" driver is backward!"); - ui.status_printf(2, F(S_FMT S_FMT), str, GET_TEXT(MSG_DRIVER_BACKWARD)); + ui.status_printf(2, F(S_FMT S_FMT), FTOP(fstr), GET_TEXT(MSG_DRIVER_BACKWARD)); } void stepper_driver_backward_check() { @@ -45,7 +45,7 @@ void stepper_driver_backward_check() { delay(20); \ if (READ(AXIS##_ENABLE_PIN) == false) { \ SBI(axis_plug_backward, BIT); \ - stepper_driver_backward_error(PSTR(STRINGIFY(AXIS))); \ + stepper_driver_backward_error(F(STRINGIFY(AXIS))); \ } \ }while(0) @@ -82,12 +82,12 @@ void stepper_driver_backward_check() { void stepper_driver_backward_report() { if (!axis_plug_backward) return; - auto _report_if_backward = [](PGM_P axis, uint8_t bit) { + auto _report_if_backward = [](FSTR_P const axis, uint8_t bit) { if (TEST(axis_plug_backward, bit)) stepper_driver_backward_error(axis); }; - #define REPORT_BACKWARD(axis, bit) TERN_(HAS_##axis##_ENABLE, _report_if_backward(PSTR(STRINGIFY(axis)), bit)) + #define REPORT_BACKWARD(axis, bit) TERN_(HAS_##axis##_ENABLE, _report_if_backward(F(STRINGIFY(axis)), bit)) REPORT_BACKWARD(X, 0); REPORT_BACKWARD(X2, 1); diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 5f5209cdd4..55e4da75cf 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -51,27 +51,27 @@ void TWIBus::address(const uint8_t adr) { addr = adr; - debug(PSTR("address"), adr); + debug(F("address"), adr); } void TWIBus::addbyte(const char c) { if (buffer_s >= COUNT(buffer)) return; buffer[buffer_s++] = c; - debug(PSTR("addbyte"), c); + debug(F("addbyte"), c); } void TWIBus::addbytes(char src[], uint8_t bytes) { - debug(PSTR("addbytes"), bytes); + debug(F("addbytes"), bytes); while (bytes--) addbyte(*src++); } void TWIBus::addstring(char str[]) { - debug(PSTR("addstring"), str); + debug(F("addstring"), str); while (char c = *str++) addbyte(c); } void TWIBus::send() { - debug(PSTR("send"), addr); + debug(F("send"), addr); Wire.beginTransmission(I2C_ADDRESS(addr)); Wire.write(buffer, buffer_s); @@ -81,20 +81,20 @@ void TWIBus::send() { } // static -void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) { +void TWIBus::echoprefix(uint8_t bytes, FSTR_P const pref, uint8_t adr) { SERIAL_ECHO_START(); - SERIAL_ECHOPGM_P(pref); + SERIAL_ECHOF(pref); SERIAL_ECHOPGM(": from:", adr, " bytes:", bytes, " data:"); } // static -void TWIBus::echodata(uint8_t bytes, const char pref[], uint8_t adr) { +void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr) { echoprefix(bytes, pref, adr); while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); SERIAL_EOL(); } -void TWIBus::echobuffer(const char pref[], uint8_t adr) { +void TWIBus::echobuffer(FSTR_P const pref, uint8_t adr) { echoprefix(buffer_s, pref, adr); LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); @@ -103,11 +103,11 @@ void TWIBus::echobuffer(const char pref[], uint8_t adr) { bool TWIBus::request(const uint8_t bytes) { if (!addr) return false; - debug(PSTR("request"), bytes); + debug(F("request"), bytes); // requestFrom() is a blocking function if (Wire.requestFrom(I2C_ADDRESS(addr), bytes) == 0) { - debug("request fail", I2C_ADDRESS(addr)); + debug(F("request fail"), I2C_ADDRESS(addr)); return false; } @@ -115,10 +115,10 @@ bool TWIBus::request(const uint8_t bytes) { } void TWIBus::relay(const uint8_t bytes) { - debug(PSTR("relay"), bytes); + debug(F("relay"), bytes); if (request(bytes)) - echodata(bytes, PSTR("i2c-reply"), addr); + echodata(bytes, F("i2c-reply"), addr); } uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { @@ -127,7 +127,7 @@ uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { while (count < bytes && Wire.available()) dst[count++] = Wire.read(); - debug(PSTR("capture"), count); + debug(F("capture"), count); return count; } @@ -140,12 +140,12 @@ void TWIBus::flush() { #if I2C_SLAVE_ADDRESS > 0 void TWIBus::receive(uint8_t bytes) { - debug(PSTR("receive"), bytes); - echodata(bytes, PSTR("i2c-receive"), 0); + debug(F("receive"), bytes); + echodata(bytes, F("i2c-receive"), 0); } void TWIBus::reply(char str[]/*=nullptr*/) { - debug(PSTR("reply"), str); + debug(F("reply"), str); if (str) { reset(); @@ -170,18 +170,16 @@ void TWIBus::flush() { #if ENABLED(DEBUG_TWIBUS) // static - void TWIBus::prefix(const char func[]) { - SERIAL_ECHOPGM("TWIBus::"); - SERIAL_ECHOPGM_P(func); - SERIAL_ECHOPGM(": "); + void TWIBus::prefix(FSTR_P const func) { + SERIAL_ECHOPGM("TWIBus::", func, ": "); } - void TWIBus::debug(const char func[], uint32_t adr) { + void TWIBus::debug(FSTR_P const func, uint32_t adr) { if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(adr); } } - void TWIBus::debug(const char func[], char c) { + void TWIBus::debug(FSTR_P const func, char c) { if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(c); } } - void TWIBus::debug(const char func[], char str[]) { + void TWIBus::debug(FSTR_P const func, char str[]) { if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(str); } } diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 5939153482..2a8a7fef6a 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -142,7 +142,7 @@ class TWIBus { * * @param bytes the number of bytes to request */ - static void echoprefix(uint8_t bytes, const char prefix[], uint8_t adr); + static void echoprefix(uint8_t bytes, FSTR_P prefix, uint8_t adr); /** * @brief Echo data on the bus to serial @@ -151,7 +151,7 @@ class TWIBus { * * @param bytes the number of bytes to request */ - static void echodata(uint8_t bytes, const char prefix[], uint8_t adr); + static void echodata(uint8_t bytes, FSTR_P prefix, uint8_t adr); /** * @brief Echo data in the buffer to serial @@ -160,7 +160,7 @@ class TWIBus { * * @param bytes the number of bytes to request */ - void echobuffer(const char prefix[], uint8_t adr); + void echobuffer(FSTR_P prefix, uint8_t adr); /** * @brief Request data from the slave device and wait. @@ -237,17 +237,16 @@ class TWIBus { * @brief Prints a debug message * @details Prints a simple debug message "TWIBus::function: value" */ - static void prefix(const char func[]); - static void debug(const char func[], uint32_t adr); - static void debug(const char func[], char c); - static void debug(const char func[], char adr[]); - static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); } + static void prefix(FSTR_P const func); + static void debug(FSTR_P const func, uint32_t adr); + static void debug(FSTR_P const func, char c); + static void debug(FSTR_P const func, char adr[]); #else - static inline void debug(const char[], uint32_t) {} - static inline void debug(const char[], char) {} - static inline void debug(const char[], char[]) {} - static inline void debug(const char[], uint8_t) {} + static inline void debug(FSTR_P const, uint32_t) {} + static inline void debug(FSTR_P const, char) {} + static inline void debug(FSTR_P const, char[]) {} #endif + static inline void debug(FSTR_P const func, uint8_t v) { debug(func, (uint32_t)v); } }; extern TWIBus i2c; diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 5dcef961ee..3c23e85a1d 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -195,7 +195,7 @@ void GcodeSuite::M420() { // V to print the matrix or mesh if (seenV) { #if ABL_PLANAR - planner.bed_level_matrix.debug(PSTR("Bed Level Correction Matrix:")); + planner.bed_level_matrix.debug(F("Bed Level Correction Matrix:")); #else if (leveling_is_valid()) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 07aefe8aed..f7afd93c81 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -783,8 +783,8 @@ G29_TYPE GcodeSuite::G29() { float min_diff = 999; - auto print_topo_map = [&](PGM_P const title, const bool get_min) { - SERIAL_ECHOPGM_P(title); + auto print_topo_map = [&](FSTR_P const title, const bool get_min) { + SERIAL_ECHOF(title); for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) { LOOP_L_N(xx, abl.grid_points.x) { const int ind = abl.indexIntoAB[xx][yy]; @@ -802,19 +802,19 @@ G29_TYPE GcodeSuite::G29() { SERIAL_EOL(); }; - print_topo_map(PSTR("\nBed Height Topography:\n" - " +--- BACK --+\n" - " | |\n" - " L | (+) | R\n" - " E | | I\n" - " F | (-) N (+) | G\n" - " T | | H\n" - " | (-) | T\n" - " | |\n" - " O-- FRONT --+\n" - " (0,0)\n"), true); + print_topo_map(F("\nBed Height Topography:\n" + " +--- BACK --+\n" + " | |\n" + " L | (+) | R\n" + " E | | I\n" + " F | (-) N (+) | G\n" + " T | | H\n" + " | (-) | T\n" + " | |\n" + " O-- FRONT --+\n" + " (0,0)\n"), true); if (abl.verbose_level > 3) - print_topo_map(PSTR("\nCorrected Bed Height vs. Bed Topology:\n"), false); + print_topo_map(F("\nCorrected Bed Height vs. Bed Topology:\n"), false); } // abl.topography_map @@ -825,7 +825,7 @@ G29_TYPE GcodeSuite::G29() { // For LINEAR and 3POINT leveling correct the current position if (abl.verbose_level > 0) - planner.bed_level_matrix.debug(PSTR("\n\nBed Level Correction Matrix:")); + planner.bed_level_matrix.debug(F("\n\nBed Level Correction Matrix:")); if (!abl.dryrun) { // diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index cd6a3a760d..95f2a9b176 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -269,33 +269,33 @@ void GcodeSuite::G28() { #endif #if HAS_HOMING_CURRENT - auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b) { - DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); + auto debug_current = [](FSTR_P const s, const int16_t a, const int16_t b) { + DEBUG_ECHOF(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) const int16_t tmc_save_current_X = stepperX.getMilliamps(); stepperX.rms_current(X_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(PSTR("X"), tmc_save_current_X, X_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F("X"), tmc_save_current_X, X_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(X2) const int16_t tmc_save_current_X2 = stepperX2.getMilliamps(); stepperX2.rms_current(X2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(PSTR("X2"), tmc_save_current_X2, X2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F("X2"), tmc_save_current_X2, X2_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y) const int16_t tmc_save_current_Y = stepperY.getMilliamps(); stepperY.rms_current(Y_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(PSTR("Y"), tmc_save_current_Y, Y_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F("Y"), tmc_save_current_Y, Y_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y2) const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps(); stepperY2.rms_current(Y2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); stepperZ.rms_current(Z_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(PSTR("Z"), tmc_save_current_Z, Z_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F("Z"), tmc_save_current_Z, Z_CURRENT_HOME); #endif #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 39494cde24..8a9de49880 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -97,10 +97,9 @@ void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true)); } -void print_signed_float(PGM_P const prefix, const_float_t f) { +void print_signed_float(FSTR_P const prefix, const_float_t f) { SERIAL_ECHOPGM(" "); - SERIAL_ECHOPGM_P(prefix); - SERIAL_CHAR(':'); + SERIAL_ECHOF(prefix, AS_CHAR(':')); if (f >= 0) SERIAL_CHAR('+'); SERIAL_ECHO_F(f, 2); } @@ -111,24 +110,23 @@ void print_signed_float(PGM_P const prefix, const_float_t f) { static void print_calibration_settings(const bool end_stops, const bool tower_angles) { SERIAL_ECHOPGM(".Height:", delta_height); if (end_stops) { - print_signed_float(PSTR("Ex"), delta_endstop_adj.a); - print_signed_float(PSTR("Ey"), delta_endstop_adj.b); - print_signed_float(PSTR("Ez"), delta_endstop_adj.c); + print_signed_float(F("Ex"), delta_endstop_adj.a); + print_signed_float(F("Ey"), delta_endstop_adj.b); + print_signed_float(F("Ez"), delta_endstop_adj.c); } if (end_stops && tower_angles) { - SERIAL_ECHOPGM(" Radius:", delta_radius); - SERIAL_EOL(); + SERIAL_ECHOLNPGM(" Radius:", delta_radius); SERIAL_CHAR('.'); SERIAL_ECHO_SP(13); } if (tower_angles) { - print_signed_float(PSTR("Tx"), delta_tower_angle_trim.a); - print_signed_float(PSTR("Ty"), delta_tower_angle_trim.b); - print_signed_float(PSTR("Tz"), delta_tower_angle_trim.c); + print_signed_float(F("Tx"), delta_tower_angle_trim.a); + print_signed_float(F("Ty"), delta_tower_angle_trim.b); + print_signed_float(F("Tz"), delta_tower_angle_trim.c); } - if ((!end_stops && tower_angles) || (end_stops && !tower_angles)) { // XOR + if (end_stops != tower_angles) SERIAL_ECHOPGM(" Radius:", delta_radius); - } + SERIAL_EOL(); } @@ -137,11 +135,11 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an */ static void print_calibration_results(const float z_pt[NPP + 1], const bool tower_points, const bool opposite_points) { SERIAL_ECHOPGM(". "); - print_signed_float(PSTR("c"), z_pt[CEN]); + print_signed_float(F("c"), z_pt[CEN]); if (tower_points) { - print_signed_float(PSTR(" x"), z_pt[__A]); - print_signed_float(PSTR(" y"), z_pt[__B]); - print_signed_float(PSTR(" z"), z_pt[__C]); + print_signed_float(F(" x"), z_pt[__A]); + print_signed_float(F(" y"), z_pt[__B]); + print_signed_float(F(" z"), z_pt[__C]); } if (tower_points && opposite_points) { SERIAL_EOL(); @@ -149,9 +147,9 @@ static void print_calibration_results(const float z_pt[NPP + 1], const bool towe SERIAL_ECHO_SP(13); } if (opposite_points) { - print_signed_float(PSTR("yz"), z_pt[_BC]); - print_signed_float(PSTR("zx"), z_pt[_CA]); - print_signed_float(PSTR("xy"), z_pt[_AB]); + print_signed_float(F("yz"), z_pt[_BC]); + print_signed_float(F("zx"), z_pt[_CA]); + print_signed_float(F("xy"), z_pt[_AB]); } SERIAL_EOL(); } @@ -653,13 +651,13 @@ void GcodeSuite::G33() { } } else { // dry run - PGM_P const enddryrun = PSTR("End DRY-RUN"); - SERIAL_ECHOPGM_P(enddryrun); + FSTR_P const enddryrun = F("End DRY-RUN"); + SERIAL_ECHOF(enddryrun); SERIAL_ECHO_SP(35); SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3); char mess[21]; - strcpy_P(mess, enddryrun); + strcpy_P(mess, FTOP(enddryrun)); strcpy_P(&mess[11], PSTR(" sd:")); if (zero_std_dev < 1) sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev * 1000.0f)); diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 0e2d42907a..338392b597 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -51,7 +51,7 @@ * Also, there are two support functions that can be called from a developer's C code. * * uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start); - * void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size); + * void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size); * * Initial version by Roxy-3D */ @@ -182,8 +182,8 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { } } - void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size) { - SERIAL_ECHOLNPGM_P(title); + void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size) { + SERIAL_ECHOLNF(title); // // Round the start and end locations to produce full lines of output // @@ -196,8 +196,8 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { #endif // M100_FREE_MEMORY_DUMPER -inline int check_for_free_memory_corruption(PGM_P const title) { - SERIAL_ECHOPGM_P(title); +inline int check_for_free_memory_corruption(FSTR_P const title) { + SERIAL_ECHOF(title); char *start_free_memory = free_memory_start, *end_free_memory = free_memory_end; int n = end_free_memory - start_free_memory; @@ -217,7 +217,7 @@ inline int check_for_free_memory_corruption(PGM_P const title) { // idle(); serial_delay(20); #if ENABLED(M100_FREE_MEMORY_DUMPER) - M100_dump_routine(PSTR(" Memory corruption detected with end_free_memory, M532 X L) - cap_line(PSTR("PROGRESS")); + cap_line(F("PROGRESS")); // Print Job timer M75, M76, M77 - cap_line(PSTR("PRINT_JOB"), true); + cap_line(F("PRINT_JOB"), true); // AUTOLEVEL (G29) - cap_line(PSTR("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL)); + cap_line(F("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL)); // RUNOUT (M412, M600) - cap_line(PSTR("RUNOUT"), ENABLED(FILAMENT_RUNOUT_SENSOR)); + cap_line(F("RUNOUT"), ENABLED(FILAMENT_RUNOUT_SENSOR)); // Z_PROBE (G30) - cap_line(PSTR("Z_PROBE"), ENABLED(HAS_BED_PROBE)); + cap_line(F("Z_PROBE"), ENABLED(HAS_BED_PROBE)); // MESH_REPORT (M420 V) - cap_line(PSTR("LEVELING_DATA"), ENABLED(HAS_LEVELING)); + cap_line(F("LEVELING_DATA"), ENABLED(HAS_LEVELING)); // BUILD_PERCENT (M73) - cap_line(PSTR("BUILD_PERCENT"), ENABLED(LCD_SET_PROGRESS_MANUALLY)); + cap_line(F("BUILD_PERCENT"), ENABLED(LCD_SET_PROGRESS_MANUALLY)); // SOFTWARE_POWER (M80, M81) - cap_line(PSTR("SOFTWARE_POWER"), ENABLED(PSU_CONTROL)); + cap_line(F("SOFTWARE_POWER"), ENABLED(PSU_CONTROL)); // TOGGLE_LIGHTS (M355) - cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(CASE_LIGHT_ENABLE)); - cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, caselight.has_brightness())); + cap_line(F("TOGGLE_LIGHTS"), ENABLED(CASE_LIGHT_ENABLE)); + cap_line(F("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, caselight.has_brightness())); // EMERGENCY_PARSER (M108, M112, M410, M876) - cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); + cap_line(F("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); // HOST ACTION COMMANDS (paused, resume, resumed, cancel, etc.) - cap_line(PSTR("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS)); + cap_line(F("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS)); // PROMPT SUPPORT (M876) - cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); + cap_line(F("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); // SDCARD (M20, M23, M24, etc.) - cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT)); + cap_line(F("SDCARD"), ENABLED(SDSUPPORT)); // REPEAT (M808) - cap_line(PSTR("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); + cap_line(F("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); // SD_WRITE (M928, M28, M29) - cap_line(PSTR("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY)); + cap_line(F("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY)); // AUTOREPORT_SD_STATUS (M27 extension) - cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); + cap_line(F("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); // LONG_FILENAME_HOST_SUPPORT (M33) - cap_line(PSTR("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT)); + cap_line(F("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT)); // THERMAL_PROTECTION - cap_line(PSTR("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE)); + cap_line(F("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE)); // MOTION_MODES (M80-M89) - cap_line(PSTR("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES)); + cap_line(F("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES)); // ARC_SUPPORT (G2-G3) - cap_line(PSTR("ARCS"), ENABLED(ARC_SUPPORT)); + cap_line(F("ARCS"), ENABLED(ARC_SUPPORT)); // BABYSTEPPING (M290) - cap_line(PSTR("BABYSTEPPING"), ENABLED(BABYSTEPPING)); + cap_line(F("BABYSTEPPING"), ENABLED(BABYSTEPPING)); // CHAMBER_TEMPERATURE (M141, M191) - cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); + cap_line(F("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); // COOLER_TEMPERATURE (M143, M193) - cap_line(PSTR("COOLER_TEMPERATURE"), ENABLED(HAS_COOLER)); + cap_line(F("COOLER_TEMPERATURE"), ENABLED(HAS_COOLER)); // MEATPACK Compression - cap_line(PSTR("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack)); + cap_line(F("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack)); // Machine Geometry #if ENABLED(M115_GEOMETRY_REPORT) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 1830dea3bf..29b7ae602b 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -43,9 +43,15 @@ static void config_line(PGM_P const name, const float val, PGM_P const pref=null config_prefix(name, pref, ind); SERIAL_ECHOLN(val); } +static void config_line(FSTR_P const name, const float val, FSTR_P const pref=nullptr, const int8_t ind=-1) { + config_line(FTOP(name), val, FTOP(pref) , ind); +} static void config_line_e(const int8_t e, PGM_P const name, const float val) { config_line(name, val, PSTR("Extr."), e + 1); } +static void config_line_e(const int8_t e, FSTR_P const name, const float val) { + config_line_e(e, FTOP(name), val); +} /** * M360: Report Firmware configuration @@ -60,19 +66,19 @@ void GcodeSuite::M360() { // // Basics and Enabled items // - config_line(PSTR("Baudrate"), BAUDRATE); - config_line(PSTR("InputBuffer"), MAX_CMD_SIZE); - config_line(PSTR("PrintlineCache"), BUFSIZE); - config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); - config_line(PSTR("SDCard"), ENABLED(SDSUPPORT)); - config_line(PSTR("Fan"), ENABLED(HAS_FAN)); - config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY)); - config_line(PSTR("SoftwarePowerSwitch"), 1); - config_line(PSTR("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE)); - config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); - config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE)); - config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING)); - config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); + config_line(F("Baudrate"), BAUDRATE); + config_line(F("InputBuffer"), MAX_CMD_SIZE); + config_line(F("PrintlineCache"), BUFSIZE); + config_line(F("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); + config_line(F("SDCard"), ENABLED(SDSUPPORT)); + config_line(F("Fan"), ENABLED(HAS_FAN)); + config_line(F("LCD"), ENABLED(HAS_DISPLAY)); + config_line(F("SoftwarePowerSwitch"), 1); + config_line(F("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE)); + config_line(F("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); + config_line(F("ZProbe"), ENABLED(HAS_BED_PROBE)); + config_line(F("Autolevel"), ENABLED(HAS_LEVELING)); + config_line(F("EEPROM"), ENABLED(EEPROM_SETTINGS)); // // Homing Directions @@ -87,7 +93,7 @@ void GcodeSuite::M360() { // #if HAS_CLASSIC_JERK if (planner.max_jerk.x == planner.max_jerk.y) - config_line(PSTR("XY"), planner.max_jerk.x, JERK_STR); + config_line(F("XY"), planner.max_jerk.x, JERK_STR); else { config_line(X_STR, planner.max_jerk.x, JERK_STR); config_line(Y_STR, planner.max_jerk.y, JERK_STR); @@ -98,21 +104,21 @@ void GcodeSuite::M360() { // // Firmware Retraction // - config_line(PSTR("SupportG10G11"), ENABLED(FWRETRACT)); + config_line(F("SupportG10G11"), ENABLED(FWRETRACT)); #if ENABLED(FWRETRACT) PGMSTR(RET_STR, "Retraction"); PGMSTR(UNRET_STR, "RetractionUndo"); PGMSTR(SPEED_STR, "Speed"); // M10 Retract with swap (long) moves - config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR); + config_line(F("Length"), fwretract.settings.retract_length, RET_STR); config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); - config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR); - config_line(PSTR("LongLength"), fwretract.settings.swap_retract_length, RET_STR); + config_line(F("ZLift"), fwretract.settings.retract_zraise, RET_STR); + config_line(F("LongLength"), fwretract.settings.swap_retract_length, RET_STR); // M11 Recover (undo) with swap (long) moves config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); - config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); - config_line(PSTR("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); - config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); + config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); + config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); + config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); #endif // @@ -163,22 +169,22 @@ void GcodeSuite::M360() { // // Heated Bed // - config_line(PSTR("HeatedBed"), ENABLED(HAS_HEATED_BED)); + config_line(F("HeatedBed"), ENABLED(HAS_HEATED_BED)); #if HAS_HEATED_BED - config_line(PSTR("MaxBedTemp"), BED_MAX_TARGET); + config_line(F("MaxBedTemp"), BED_MAX_TARGET); #endif // // Per-Extruder settings // - config_line(PSTR("NumExtruder"), EXTRUDERS); + config_line(F("NumExtruder"), EXTRUDERS); #if HAS_EXTRUDERS LOOP_L_N(e, EXTRUDERS) { config_line_e(e, JERK_STR, TERN(HAS_LINEAR_E_JERK, planner.max_e_jerk[E_INDEX_N(e)], TERN(HAS_CLASSIC_JERK, planner.max_jerk.e, DEFAULT_EJERK))); - config_line_e(e, PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); - config_line_e(e, PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); - config_line_e(e, PSTR("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e])); - config_line_e(e, PSTR("MaxTemp"), thermalManager.hotend_maxtemp[e]); + config_line_e(e, F("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); + config_line_e(e, F("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); + config_line_e(e, F("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e])); + config_line_e(e, F("MaxTemp"), thermalManager.hotend_maxtemp[e]); } #endif } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 5424809699..9c3175da58 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -302,10 +302,10 @@ static bool serial_data_available(serial_index_t index) { inline int read_serial(const serial_index_t index) { return SERIAL_IMPL.read(index); } -void GCodeQueue::gcode_line_error(PGM_P const err, const serial_index_t serial_ind) { +void GCodeQueue::gcode_line_error(FSTR_P const ferr, const serial_index_t serial_ind) { PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command SERIAL_ERROR_START(); - SERIAL_ECHOLNPGM_P(err, serial_state[serial_ind.index].last_N); + SERIAL_ECHOLNF(ferr, serial_state[serial_ind.index].last_N); while (read_serial(serial_ind) != -1) { /* nada */ } // Clear out the RX buffer. Why don't use flush here ? flush_and_request_resend(serial_ind); serial_state[serial_ind.index].count = 0; @@ -470,7 +470,7 @@ void GCodeQueue::get_serial_commands() { if (gcode_N != serial.last_N + 1 && !M110) { // In case of error on a serial port, don't prevent other serial port from making progress - gcode_line_error(PSTR(STR_ERR_LINE_NO), p); + gcode_line_error(F(STR_ERR_LINE_NO), p); break; } @@ -480,13 +480,13 @@ void GCodeQueue::get_serial_commands() { while (count) checksum ^= command[--count]; if (strtol(apos + 1, nullptr, 10) != checksum) { // In case of error on a serial port, don't prevent other serial port from making progress - gcode_line_error(PSTR(STR_ERR_CHECKSUM_MISMATCH), p); + gcode_line_error(F(STR_ERR_CHECKSUM_MISMATCH), p); break; } } else { // In case of error on a serial port, don't prevent other serial port from making progress - gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), p); + gcode_line_error(F(STR_ERR_NO_CHECKSUM), p); break; } @@ -495,7 +495,7 @@ void GCodeQueue::get_serial_commands() { #if ENABLED(SDSUPPORT) // Pronterface "M29" and "M29 " has no line number else if (card.flag.saving && !is_M29(command)) { - gcode_line_error(PSTR(STR_ERR_NO_CHECKSUM), p); + gcode_line_error(F(STR_ERR_NO_CHECKSUM), p); break; } #endif diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 71a710b8cb..c5562da3aa 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -259,7 +259,7 @@ private: */ static bool enqueue_one(const char *cmd); - static void gcode_line_error(PGM_P const err, const serial_index_t serial_ind); + static void gcode_line_error(FSTR_P const ferr, const serial_index_t serial_ind); friend class GcodeSuite; }; diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index adfaa3b043..4178807951 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -34,7 +34,7 @@ millis_t Stopwatch::startTimestamp; millis_t Stopwatch::stopTimestamp; bool Stopwatch::stop() { - Stopwatch::debug(PSTR("stop")); + debug(F("stop")); if (isRunning() || isPaused()) { TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStopped()); @@ -46,7 +46,7 @@ bool Stopwatch::stop() { } bool Stopwatch::pause() { - Stopwatch::debug(PSTR("pause")); + debug(F("pause")); if (isRunning()) { TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerPaused()); @@ -58,7 +58,7 @@ bool Stopwatch::pause() { } bool Stopwatch::start() { - Stopwatch::debug(PSTR("start")); + debug(F("start")); TERN_(EXTENSIBLE_UI, ExtUI::onPrintTimerStarted()); @@ -74,14 +74,14 @@ bool Stopwatch::start() { } void Stopwatch::resume(const millis_t with_time) { - Stopwatch::debug(PSTR("resume")); + debug(F("resume")); reset(); if ((accumulator = with_time)) state = RUNNING; } void Stopwatch::reset() { - Stopwatch::debug(PSTR("reset")); + debug(F("reset")); state = STOPPED; startTimestamp = 0; @@ -95,12 +95,8 @@ millis_t Stopwatch::duration() { #if ENABLED(DEBUG_STOPWATCH) - void Stopwatch::debug(const char func[]) { - if (DEBUGGING(INFO)) { - SERIAL_ECHOPGM("Stopwatch::"); - SERIAL_ECHOPGM_P(func); - SERIAL_ECHOLNPGM("()"); - } + void Stopwatch::debug(FSTR_P const func) { + if (DEBUGGING(INFO)) SERIAL_ECHOLNPGM("Stopwatch::", func, "()"); } #endif diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index b64a36a90e..fe5101a5be 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -21,14 +21,11 @@ */ #pragma once +#include "../inc/MarlinConfig.h" + // Print debug messages with M111 S2 (Uses 156 bytes of PROGMEM) //#define DEBUG_STOPWATCH -#include "../core/macros.h" // for FORCE_INLINE - -#include -typedef uint32_t millis_t; - /** * @brief Stopwatch class * @details This class acts as a timer proving stopwatch functionality including @@ -113,11 +110,11 @@ class Stopwatch { * @brief Print a debug message * @details Print a simple debug message "Stopwatch::function" */ - static void debug(const char func[]); + static void debug(FSTR_P const); #else - static inline void debug(const char[]) {} + static inline void debug(FSTR_P const) {} #endif }; diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index 4db8fb5f2e..614d2121b8 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -75,8 +75,8 @@ void vector_3::apply_rotation(const matrix_3x3 &matrix) { matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z }; } -void vector_3::debug(PGM_P const title) { - SERIAL_ECHOPGM_P(title); +void vector_3::debug(FSTR_P const title) { + SERIAL_ECHOF(title); SERIAL_ECHOPAIR_F_P(SP_X_STR, x, 6); SERIAL_ECHOPAIR_F_P(SP_Y_STR, y, 6); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z, 6); @@ -100,14 +100,14 @@ void matrix_3x3::set_to_identity() { // Create a matrix from 3 vector_3 inputs matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2) { - //row_0.debug(PSTR("row_0")); - //row_1.debug(PSTR("row_1")); - //row_2.debug(PSTR("row_2")); + //row_0.debug(F("row_0")); + //row_1.debug(F("row_1")); + //row_2.debug(F("row_2")); matrix_3x3 new_matrix; new_matrix.vectors[0] = row_0; new_matrix.vectors[1] = row_1; new_matrix.vectors[2] = row_2; - //new_matrix.debug(PSTR("new_matrix")); + //new_matrix.debug(F("new_matrix")); return new_matrix; } @@ -117,14 +117,14 @@ matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { x_row = vector_3(1, 0, -target.x / target.z).get_normal(), y_row = vector_3::cross(z_row, x_row).get_normal(); - // x_row.debug(PSTR("x_row")); - // y_row.debug(PSTR("y_row")); - // z_row.debug(PSTR("z_row")); + // x_row.debug(F("x_row")); + // y_row.debug(F("y_row")); + // z_row.debug(F("z_row")); // create the matrix already correctly transposed matrix_3x3 rot = matrix_3x3::create_from_rows(x_row, y_row, z_row); - // rot.debug(PSTR("rot")); + // rot.debug(F("rot")); return rot; } @@ -137,8 +137,8 @@ matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { return new_matrix; } -void matrix_3x3::debug(PGM_P const title) { - if (title) SERIAL_ECHOLNPGM_P(title); +void matrix_3x3::debug(FSTR_P const title) { + if (title) SERIAL_ECHOLNF(title); LOOP_L_N(i, 3) { LOOP_L_N(j, 3) { if (vectors[i][j] >= 0.0) SERIAL_CHAR('+'); diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 5d99fcec20..f515333cc7 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -78,7 +78,7 @@ struct vector_3 { operator xy_float_t() { return xy_float_t({ x, y }); } operator xyz_float_t() { return xyz_float_t({ x, y, z }); } - void debug(PGM_P const title); + void debug(FSTR_P const title); }; struct matrix_3x3 { @@ -91,7 +91,7 @@ struct matrix_3x3 { void set_to_identity(); - void debug(PGM_P const title); + void debug(FSTR_P const title); void apply_rotation_xyz(float &x, float &y, float &z); }; diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index b5f270ee63..80e20a0778 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -483,10 +483,10 @@ void Endstops::event_handler() { #pragma GCC diagnostic ignored "-Wunused-function" #endif -static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { - if (label) SERIAL_ECHOPGM_P(label); +static void print_es_state(const bool is_hit, FSTR_P const flabel=nullptr) { + if (flabel) SERIAL_ECHOF(flabel); SERIAL_ECHOPGM(": "); - SERIAL_ECHOLNPGM_P(is_hit ? PSTR(STR_ENDSTOP_HIT) : PSTR(STR_ENDSTOP_OPEN)); + SERIAL_ECHOLNF(is_hit ? F(STR_ENDSTOP_HIT) : F(STR_ENDSTOP_OPEN)); } #if GCC_VERSION <= 50000 @@ -496,7 +496,7 @@ static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { void _O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); - #define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, PSTR(STR_##S)) + #define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, F(STR_##S)) #if HAS_X_MIN ES_REPORT(X_MIN); #endif @@ -564,10 +564,10 @@ void _O2 Endstops::report_states() { ES_REPORT(K_MAX); #endif #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) - print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN)); + print_es_state(probe_switch_activated(), F(STR_PROBE_EN)); #endif #if USES_Z_MIN_PROBE_PIN - print_es_state(PROBE_TRIGGERED(), PSTR(STR_Z_PROBE)); + print_es_state(PROBE_TRIGGERED(), F(STR_Z_PROBE)); #endif #if MULTI_FILAMENT_SENSOR #define _CASE_RUNOUT(N) case N: pin = FIL_RUNOUT##N##_PIN; state = FIL_RUNOUT##N##_STATE; break; @@ -584,7 +584,7 @@ void _O2 Endstops::report_states() { } #undef _CASE_RUNOUT #elif HAS_FILAMENT_SENSOR - print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, PSTR(STR_FILAMENT)); + print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, F(STR_FILAMENT)); #endif TERN_(BLTOUCH, bltouch._reset_SW_mode()); diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index b384342335..e5db7f7b54 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -178,7 +178,7 @@ static void print_input_or_output(const bool isout) { } // pretty report with PWM info -inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool extended=false, PGM_P const start_string=nullptr) { +inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool extended=false, FSTR_P const start_string=nullptr) { char buffer[MAX_NAME_LENGTH + 1]; // for the sprintf statements bool found = false, multi_name_pin = false; @@ -202,7 +202,7 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e 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) { // report digital and analog pin number only on the first time through - if (start_string) SERIAL_ECHOPGM_P(start_string); + if (start_string) SERIAL_ECHOF(start_string); SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); @@ -211,7 +211,7 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e } else { SERIAL_CHAR('.'); - SERIAL_ECHO_SP(MULTI_NAME_PAD + (start_string ? strlen_P(start_string) : 0)); // add padding if not the first instance found + SERIAL_ECHO_SP(MULTI_NAME_PAD + (start_string ? strlen_P(FTOP(start_string)) : 0)); // add padding if not the first instance found } PRINT_ARRAY_NAME(x); if (extended) { @@ -250,7 +250,7 @@ inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool e } // end of for loop if (!found) { - if (start_string) SERIAL_ECHOPGM_P(start_string); + if (start_string) SERIAL_ECHOF(start_string); SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); PRINT_PORT(pin); From d1938d54ed5e42d766d97d898cd117893ea24083 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Sep 2021 19:28:29 -0500 Subject: [PATCH 0762/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20MKS?= =?UTF-8?q?=20UI=20errors,=20assets?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../lcd/extui/mks_ui/draw_error_message.cpp | 9 +- .../src/lcd/extui/mks_ui/draw_error_message.h | 2 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 28 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.h | 5 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 268 +++++++++--------- 5 files changed, 159 insertions(+), 153 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index 6955e1803d..bc15100153 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -33,11 +33,12 @@ static lv_obj_t *scr; -void lv_draw_error_message(PGM_P const msg) { +void lv_draw_error_message(FSTR_P const fmsg) { + FSTR_P fhalted = F("PRINTER HALTED"), fplease = F("Please Reset"); SPI_TFT.LCD_clear(0x0000); - if (msg) disp_string((TFT_WIDTH - strlen(msg) * 16) / 2, 100, msg, 0xFFFF, 0x0000); - disp_string((TFT_WIDTH - strlen("PRINTER HALTED") * 16) / 2, 140, "PRINTER HALTED", 0xFFFF, 0x0000); - disp_string((TFT_WIDTH - strlen("Please Reset") * 16) / 2, 180, "Please Reset", 0xFFFF, 0x0000); + if (fmsg) disp_string((TFT_WIDTH - strlen_P(FTOP(fmsg)) * 16) / 2, 100, fmsg, 0xFFFF, 0x0000); + disp_string((TFT_WIDTH - strlen_P(FTOP(fhalted)) * 16) / 2, 140, fhalted, 0xFFFF, 0x0000); + disp_string((TFT_WIDTH - strlen_P(FTOP(fplease)) * 16) / 2, 180, fplease, 0xFFFF, 0x0000); } void lv_clear_error_message() { lv_obj_del(scr); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.h b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h index 6999ecf5e4..8963e7f477 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h @@ -29,7 +29,7 @@ #define PGM_P const char * #endif -void lv_draw_error_message(PGM_P const msg); +void lv_draw_error_message(FSTR_P const fmsg); void lv_clear_error_message(); #ifdef __cplusplus diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 3bd04563ba..4305462162 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -697,24 +697,28 @@ void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint1 } } -void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor) { - while (*string != '\0') { - disp_char_1624(x, y, *string, charColor, bkColor); - string++; - x += 16; - } +void disp_string(uint16_t x, uint16_t y, const char * cstr, uint16_t charColor, uint16_t bkColor) { + for (char c; (c = *cstr); cstr++, x += 16) + disp_char_1624(x, y, c, charColor, bkColor); +} + +void disp_string(uint16_t x, uint16_t y, FSTR_P const fstr, uint16_t charColor, uint16_t bkColor) { + PGM_P pstr = FTOP(fstr); + for (char c; (c = pgm_read_byte(pstr)); pstr++, x += 16) + disp_char_1624(x, y, c, charColor, bkColor); } void disp_assets_update() { SPI_TFT.LCD_clear(0x0000); - disp_string(100, 140, "Assets Updating...", 0xFFFF, 0x0000); + disp_string(100, 140, F("Assets Updating..."), 0xFFFF, 0x0000); } -void disp_assets_update_progress(const char *msg) { - char buf[30]; - memset(buf, ' ', COUNT(buf)); - strncpy(buf, msg, strlen(msg)); - buf[COUNT(buf) - 1] = '\0'; +void disp_assets_update_progress(FSTR_P const fmsg) { + static constexpr int buflen = 30; + char buf[buflen]; + memset(buf, ' ', buflen); + strncpy_P(buf, FTOP(fmsg), buflen - 1); + buf[buflen - 1] = '\0'; disp_string(100, 165, buf, 0xFFFF, 0x0000); } diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h index 5313265662..c0cdacd963 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -36,6 +36,7 @@ #endif // String display and assets -void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor); +void disp_string(uint16_t x, uint16_t y, const char * cstr, uint16_t charColor, uint16_t bkColor); +void disp_string(uint16_t x, uint16_t y, FSTR_P const fstr, uint16_t charColor, uint16_t bkColor); void disp_assets_update(); -void disp_assets_update_progress(const char *msg); +void disp_assets_update_progress(FSTR_P const msg); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 8333709074..ba2df10ecb 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -40,186 +40,186 @@ extern uint16_t DeviceCode; extern char *createFilename(char * const buffer, const dir_t &p); #endif -static const char assets[][LONG_FILENAME_LENGTH] = { +static FSTR_P const assets[] = { // Homing screen - "bmp_zeroAll.bin", - "bmp_zero.bin", - "bmp_zeroX.bin", - "bmp_zeroY.bin", - "bmp_zeroZ.bin", - "bmp_manual_off.bin", + F("bmp_zeroAll.bin"), + F("bmp_zero.bin"), + F("bmp_zeroX.bin"), + F("bmp_zeroY.bin"), + F("bmp_zeroZ.bin"), + F("bmp_manual_off.bin"), // Tool screen - "bmp_preHeat.bin", - "bmp_extruct.bin", - "bmp_mov.bin", - "bmp_leveling.bin", - "bmp_filamentchange.bin", - "bmp_more.bin", + F("bmp_preHeat.bin"), + F("bmp_extruct.bin"), + F("bmp_mov.bin"), + F("bmp_leveling.bin"), + F("bmp_filamentchange.bin"), + F("bmp_more.bin"), // Fan screen - "bmp_Add.bin", - "bmp_Dec.bin", - "bmp_speed255.bin", - "bmp_speed127.bin", - "bmp_speed0.bin", + F("bmp_Add.bin"), + F("bmp_Dec.bin"), + F("bmp_speed255.bin"), + F("bmp_speed127.bin"), + F("bmp_speed0.bin"), - "bmp_bed.bin", - "bmp_step1_degree.bin", - "bmp_step5_degree.bin", - "bmp_step10_degree.bin", + F("bmp_bed.bin"), + F("bmp_step1_degree.bin"), + F("bmp_step5_degree.bin"), + F("bmp_step10_degree.bin"), // Extrusion screen - "bmp_in.bin", - "bmp_out.bin", - "bmp_extru1.bin", + F("bmp_in.bin"), + F("bmp_out.bin"), + F("bmp_extru1.bin"), #if HAS_MULTI_EXTRUDER - "bmp_extru2.bin", + F("bmp_extru2.bin"), #endif - "bmp_speed_high.bin", - "bmp_speed_slow.bin", - "bmp_speed_normal.bin", - "bmp_step1_mm.bin", - "bmp_step5_mm.bin", - "bmp_step10_mm.bin", + F("bmp_speed_high.bin"), + F("bmp_speed_slow.bin"), + F("bmp_speed_normal.bin"), + F("bmp_step1_mm.bin"), + F("bmp_step5_mm.bin"), + F("bmp_step10_mm.bin"), // Select file screen - "bmp_pageUp.bin", - "bmp_pageDown.bin", - "bmp_back.bin", //TODO: why two back buttons? Why not just one? (return / back) - "bmp_dir.bin", - "bmp_file.bin", + F("bmp_pageUp.bin"), + F("bmp_pageDown.bin"), + F("bmp_back.bin"), // TODO: why two back buttons? Why not just one? (return / back) + F("bmp_dir.bin"), + F("bmp_file.bin"), // Move motor screen // TODO: 6 equal icons, just in diffenct rotation... it may be optimized too - "bmp_xAdd.bin", - "bmp_xDec.bin", - "bmp_yAdd.bin", - "bmp_yDec.bin", - "bmp_zAdd.bin", - "bmp_zDec.bin", - "bmp_step_move0_1.bin", - "bmp_step_move1.bin", - "bmp_step_move10.bin", + F("bmp_xAdd.bin"), + F("bmp_xDec.bin"), + F("bmp_yAdd.bin"), + F("bmp_yDec.bin"), + F("bmp_zAdd.bin"), + F("bmp_zDec.bin"), + F("bmp_step_move0_1.bin"), + F("bmp_step_move1.bin"), + F("bmp_step_move10.bin"), // Operation screen - "bmp_auto_off.bin", - "bmp_speed.bin", - "bmp_fan.bin", - "bmp_temp.bin", - "bmp_extrude_opr.bin", - "bmp_move_opr.bin", + F("bmp_auto_off.bin"), + F("bmp_speed.bin"), + F("bmp_fan.bin"), + F("bmp_temp.bin"), + F("bmp_extrude_opr.bin"), + F("bmp_move_opr.bin"), // Change speed screen - "bmp_step1_percent.bin", - "bmp_step5_percent.bin", - "bmp_step10_percent.bin", - "bmp_extruct_sel.bin", - "bmp_mov_changespeed.bin", - "bmp_mov_sel.bin", - "bmp_speed_extruct.bin", + F("bmp_step1_percent.bin"), + F("bmp_step5_percent.bin"), + F("bmp_step10_percent.bin"), + F("bmp_extruct_sel.bin"), + F("bmp_mov_changespeed.bin"), + F("bmp_mov_sel.bin"), + F("bmp_speed_extruct.bin"), // Printing screen - "bmp_pause.bin", - "bmp_resume.bin", - "bmp_stop.bin", - "bmp_ext1_state.bin", + F("bmp_pause.bin"), + F("bmp_resume.bin"), + F("bmp_stop.bin"), + F("bmp_ext1_state.bin"), #if HAS_MULTI_EXTRUDER - "bmp_ext2_state.bin", + F("bmp_ext2_state.bin"), #endif - "bmp_bed_state.bin", - "bmp_fan_state.bin", - "bmp_time_state.bin", - "bmp_zpos_state.bin", - "bmp_operate.bin", + F("bmp_bed_state.bin"), + F("bmp_fan_state.bin"), + F("bmp_time_state.bin"), + F("bmp_zpos_state.bin"), + F("bmp_operate.bin"), // Manual Level screen (only if auto level is disabled) #if DISABLED(AUTO_BED_LEVELING_BILINEAR) - "bmp_leveling1.bin", - "bmp_leveling2.bin", - "bmp_leveling3.bin", - "bmp_leveling4.bin", - "bmp_leveling5.bin", + F("bmp_leveling1.bin"), + F("bmp_leveling2.bin"), + F("bmp_leveling3.bin"), + F("bmp_leveling4.bin"), + F("bmp_leveling5.bin"), #endif // Language Select screen #if HAS_LANG_SELECT_SCREEN - "bmp_language.bin", - "bmp_simplified_cn.bin", - "bmp_simplified_cn_sel.bin", - "bmp_traditional_cn.bin", - "bmp_traditional_cn_sel.bin", - "bmp_english.bin", - "bmp_english_sel.bin", - "bmp_russian.bin", - "bmp_russian_sel.bin", - "bmp_spanish.bin", - "bmp_spanish_sel.bin", - "bmp_french.bin", - "bmp_french_sel.bin", - "bmp_italy.bin", - "bmp_italy_sel.bin", + F("bmp_language.bin"), + F("bmp_simplified_cn.bin"), + F("bmp_simplified_cn_sel.bin"), + F("bmp_traditional_cn.bin"), + F("bmp_traditional_cn_sel.bin"), + F("bmp_english.bin"), + F("bmp_english_sel.bin"), + F("bmp_russian.bin"), + F("bmp_russian_sel.bin"), + F("bmp_spanish.bin"), + F("bmp_spanish_sel.bin"), + F("bmp_french.bin"), + F("bmp_french_sel.bin"), + F("bmp_italy.bin"), + F("bmp_italy_sel.bin"), #endif // HAS_LANG_SELECT_SCREEN // G-code preview #if HAS_GCODE_DEFAULT_VIEW_IN_FLASH - "bmp_preview.bin", + F("bmp_preview.bin"), #endif #if HAS_LOGO_IN_FLASH - "bmp_logo.bin", + F("bmp_logo.bin"), #endif // Settings screen - "bmp_about.bin", - "bmp_eeprom_settings.bin", - "bmp_machine_para.bin", - "bmp_function1.bin", + F("bmp_about.bin"), + F("bmp_eeprom_settings.bin"), + F("bmp_machine_para.bin"), + F("bmp_function1.bin"), // Start screen - "bmp_printing.bin", - "bmp_set.bin", - "bmp_tool.bin", + F("bmp_printing.bin"), + F("bmp_set.bin"), + F("bmp_tool.bin"), // Base icons - "bmp_arrow.bin", - "bmp_back70x40.bin", - "bmp_value_blank.bin", - "bmp_blank_sel.bin", - "bmp_disable.bin", - "bmp_enable.bin", - "bmp_return.bin", + F("bmp_arrow.bin"), + F("bmp_back70x40.bin"), + F("bmp_value_blank.bin"), + F("bmp_blank_sel.bin"), + F("bmp_disable.bin"), + F("bmp_enable.bin"), + F("bmp_return.bin"), #if ENABLED(MKS_WIFI_MODULE) // Wifi screen - "bmp_wifi.bin", - "bmp_cloud.bin", + F("bmp_wifi.bin"), + F("bmp_cloud.bin"), #endif #if ENABLED(MULTI_VOLUME) - "bmp_usb_disk.bin", - // "bmp_usb_disk_sel.bin", - "bmp_sd.bin", - // "bmp_sd_sel.bin", + F("bmp_usb_disk.bin"), + //F("bmp_usb_disk_sel.bin"), + F("bmp_sd.bin"), + //F("bmp_sd_sel.bin"), #endif // Babystep screen - "bmp_baby_move0_01.bin", - "bmp_baby_move0_05.bin", - "bmp_baby_move0_1.bin", + F("bmp_baby_move0_01.bin"), + F("bmp_baby_move0_05.bin"), + F("bmp_baby_move0_1.bin"), // More screen - "bmp_custom1.bin", - "bmp_custom2.bin", - "bmp_custom3.bin", - "bmp_custom4.bin", - "bmp_custom5.bin", - "bmp_custom6.bin", - "bmp_custom7.bin" + F("bmp_custom1.bin"), + F("bmp_custom2.bin"), + F("bmp_custom3.bin"), + F("bmp_custom4.bin"), + F("bmp_custom5.bin"), + F("bmp_custom6.bin"), + F("bmp_custom7.bin") }; #if HAS_SPI_FLASH_FONT - static char fonts[][LONG_FILENAME_LENGTH] = { "FontUNIGBK.bin" }; + static FSTR_P const fonts[] = { F("FontUNIGBK.bin") }; #endif uint8_t currentFlashPage = 0; @@ -386,9 +386,9 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { longName[j] = '\0'; } - static int8_t arrayFindStr(const char arr[][LONG_FILENAME_LENGTH], uint8_t arraySize, const char *str) { + static int8_t arrayFindStr(FSTR_P const arr[], uint8_t arraySize, const char *str) { for (uint8_t a = 0; a < arraySize; a++) { - if (strcasecmp(arr[a], str) == 0) + if (strcasecmp(FTOP(arr[a]), str) == 0) return a; } return -1; @@ -403,7 +403,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { #define ASSET_TYPE_TITLE_LOGO 2 #define ASSET_TYPE_G_PREVIEW 3 #define ASSET_TYPE_FONT 4 - static void loadAsset(SdFile &dir, dir_t& entry, const char *fn, int8_t assetType) { + static void loadAsset(SdFile &dir, dir_t& entry, FSTR_P const fn, int8_t assetType) { SdFile file; char dosFilename[FILENAME_LENGTH]; createFilename(dosFilename, entry); @@ -429,14 +429,14 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { do { watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); - Pic_Logo_Write((uint8_t *)fn, public_buf, pbr); + Pic_Logo_Write((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_TITLE_LOGO) { do { watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); - Pic_TitleLogo_Write((uint8_t *)fn, public_buf, pbr); + Pic_TitleLogo_Write((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_G_PREVIEW) { @@ -447,7 +447,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_ICON) { - Pic_Write_Addr = Pic_Info_Write((uint8_t *)fn, pfileSize); + Pic_Write_Addr = Pic_Info_Write((uint8_t*)fn, pfileSize); SPIFlash.beginWrite(Pic_Write_Addr); #if HAS_SPI_FLASH_COMPRESSION do { @@ -492,16 +492,16 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { if (dir.open(&root, assetsPath, O_RDONLY)) { disp_assets_update(); - disp_assets_update_progress("Erasing pics..."); + disp_assets_update_progress(F("Erasing pics...")); watchdog_refresh(); spiFlashErase_PIC(); #if HAS_SPI_FLASH_FONT - disp_assets_update_progress("Erasing fonts..."); + disp_assets_update_progress(F("Erasing fonts...")); watchdog_refresh(); spiFlashErase_FONT(); #endif - disp_assets_update_progress("Reading files..."); + disp_assets_update_progress(F("Reading files...")); dir_t d; while (dir.readDir(&d, card.longFilename) > 0) { // If we don't get a long name, but gets a short one, try it @@ -513,11 +513,11 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { int8_t a = arrayFindStr(assets, COUNT(assets), card.longFilename); if (a >= 0 && a < (int8_t)COUNT(assets)) { uint8_t assetType = ASSET_TYPE_ICON; - if (strstr(assets[a], "_logo")) + if (strstr_P(FTOP(assets[a]), PSTR("_logo"))) assetType = ASSET_TYPE_LOGO; - else if (strstr(assets[a], "_titlelogo")) + else if (strstr_P(FTOP(assets[a]), PSTR("_titlelogo"))) assetType = ASSET_TYPE_TITLE_LOGO; - else if (strstr(assets[a], "_preview")) + else if (strstr_P(FTOP(assets[a]), PSTR("_preview"))) assetType = ASSET_TYPE_G_PREVIEW; loadAsset(dir, d, assets[a], assetType); From 65b950a489c35b1d5547da3a504af4dad8cde3d7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Sep 2021 20:15:52 -0500 Subject: [PATCH 0763/2168] =?UTF-8?q?=F0=9F=8E=A8=20Apply=20F()=20to=20kil?= =?UTF-8?q?l=20/=20sendinfoscreen?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 6 +-- Marlin/src/MarlinCore.h | 2 +- Marlin/src/feature/direct_stepping.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 2 +- Marlin/src/feature/mmu/mmu2.cpp | 2 +- Marlin/src/feature/pause.cpp | 2 +- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/gcode/control/M108_M112_M410.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode_d.cpp | 2 +- Marlin/src/gcode/host/M16.cpp | 2 +- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/gcode/queue.cpp | 2 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 2 +- .../extui/anycubic_chiron/chiron_extui.cpp | 4 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.h | 2 +- .../extui/anycubic_i3mega/anycubic_extui.cpp | 2 +- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 2 +- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 4 +- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 6 +-- .../lcd/extui/dgus/fysetc/DGUSScreenHandler.h | 6 +++ .../extui/dgus/hiprecy/DGUSScreenHandler.h | 6 +++ .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 4 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 6 +++ .../lcd/extui/dgus/origin/DGUSScreenHandler.h | 6 +++ .../extui/dgus_reloaded/DGUSScreenHandler.cpp | 6 +-- .../extui/dgus_reloaded/DGUSScreenHandler.h | 2 +- .../dgus_reloaded/dgus_reloaded_extui.cpp | 2 +- Marlin/src/lcd/extui/example/example.cpp | 2 +- .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 6 +-- Marlin/src/lcd/extui/malyan/malyan.cpp | 41 ++++++++------- Marlin/src/lcd/extui/malyan/malyan.h | 6 +-- Marlin/src/lcd/extui/malyan/malyan_extui.cpp | 24 ++++----- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- .../src/lcd/extui/nextion/nextion_extui.cpp | 2 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 10 ++-- .../src/lcd/extui/nextion/nextion_tft_defs.h | 4 +- Marlin/src/lcd/extui/ui_api.cpp | 3 +- Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/lcd/marlinui.cpp | 4 +- Marlin/src/lcd/marlinui.h | 4 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/planner.cpp | 2 +- Marlin/src/module/probe.cpp | 2 +- Marlin/src/module/temperature.cpp | 52 +++++++++---------- Marlin/src/module/temperature.h | 2 +- Marlin/src/module/tool_change.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 2 +- 52 files changed, 149 insertions(+), 123 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8a15c45f83..346c5f8f2c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -852,16 +852,16 @@ void idle(bool no_stepper_sleep/*=false*/) { * Kill all activity and lock the machine. * After this the machine will need to be reset. */ -void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { +void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control // Echo the LCD message to serial for extra context - if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P(lcd_error); } + if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNF(lcd_error); } #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) - ui.kill_screen(lcd_error ?: GET_TEXT(MSG_KILLED), lcd_component ?: NUL_STR); + ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); #else UNUSED(lcd_error); UNUSED(lcd_component); #endif diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index c3698d616d..7063c7e2de 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -38,7 +38,7 @@ inline void idle_no_sleep() { idle(true); } extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed #endif -void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false); +void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); void minkill(const bool steppers_off=false); // Global State of the firmware diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index ce979145a1..b8ef04fcd9 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -174,7 +174,7 @@ namespace DirectStepping { template void SerialPageManager::write_responses() { if (fatal_error) { - kill(GET_TEXT(MSG_BAD_PAGE)); + kill(GET_TEXT_F(MSG_BAD_PAGE)); return; } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index f843011b5d..87e611f86c 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -153,7 +153,7 @@ void I2CPositionEncoder::update() { #ifdef I2CPE_ERR_THRESH_ABORT if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.settings.axis_steps_per_mm[encoderAxis]) { - //kill(PSTR("Significant Error")); + //kill(F("Significant Error")); SERIAL_ECHOLNPGM("Axis error over threshold, aborting!", error); safe_delay(5000); } diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index b2835dc3ce..56e6e6150b 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -448,7 +448,7 @@ bool MMU2::rx_ok() { void MMU2::check_version() { if (buildnr < MMU_REQUIRED_FW_BUILDNR) { SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); - kill(GET_TEXT(MSG_KILL_MMU2_FIRMWARE)); + kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); } } diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 8a35a87eeb..643c4ef9fc 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -254,7 +254,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT(MSG_FILAMENT_CHANGE_PURGE), CONTINUE_STR)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index bc19c9b18e..723ec1903b 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -301,7 +301,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW retract_and_lift(zraise); #endif - kill(GET_TEXT(MSG_OUTAGE_RECOVERY)); + kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); } #endif diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index c11d2e5f6d..82c10e6e8e 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -212,7 +212,7 @@ if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); TERN_(TMC_DEBUG, tmc_report_all()); - kill(PSTR("Driver error")); + kill(F("Driver error")); } #endif diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp index 309c806c8f..39f9c04e19 100644 --- a/Marlin/src/gcode/control/M108_M112_M410.cpp +++ b/Marlin/src/gcode/control/M108_M112_M410.cpp @@ -40,7 +40,7 @@ void GcodeSuite::M108() { * M112: Full Shutdown */ void GcodeSuite::M112() { - kill(M112_KILL_STR, nullptr, true); + kill(FPSTR(M112_KILL_STR), nullptr, true); } /** diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 126f7452b8..e0d6101ae2 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -261,7 +261,7 @@ void GcodeSuite::dwell(millis_t time) { #ifdef ACTION_ON_CANCEL host_action_cancel(); #endif - kill(GET_TEXT(MSG_LCD_PROBING_FAILED)); + kill(GET_TEXT_F(MSG_LCD_PROBING_FAILED)); #endif } diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 83646ef67c..204455e65e 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -58,7 +58,7 @@ void GcodeSuite::D(const int16_t dcode) { break; case 10: - kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P')); + kill(F("D10"), F("KILL TEST"), parser.seen_test('P')); break; case 1: { diff --git a/Marlin/src/gcode/host/M16.cpp b/Marlin/src/gcode/host/M16.cpp index 1ac8580396..03e734daaa 100644 --- a/Marlin/src/gcode/host/M16.cpp +++ b/Marlin/src/gcode/host/M16.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M16() { if (strcmp_P(parser.string_arg, PSTR(MACHINE_NAME))) - kill(GET_TEXT(MSG_KILL_EXPECTED_PRINTER)); + kill(GET_TEXT_F(MSG_KILL_EXPECTED_PRINTER)); } diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 17481f0198..239366fec8 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -67,7 +67,7 @@ void GcodeSuite::M0_M1() { #elif ENABLED(EXTENSIBLE_UI) if (parser.string_arg) - ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? + ExtUI::onUserConfirmRequired(parser.string_arg); // String in an SRAM buffer else ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 9c3175da58..cc072e51a1 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -523,7 +523,7 @@ void GCodeQueue::get_serial_commands() { // Process critical commands early if (command[0] == 'M') switch (command[3]) { case '8': if (command[2] == '0' && command[1] == '1') { wait_for_heatup = false; TERN_(HAS_LCD_MENU, wait_for_user = false); } break; - case '2': if (command[2] == '1' && command[1] == '1') kill(M112_KILL_STR, nullptr, true); break; + case '2': if (command[2] == '1' && command[1] == '1') kill(FPSTR(M112_KILL_STR), nullptr, true); break; case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; } #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 85d4400150..4035a78c93 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -1850,7 +1850,7 @@ void DWIN_LoadSettings(const char *buff) { feedrate_percentage = 100; } -void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { +void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { DWIN_Draw_Popup(ICON_BLTouch, lcd_error, lcd_component); DWIN_UpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 8e4abbe4bc..9bb324b05e 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -949,7 +949,7 @@ void CrealityDWINClass::Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_ } } -void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { +void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { CrealityDWIN.Draw_Popup(F("Printer Kill Reason:"), error, F("Restart Required"), Wait, ICON_BLTouch); } diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 5cd0922800..7a58963c11 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -41,8 +41,8 @@ namespace ExtUI { void onIdle() { Chiron.IdleLoop(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { - Chiron.PrinterKilled(error,component); + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { + Chiron.PrinterKilled(error, component); } void onMediaInserted() { Chiron.MediaEvent(AC_media_inserted); } diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 483da200e8..c3fc6aa96e 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -126,7 +126,7 @@ void ChironTFT::IdleLoop() { CheckHeaters(); } -void ChironTFT::PrinterKilled(PGM_P error,PGM_P component) { +void ChironTFT::PrinterKilled(FSTR_P const error, FSTR_P const component) { SendtoTFTLN(AC_msg_kill_lcd); #if ACDEBUG(AC_MARLIN) SERIAL_ECHOLNPGM("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h index a80763e372..44ba02dc5d 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h @@ -59,7 +59,7 @@ class ChironTFT { public: static void Startup(); static void IdleLoop(); - static void PrinterKilled(PGM_P, PGM_P); + static void PrinterKilled(FSTR_P, FSTR_P); static void MediaEvent(media_event_t); static void TimerEvent(timer_event_t); static void FilamentRunout(); diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index 33e7e84a81..c0e1b44578 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -37,7 +37,7 @@ namespace ExtUI { void onStartup() { AnycubicTFT.OnSetup(); } void onIdle() { AnycubicTFT.OnCommandScan(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { AnycubicTFT.OnKillTFT(); } + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { AnycubicTFT.OnKillTFT(); } void onMediaInserted() { AnycubicTFT.OnSDCardStateChange(true); } void onMediaError() { AnycubicTFT.OnSDCardError(); } void onMediaRemoved() { AnycubicTFT.OnSDCardStateChange(false); } diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 5bbcfd0b5e..98534ba65f 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -654,7 +654,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { break; case 12: // A12 kill - kill(PSTR(STR_ERR_KILLED)); + kill(F(STR_ERR_KILLED)); break; case 13: // A13 SELECTION FILE diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 06b350ff77..c9e7268f04 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -340,7 +340,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) void DGUSScreenHandler::SDCardError() { DGUSScreenHandler::SDCardRemoved(); - sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("SD card error"), nullptr, true, true, true, true); + sendinfoscreen(F("NOTICE"), nullptr, F("SD card error"), nullptr, true, true, true, true); SetupConfirmAction(nullptr); GotoScreen(DGUSLCD_SCREEN_POPUP); } @@ -567,7 +567,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo if (buf[0]) queue.enqueue_one_now(buf); #if ENABLED(DGUS_UI_WAITING) - sendinfoscreen(PSTR("PID is autotuning"), PSTR("please wait"), NUL_STR, NUL_STR, true, true, true, true); + sendinfoscreen(F("PID is autotuning"), F("please wait"), NUL_STR, NUL_STR, true, true, true, true); GotoScreen(DGUSLCD_SCREEN_WAITING); #endif } diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 4f15827a49..04ba6b95c2 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -42,8 +42,8 @@ namespace ExtUI { void onIdle() { ScreenHandler.loop(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { - ScreenHandler.sendinfoscreen(GET_TEXT(MSG_HALTED), error, NUL_STR, GET_TEXT(MSG_PLEASE_RESET), true, true, true, true); + void onPrinterKilled(FSTR_P const error, FSTR_P const) { + ScreenHandler.sendinfoscreen(GET_TEXT_F(MSG_HALTED), error, FPSTR(NUL_STR), GET_TEXT_F(MSG_PLEASE_RESET), true, true, true, true); ScreenHandler.GotoScreen(DGUSLCD_SCREEN_KILL); while (!ScreenHandler.loop()); // Wait while anything is left to be sent } @@ -60,7 +60,7 @@ namespace ExtUI { void onUserConfirmRequired(const char * const msg) { if (msg) { - ScreenHandler.sendinfoscreen(PSTR("Please confirm."), nullptr, msg, nullptr, true, true, false, true); + ScreenHandler.sendinfoscreen(F("Please confirm."), nullptr, msg, nullptr, true, true, false, true); ScreenHandler.SetupConfirmAction(setUserConfirmed); ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index ee0af013a8..bb0bd2bd3b 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -38,6 +38,12 @@ public: // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); + } + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); + } static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index ee0af013a8..bb0bd2bd3b 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -38,6 +38,12 @@ public: // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); + } + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); + } static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 0dc1e2245e..0e2a971fd1 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -1233,7 +1233,7 @@ void DGUSScreenHandler::MKS_FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ #if BOTH(HAS_HOTEND, PREVENT_COLD_EXTRUSION) if (hotend_too_cold) { if (thermalManager.targetTooColdToExtrude(hotend_too_cold - 1)) thermalManager.setTargetHotend(thermalManager.extrude_min_temp, hotend_too_cold - 1); - sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please wait."), PSTR("Nozzle heating!"), true, true, true, true); + sendinfoscreen(F("NOTICE"), nullptr, F("Please wait."), F("Nozzle heating!"), true, true, true, true); SetupConfirmAction(nullptr); GotoScreen(DGUSLCD_SCREEN_POPUP); } @@ -1489,7 +1489,7 @@ void DGUSScreenHandler::DGUS_Runout_Idle(void) { queue.inject(F("M25")); GotoScreen(MKSLCD_SCREEN_PAUSE); - sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please change filament!"), nullptr, true, true, true, true); + sendinfoscreen(F("NOTICE"), nullptr, F("Please change filament!"), nullptr, true, true, true, true); //SetupConfirmAction(nullptr); GotoScreen(DGUSLCD_SCREEN_POPUP); break; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 8d5d9066f4..0c80cd260e 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -38,6 +38,12 @@ public: // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); + } + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); + } static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index ee0af013a8..bb0bd2bd3b 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -38,6 +38,12 @@ public: // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); + } + static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); + } static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index b2189f1c82..e81eab8e73 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -159,9 +159,9 @@ void DGUSScreenHandler::Loop() { dgus_display.Loop(); } -void DGUSScreenHandler::PrinterKilled(PGM_P error, PGM_P component) { - SetMessageLinePGM(error, 1); - SetMessageLinePGM(component, 2); +void DGUSScreenHandler::PrinterKilled(FSTR_P const error, FSTR_P const component) { + SetMessageLinePGM(FTOP(error), 1); + SetMessageLinePGM(FTOP(component), 2); SetMessageLinePGM(NUL_STR, 3); SetMessageLinePGM(GET_TEXT(MSG_PLEASE_RESET), 4); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index ea1289dd67..4a5fbd141a 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -37,7 +37,7 @@ public: static void Ready(); static void Loop(); - static void PrinterKilled(PGM_P error, PGM_P component); + static void PrinterKilled(FSTR_P const error, FSTR_P const component); static void UserConfirmRequired(const char * const msg); static void SettingsReset(); static void StoreSettings(char *buff); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp index 4d57fbd7e2..bf79661b42 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -46,7 +46,7 @@ namespace ExtUI { } } - void onPrinterKilled(PGM_P error, PGM_P component) { + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { dgus_screen_handler.PrinterKilled(error, component); } diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index f74cbee91c..8f38d2aba6 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -46,7 +46,7 @@ namespace ExtUI { */ } void onIdle() {} - void onPrinterKilled(PGM_P const error, PGM_P const component) {} + void onPrinterKilled(FSTR_P const error, FSTR_P const component) {} void onMediaInserted() {} void onMediaError() {} void onMediaRemoved() {} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index 59833b06a0..109814abf2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -38,9 +38,9 @@ namespace ExtUI { void onIdle() { EventLoop::loop(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { - char str[strlen_P(error) + strlen_P(component) + 3]; - sprintf_P(str, PSTR(S_FMT ": " S_FMT), error, component); + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { + char str[strlen_P(FTOP(error)) + strlen_P(FTOP(component)) + 3]; + sprintf_P(str, PSTR(S_FMT ": " S_FMT), FTOP(error), FTOP(component)); KillScreen::show(str); } diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index 8c9bfc32e5..df7f305df2 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -74,35 +74,36 @@ uint16_t inbound_count; bool last_printing_status = false; // Everything written needs the high bit set. -void write_to_lcd_P(PGM_P const message) { +void write_to_lcd(FSTR_P const fmsg) { + PGM_P pmsg = FTOP(fmsg); char encoded_message[MAX_CURLY_COMMAND]; - uint8_t message_length = _MIN(strlen_P(message), sizeof(encoded_message)); + uint8_t message_length = _MIN(strlen_P(pmsg), sizeof(encoded_message)); LOOP_L_N(i, message_length) - encoded_message[i] = pgm_read_byte(&message[i]) | 0x80; + encoded_message[i] = pgm_read_byte(&pmsg[i]) | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); } -void write_to_lcd(const char * const message) { +void write_to_lcd(const char * const cmsg) { char encoded_message[MAX_CURLY_COMMAND]; - const uint8_t message_length = _MIN(strlen(message), sizeof(encoded_message)); + const uint8_t message_length = _MIN(strlen(cmsg), sizeof(encoded_message)); LOOP_L_N(i, message_length) - encoded_message[i] = message[i] | 0x80; + encoded_message[i] = cmsg[i] | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); } // {E:} is for error states. -void set_lcd_error_P(PGM_P const error, PGM_P const component/*=nullptr*/) { - write_to_lcd_P(PSTR("{E:")); - write_to_lcd_P(error); +void set_lcd_error(FSTR_P const error, FSTR_P const component/*=nullptr*/) { + write_to_lcd(F("{E:")); + write_to_lcd(error); if (component) { - write_to_lcd_P(PSTR(" ")); - write_to_lcd_P(component); + write_to_lcd(F(" ")); + write_to_lcd(component); } - write_to_lcd_P(PSTR("}")); + write_to_lcd(F("}")); } @@ -243,16 +244,16 @@ void process_lcd_p_command(const char *command) { switch (command[0]) { case 'P': ExtUI::pausePrint(); - write_to_lcd_P(PSTR("{SYS:PAUSED}")); + write_to_lcd(F("{SYS:PAUSED}")); break; case 'R': ExtUI::resumePrint(); - write_to_lcd_P(PSTR("{SYS:RESUMED}")); + write_to_lcd(F("{SYS:RESUMED}")); break; case 'X': - write_to_lcd_P(PSTR("{SYS:CANCELING}")); + write_to_lcd(F("{SYS:CANCELING}")); ExtUI::stopPrint(); - write_to_lcd_P(PSTR("{SYS:STARTED}")); + write_to_lcd(F("{SYS:STARTED}")); break; case 'H': queue.enqueue_now_P(G28_STR); break; // Home all axes default: { @@ -271,13 +272,13 @@ void process_lcd_p_command(const char *command) { // but the V2 LCD switches to "print" mode on {SYS:DIR} response. if (card.flag.filenameIsDir) { card.cd(card.filename); - write_to_lcd_P(PSTR("{SYS:DIR}")); + write_to_lcd(F("{SYS:DIR}")); } else { char message_buffer[MAX_CURLY_COMMAND]; sprintf_P(message_buffer, PSTR("{PRINTFILE:%s}"), card.longest_filename()); write_to_lcd(message_buffer); - write_to_lcd_P(PSTR("{SYS:BUILD}")); + write_to_lcd(F("{SYS:BUILD}")); card.openAndPrintFile(card.filename); } #endif @@ -332,7 +333,7 @@ void process_lcd_s_command(const char *command) { write_to_lcd(message_buffer); } - write_to_lcd_P(PSTR("{SYS:OK}")); + write_to_lcd(F("{SYS:OK}")); #endif } break; @@ -413,7 +414,7 @@ void update_usb_status(const bool forceUpdate) { // This is more logical. if (last_usb_connected_status != MYSERIAL1.connected() || forceUpdate) { last_usb_connected_status = MYSERIAL1.connected(); - write_to_lcd_P(last_usb_connected_status ? PSTR("{R:UC}\r\n") : PSTR("{R:UD}\r\n")); + write_to_lcd(last_usb_connected_status ? F("{R:UC}\r\n") : F("{R:UD}\r\n")); } } diff --git a/Marlin/src/lcd/extui/malyan/malyan.h b/Marlin/src/lcd/extui/malyan/malyan.h index e8afbd4a59..1d0e911ccd 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.h +++ b/Marlin/src/lcd/extui/malyan/malyan.h @@ -33,10 +33,10 @@ extern uint16_t inbound_count; // For sending print completion messages extern bool last_printing_status; -void write_to_lcd_P(PGM_P const message); -void write_to_lcd(const char * const message); +void write_to_lcd(FSTR_P const fmsg); +void write_to_lcd(const char * const cmsg); -void set_lcd_error_P(PGM_P const error, PGM_P const component=nullptr); +void set_lcd_error(FSTR_P const error, FSTR_P const component=nullptr); void process_lcd_c_command(const char *command); void process_lcd_eb_command(const char *command); diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index cae534de3b..f323728e27 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -55,13 +55,13 @@ namespace ExtUI { LCD_SERIAL.begin(LCD_BAUDRATE); // Signal init - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + write_to_lcd(F("{SYS:STARTED}\r\n")); // send a version that says "unsupported" - write_to_lcd_P(PSTR("{VER:99}\r\n")); + write_to_lcd(F("{VER:99}\r\n")); // No idea why it does this twice. - write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); + write_to_lcd(F("{SYS:STARTED}\r\n")); update_usb_status(true); } @@ -98,8 +98,8 @@ namespace ExtUI { #endif } - void onPrinterKilled(PGM_P const error, PGM_P const component) { - set_lcd_error_P(error, component); + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { + set_lcd_error(error, component); } #if HAS_PID_HEATING @@ -109,28 +109,28 @@ namespace ExtUI { //SERIAL_ECHOLNPGM("OnPidTuning:", rst); switch (rst) { case PID_STARTED: - set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE)); + set_lcd_error(GET_TEXT_F(MSG_PID_AUTOTUNE)); break; case PID_BAD_EXTRUDER_NUM: - set_lcd_error_P(GET_TEXT(MSG_PID_BAD_EXTRUDER_NUM)); + set_lcd_error(GET_TEXT_F(MSG_PID_BAD_EXTRUDER_NUM)); break; case PID_TEMP_TOO_HIGH: - set_lcd_error_P(GET_TEXT(MSG_PID_TEMP_TOO_HIGH)); + set_lcd_error(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); break; case PID_TUNING_TIMEOUT: - set_lcd_error_P(GET_TEXT(MSG_PID_TIMEOUT)); + set_lcd_error(GET_TEXT_F(MSG_PID_TIMEOUT)); break; case PID_DONE: - set_lcd_error_P(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); + set_lcd_error(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); break; } } #endif - void onPrintTimerStarted() { write_to_lcd_P(PSTR("{SYS:BUILD}")); } + void onPrintTimerStarted() { write_to_lcd(F("{SYS:BUILD}")); } void onPrintTimerPaused() {} - void onPrintTimerStopped() { write_to_lcd_P(PSTR("{TQ:100}")); } + void onPrintTimerStopped() { write_to_lcd(F("{TQ:100}")); } // Not needed for Malyan LCD void onStatusChanged(const char * const) {} diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 96b0f2a086..20d4720d00 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -2030,7 +2030,7 @@ void get_wifi_commands() { wait_for_heatup = false; TERN_(HAS_LCD_MENU, wait_for_user = false); } - if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); + if (strcmp(command, "M112") == 0) kill(FPSTR(M112_KILL_STR), nullptr, true); if (strcmp(command, "M410") == 0) quickstop_stepper(); #endif diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index a825bd502f..c19d3aee46 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -37,7 +37,7 @@ namespace ExtUI { void onStartup() { nextion.Startup(); } void onIdle() { nextion.IdleLoop(); } - void onPrinterKilled(PGM_P const error, PGM_P const component) { nextion.PrinterKilled(error,component); } + void onPrinterKilled(FSTR_P const error, FSTR_P const component) { nextion.PrinterKilled(error, component); } void onMediaInserted() {} void onMediaError() {} void onMediaRemoved() {} diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 64e909779d..810848469c 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -84,12 +84,12 @@ void NextionTFT::IdleLoop() { UpdateOnChange(); } -void NextionTFT::PrinterKilled(PGM_P error, PGM_P component) { +void NextionTFT::PrinterKilled(FSTR_P const error, FSTR_P const component) { SEND_TXT_END("page error"); - SEND_TXT("t3", "Error"); - SEND_TXT_P("t4", component); - SEND_TXT_P("t5", error); - SEND_TXT("t6", "Need reset"); + SEND_TXT_F("t3", F("Error")); + SEND_TXT_F("t4", component); + SEND_TXT_F("t5", error); + SEND_TXT_F("t6", F("Need reset")); } void NextionTFT::PrintFinished() { diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h index 4570e9bba4..cdd91bf2a3 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft_defs.h @@ -56,8 +56,8 @@ #define SEND_TEMP(x,y,t,z) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(F(t)), LCD_SERIAL.print(z), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) #define SEND_VAL(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".val=")), LCD_SERIAL.print(y), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) -#define SEND_TXT(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(F(y)), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) -#define SEND_TXT_P(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(y), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_TXT(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(F(y)), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) +#define SEND_TXT_F(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), nextion.SendtoTFT(y), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) #define SEND_VALasTXT(x,y) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F(".txt=\"")), LCD_SERIAL.print(y), nextion.SendtoTFT(F("\"\xFF\xFF\xFF"))) #define SEND_TXT_END(x) (nextion.SendtoTFT(F(x)), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) #define SEND_PCO2(x,y,z) (nextion.SendtoTFT(F(x)), LCD_SERIAL.print(y), nextion.SendtoTFT(F(".pco=")), nextion.SendtoTFT(F(z)), nextion.SendtoTFT(F("\xFF\xFF\xFF"))) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index afd762a470..8e588ef8c2 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1077,6 +1077,7 @@ namespace ExtUI { void resumePrint() { ui.resume_print(); } void stopPrint() { ui.abort_print(); } + // Simplest approach is to make an SRAM copy void onUserConfirmRequired(FSTR_P const fstr) { char msg[strlen_P(FTOP(fstr)) + 1]; strcpy_P(msg, FTOP(fstr)); @@ -1153,7 +1154,7 @@ void MarlinUI::init() { ExtUI::onStartup(); } void MarlinUI::update() { ExtUI::onIdle(); } -void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { +void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const component) { using namespace ExtUI; if (!flags.printer_killed) { flags.printer_killed = true; diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 4866c5b9d7..7e899221ad 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -394,7 +394,7 @@ namespace ExtUI { void onMediaError(); void onMediaRemoved(); void onPlayTone(const uint16_t frequency, const uint16_t duration); - void onPrinterKilled(PGM_P const error, PGM_P const component); + void onPrinterKilled(FSTR_P const error, FSTR_P const component); void onPrintTimerStarted(); void onPrintTimerPaused(); void onPrintTimerStopped(); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1fec14228b..fd805d2df1 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -663,9 +663,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; draw_status_screen(); } - void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { + void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { init(); - status_printf(1, F(S_FMT ": " S_FMT), lcd_error, lcd_component); + status_printf(1, F(S_FMT ": " S_FMT), FTOP(lcd_error), FTOP(lcd_component)); TERN_(HAS_LCD_MENU, return_to_status()); // RED ALERT. RED ALERT. diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index bc8442c576..883850d6e0 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -356,9 +356,9 @@ public: static void status_printf(const uint8_t level, FSTR_P const fmt, ...); #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) - static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); + static void kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component); #else - static inline void kill_screen(PGM_P const, PGM_P const) {} + static inline void kill_screen(FSTR_P const, FSTR_P const) {} #endif #if HAS_DISPLAY diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 80e20a0778..da5a0073cf 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -384,7 +384,7 @@ void Endstops::not_homing() { // If the last move failed to trigger an endstop, call kill void Endstops::validate_homing_move() { if (trigger_state()) hit_on_purpose(); - else kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); + else kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); } #endif diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index a56831c214..1f13bd22ee 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1829,7 +1829,7 @@ void prepare_line_to_destination() { } if (TEST(endstops.state(), es)) { SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); - kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); + kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); } #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c6edfb835e..e62a9ab5ee 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3036,7 +3036,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons void Planner::buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps) { if (!last_page_step_rate) { - kill(GET_TEXT(MSG_BAD_PAGE_SPEED)); + kill(GET_TEXT_F(MSG_BAD_PAGE_SPEED)); return; } diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index f37d2aa03f..4078effe76 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -297,7 +297,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, F("Stow Probe"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Stow Probe"))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, PSTR("Stow Probe"), CONTINUE_STR)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, F("Stow Probe"), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e0a35787c6..3130914451 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -187,8 +187,8 @@ Temperature thermalManager; -const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, - str_t_heating_failed[] PROGMEM = STR_T_HEATING_FAILED; +PGMSTR(str_t_thermal_runaway, STR_T_THERMAL_RUNAWAY); +PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); /** * Macros to include the heater id in temp errors. The compiler's dead-code @@ -196,22 +196,22 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, */ #if HAS_HEATED_BED - #define _BED_PSTR(h) (h) == H_BED ? GET_TEXT(MSG_BED) : + #define _BED_FSTR(h) (h) == H_BED ? GET_TEXT_F(MSG_BED) : #else - #define _BED_PSTR(h) + #define _BED_FSTR(h) #endif #if HAS_HEATED_CHAMBER - #define _CHAMBER_PSTR(h) (h) == H_CHAMBER ? GET_TEXT(MSG_CHAMBER) : + #define _CHAMBER_FSTR(h) (h) == H_CHAMBER ? GET_TEXT_F(MSG_CHAMBER) : #else - #define _CHAMBER_PSTR(h) + #define _CHAMBER_FSTR(h) #endif #if HAS_COOLER - #define _COOLER_PSTR(h) (h) == H_COOLER ? GET_TEXT(MSG_COOLER) : + #define _COOLER_FSTR(h) (h) == H_COOLER ? GET_TEXT_F(MSG_COOLER) : #else - #define _COOLER_PSTR(h) + #define _COOLER_FSTR(h) #endif -#define _E_PSTR(h,N) ((HOTENDS) > N && (h) == N) ? PSTR(LCD_STR_E##N) : -#define HEATER_PSTR(h) _BED_PSTR(h) _CHAMBER_PSTR(h) _COOLER_PSTR(h) _E_PSTR(h,1) _E_PSTR(h,2) _E_PSTR(h,3) _E_PSTR(h,4) _E_PSTR(h,5) PSTR(LCD_STR_E0) +#define _E_FSTR(h,N) ((HOTENDS) > N && (h) == N) ? F(LCD_STR_E##N) : +#define HEATER_FSTR(h) _BED_FSTR(h) _CHAMBER_FSTR(h) _COOLER_FSTR(h) _E_FSTR(h,1) _E_FSTR(h,2) _E_FSTR(h,3) _E_FSTR(h,4) _E_FSTR(h,5) F(LCD_STR_E0) // // Initialize MAX TC objects/SPI @@ -731,10 +731,10 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired - _temp_error(heater_id, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error(heater_id, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); } else if (current_temp < target - (MAX_OVERSHOOT_PID_AUTOTUNE)) // Heated, then temperature fell too far? - _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); } #endif } // every 2 seconds @@ -951,7 +951,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { // Temperature Error Handlers // -inline void loud_kill(PGM_P const lcd_msg, const heater_id_t heater_id) { +inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; #if USE_BEEPER thermalManager.disable_all_heaters(); @@ -967,16 +967,16 @@ inline void loud_kill(PGM_P const lcd_msg, const heater_id_t heater_id) { } WRITE(BEEPER_PIN, HIGH); #endif - kill(lcd_msg, HEATER_PSTR(heater_id)); + kill(lcd_msg, HEATER_FSTR(heater_id)); } -void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_msg, PGM_P const lcd_msg) { +void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_msg, FSTR_P const lcd_msg) { static uint8_t killed = 0; if (IsRunning() && TERN1(BOGUS_TEMPERATURE_GRACE_PERIOD, killed == 2)) { SERIAL_ERROR_START(); - SERIAL_ECHOPGM_P(serial_msg); + SERIAL_ECHOF(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); heater_id_t real_heater_id = heater_id; @@ -1031,14 +1031,14 @@ void Temperature::max_temp_error(const heater_id_t heater_id) { #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(1); #endif - _temp_error(heater_id, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); + _temp_error(heater_id, F(STR_T_MAXTEMP), GET_TEXT_F(MSG_ERR_MAXTEMP)); } void Temperature::min_temp_error(const heater_id_t heater_id) { #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(0); #endif - _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); + _temp_error(heater_id, F(STR_T_MINTEMP), GET_TEXT_F(MSG_ERR_MINTEMP)); } #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) @@ -1294,7 +1294,7 @@ void Temperature::manage_heater() { REMEMBER(mh, no_reentry, true); #if ENABLED(EMERGENCY_PARSER) - if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); + if (emergency_parser.killed_by_M112) kill(FPSTR(M112_KILL_STR), nullptr, true); if (emergency_parser.quickstop_by_M410) { emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! @@ -1344,7 +1344,7 @@ void Temperature::manage_heater() { start_watching_hotend(e); // If temp reached, turn off elapsed check else { TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error((heater_id_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error((heater_id_t)e, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); } } #endif @@ -1356,7 +1356,7 @@ void Temperature::manage_heater() { #if HAS_TEMP_REDUNDANT // Make sure measured temperatures are close together if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) - _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); + _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP)); #endif #if HAS_AUTO_FAN @@ -1387,7 +1387,7 @@ void Temperature::manage_heater() { start_watching_bed(); // If temp reached, turn off elapsed check else { TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error(H_BED, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error(H_BED, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); } } #endif // WATCH_BED @@ -1467,7 +1467,7 @@ void Temperature::manage_heater() { if (watch_chamber.check(degChamber())) // Increased enough? Error below. start_watching_chamber(); // If temp reached, turn off elapsed check. else - _temp_error(H_CHAMBER, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error(H_CHAMBER, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); } #endif @@ -1589,7 +1589,7 @@ void Temperature::manage_heater() { // Make sure temperature is decreasing if (watch_cooler.elapsed(ms)) { // Time to check the cooler? if (degCooler() > watch_cooler.target) // Failed to decrease enough? - _temp_error(H_COOLER, GET_TEXT(MSG_COOLING_FAILED), GET_TEXT(MSG_COOLING_FAILED)); + _temp_error(H_COOLER, GET_TEXT_F(MSG_COOLING_FAILED), GET_TEXT_F(MSG_COOLING_FAILED)); else start_watching_cooler(); // Start again if the target is still far off } @@ -2597,7 +2597,7 @@ void Temperature::init() { case TRRunaway: TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); } } @@ -3896,7 +3896,7 @@ void Temperature::isr() { const bool wants_to_cool = isProbeAboveTemp(target_temp), will_wait = !(wants_to_cool && no_wait_for_cooling); if (will_wait) - SERIAL_ECHOLNPGM("Waiting for probe to ", (wants_to_cool ? PSTR("cool down") : PSTR("heat up")), " to ", target_temp, " degrees."); + SERIAL_ECHOLNPGM("Waiting for probe to ", wants_to_cool ? F("cool down") : F("heat up"), " to ", target_temp, " degrees."); #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) KEEPALIVE_STATE(NOT_BUSY); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 1675507f86..5579f71172 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -961,7 +961,7 @@ class Temperature { static float get_pid_output_chamber(); #endif - static void _temp_error(const heater_id_t e, PGM_P const serial_msg, PGM_P const lcd_msg); + static void _temp_error(const heater_id_t e, FSTR_P const serial_msg, FSTR_P const lcd_msg); static void min_temp_error(const heater_id_t e); static void max_temp_error(const heater_id_t e); diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 7ac13e55cf..b968537e71 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -432,7 +432,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } else if (kill_on_error && (!tool_sensor_disabled || disable)) { sensor_tries++; - if (sensor_tries > 10) kill(PSTR("Tool Sensor error")); + if (sensor_tries > 10) kill(F("Tool Sensor error")); safe_delay(5); } else { diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 6b8d2338c1..1ab6dcc7c6 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -646,7 +646,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ // Too deep? The firmware has to bail. if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:", SD_PROCEDURE_DEPTH); - kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW)); + kill(GET_TEXT_F(MSG_KILL_SUBCALL_OVERFLOW)); return; } From 2d08afe456255d47e6cd244c49c7cd243f74c53a Mon Sep 17 00:00:00 2001 From: Sebastien Andrivet Date: Mon, 4 Oct 2021 08:06:49 +0200 Subject: [PATCH 0764/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20ExtUI=20Pause=20?= =?UTF-8?q?messages=20(#22874)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 23 ++++++++++++----------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index fd805d2df1..83be7fd1a8 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1741,19 +1741,20 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; pause_mode = mode; ExtUI::pauseModeStatus = message; switch (message) { - case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); - case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); - case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); - case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING)); - case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); - case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); + case PAUSE_MESSAGE_PARKING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); break; + case PAUSE_MESSAGE_CHANGING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); break; + case PAUSE_MESSAGE_UNLOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); break; + case PAUSE_MESSAGE_WAITING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING)); break; + case PAUSE_MESSAGE_INSERT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); break; + case PAUSE_MESSAGE_LOAD: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); break; case PAUSE_MESSAGE_PURGE: ExtUI::onUserConfirmRequired(GET_TEXT_F(TERN(ADVANCED_PAUSE_CONTINUOUS_PURGE, MSG_FILAMENT_CHANGE_CONT_PURGE, MSG_FILAMENT_CHANGE_PURGE))); - case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); - case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT)); - case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEATING)); - case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_OPTION_HEADER)); - case PAUSE_MESSAGE_STATUS: + break; + case PAUSE_MESSAGE_RESUME: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); break; + case PAUSE_MESSAGE_HEAT: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT)); break; + case PAUSE_MESSAGE_HEATING: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEATING)); break; + case PAUSE_MESSAGE_OPTION: ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_OPTION_HEADER)); break; + case PAUSE_MESSAGE_STATUS: break; default: break; } } From b919bdbf0b4f78578964999373c8918cc523d736 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 4 Oct 2021 19:12:19 +1300 Subject: [PATCH 0765/2168] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20EXTRUDER=200=20c?= =?UTF-8?q?ompile=20warning=20(#22868)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 0bfb418d40..f170dd4104 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -609,7 +609,7 @@ class Stepper { static void disable_e_steppers(); #else static inline void enable_extruder() {} - static inline bool disable_extruder() {} + static inline bool disable_extruder() { return true; } static inline void enable_e_steppers() {} static inline void disable_e_steppers() {} #endif From f5b085157aaa2c3c7b360750c745588104e155f7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 Oct 2021 18:58:20 -0500 Subject: [PATCH 0766/2168] =?UTF-8?q?=F0=9F=94=A8=20Add=20'opt=5Ffind'=20t?= =?UTF-8?q?o=20find=20matching=20options?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/opt_find | 33 +++++++++++++++++++++++++++++++++ 1 file changed, 33 insertions(+) create mode 100755 buildroot/bin/opt_find diff --git a/buildroot/bin/opt_find b/buildroot/bin/opt_find new file mode 100755 index 0000000000..a7c8fd9d71 --- /dev/null +++ b/buildroot/bin/opt_find @@ -0,0 +1,33 @@ +#!/usr/bin/env bash +# +# opt_find +# Find one or more Marlin options - Configuration lines starting with #define +# + +MYNAME=$(basename $0) + +[[ $# == 0 ]] && ONE="-h" || ONE=$1 + +COMM="(//\\s*)?" ; TYPE="" +case "$ONE" in + -d|--disabled ) + shift ; COMM="(//\\s*)" ; TYPE="disabled " ;; + -e|--enabled ) + shift ; COMM="" ; TYPE="enabled " ;; + -h|--help ) + echo "$MYNAME [-d|--disabled|-e|--enabled] STRING ... Find matching Marlin configuration options." + echo ; shift ;; + -* ) + echo "Unknown option $ONE" ; shift ;; +esac + +while [[ $# > 0 ]]; do + DID=0 + for FN in Configuration Configuration_adv; do + FOUND=$( grep -HEn "^\s*${COMM}#define\s+[A-Z0-9_]*${1}" "Marlin/$FN.h" 2>/dev/null ) + [[ -n "$FOUND" ]] && { echo "$FOUND" ; DID=1 ; } + done + ((DID)) || { echo "ERROR: ${MYNAME} - No ${TYPE}match for ${1}" ; exit 9; } + shift + echo +done From d5cb30524e0ca0607ed49587f49e231c37fff4ef Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 5 Oct 2021 01:01:31 +0000 Subject: [PATCH 0767/2168] [cron] Bump distribution date (2021-10-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 727e86205d..ed42761bd0 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-04" +//#define STRING_DISTRIBUTION_DATE "2021-10-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 762854f779..b35ed5b65a 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 "2021-10-04" + #define STRING_DISTRIBUTION_DATE "2021-10-05" #endif /** From e8459ae63c8290123827b4e45bbe051c95060783 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 Oct 2021 19:50:14 -0500 Subject: [PATCH 0768/2168] =?UTF-8?q?=F0=9F=90=9B=20ExtUI=20F()=20followup?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to 12b5d997a2 --- Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp | 4 ++-- Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h | 4 ++-- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 2 +- Marlin/src/lcd/extui/nextion/nextion_tft.h | 5 +++-- 4 files changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index c3fc6aa96e..9f558e3a98 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -315,7 +315,7 @@ void ChironTFT::PrintComplete() { setSoftEndstopState(true); // enable endstops } -void ChironTFT::SendtoTFT(FSTR_P const fstr) { // A helper to print PROGMEM string to the panel +void ChironTFT::SendtoTFT(FSTR_P const fstr/*=nullptr*/) { // A helper to print PROGMEM string to the panel #if ACDEBUG(AC_SOME) SERIAL_ECHOF(fstr); #endif @@ -323,7 +323,7 @@ void ChironTFT::SendtoTFT(FSTR_P const fstr) { // A helper to print PROGMEM str while (const char c = pgm_read_byte(str++)) TFTSer.write(c); } -void ChironTFT::SendtoTFTLN(FSTR_P const fstr) { +void ChironTFT::SendtoTFTLN(FSTR_P const fstr/*=nullptr*/) { if (fstr) { #if ACDEBUG(AC_SOME) SERIAL_ECHOPGM("> "); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h index 44ba02dc5d..c9a32e584d 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.h @@ -67,8 +67,8 @@ class ChironTFT { static void StatusChange(const char * const); static void PowerLossRecovery(); static void PrintComplete(); - static void SendtoTFT(FSTR_P const); - static void SendtoTFTLN(FSTR_P const); + static void SendtoTFT(FSTR_P const=nullptr); + static void SendtoTFTLN(FSTR_P const=nullptr); private: static void DetectPanelType(); static bool ReadTFTCommand(); diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 810848469c..99211a220c 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -110,7 +110,7 @@ void NextionTFT::StatusChange(const char * const msg) { SEND_VALasTXT("tmppage.M117", msg); } -void NextionTFT::SendtoTFT(FSTR_P fstr) { // A helper to print PROGMEM string to the panel +void NextionTFT::SendtoTFT(FSTR_P const fstr/*=nullptr*/) { // A helper to print PROGMEM string to the panel #if NEXDEBUG(N_SOME) DEBUG_ECHOF(fstr); #endif diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.h b/Marlin/src/lcd/extui/nextion/nextion_tft.h index f32e5d4ef1..806630485c 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.h +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.h @@ -42,10 +42,11 @@ class NextionTFT { NextionTFT(); static void Startup(); static void IdleLoop(); - static void PrinterKilled(PGM_P, PGM_P); + static void PrinterKilled(FSTR_P const, FSTR_P const); static void ConfirmationRequest(const char * const); static void StatusChange(const char * const); - static void SendtoTFT(FSTR_P const); + static void SendtoTFT(FSTR_P const=nullptr); + //static void SendtoTFTLN(FSTR_P const=nullptr); static void UpdateOnChange(); static void PrintFinished(); static void PanelInfo(uint8_t); From f395198e14a1cbc0604611b3ca1fb6261d4871fa Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 Oct 2021 22:16:15 -0500 Subject: [PATCH 0769/2168] =?UTF-8?q?=F0=9F=94=A8=20Move=20Creality=204.2.?= =?UTF-8?q?2=20warning?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Warnings.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index aba3d94366..fbec990fa7 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -455,3 +455,8 @@ #warning "Auto-assigned K_DIAG_PIN to E7_DIAG_PIN." #endif #endif + +// Ender 3 Pro (but, apparently all Creality 4.2.2 boards) +#if ENABLED(EMIT_CREALITY_422_WARNING) || MB(CREALITY_V4) + #warning "Creality 4.2.2 boards may have A4988 or TMC2208_STANDALONE drivers. Check your board and make sure to select the correct DRIVER_TYPE!" +#endif From 4e9ae9449fbdc9ad3cd9267d8e620b5ec5eddb3e Mon Sep 17 00:00:00 2001 From: Mark Date: Tue, 5 Oct 2021 12:23:02 +0800 Subject: [PATCH 0770/2168] =?UTF-8?q?=E2=9C=A8=20ESP32=20Panda=5FZHU=20and?= =?UTF-8?q?=20Panda=5FM4=20(#22644)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 4 +- Marlin/src/HAL/ESP32/HAL.cpp | 28 ++++++- Marlin/src/HAL/ESP32/HAL.h | 4 + Marlin/src/HAL/ESP32/HAL_SPI.cpp | 6 +- Marlin/src/HAL/ESP32/esp32.csv | 6 ++ Marlin/src/HAL/ESP32/fastio.h | 18 +++-- Marlin/src/HAL/ESP32/i2s.cpp | 3 + Marlin/src/HAL/ESP32/watchdog.h | 2 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 4 +- Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 5 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 5 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 7 +- Marlin/src/core/boards.h | 2 + Marlin/src/gcode/sd/M1001.cpp | 1 + Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/pins/esp32/pins_PANDA_M4.h | 38 +++++++++ Marlin/src/pins/esp32/pins_PANDA_ZHU.h | 61 ++++++++++++++ Marlin/src/pins/esp32/pins_PANDA_common.h | 98 +++++++++++++++++++++++ Marlin/src/pins/pins.h | 4 + ini/esp32.ini | 10 +++ ini/stm32f1-maple.ini | 6 +- 21 files changed, 285 insertions(+), 31 deletions(-) create mode 100644 Marlin/src/HAL/ESP32/esp32.csv create mode 100644 Marlin/src/pins/esp32/pins_PANDA_M4.h create mode 100644 Marlin/src/pins/esp32/pins_PANDA_ZHU.h create mode 100644 Marlin/src/pins/esp32/pins_PANDA_common.h diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 319d64c8f6..8784bb07b3 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -34,7 +34,9 @@ #include "../../inc/MarlinConfig.h" void spiBegin() { - OUT_WRITE(SD_SS_PIN, HIGH); + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 7818dbdd87..6a66d519b3 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -28,6 +28,10 @@ #include #include +#if ENABLED(USE_ESP32_TASK_WDT) + #include +#endif + #if ENABLED(WIFISUPPORT) #include #include "wifi.h" @@ -90,8 +94,24 @@ volatile int numPWMUsed = 0, #endif -void HAL_init_board() { +#if ENABLED(USE_ESP32_EXIO) + HardwareSerial YSerial2(2); + void Write_EXIO(uint8_t IO, uint8_t v) { + if (ISRS_ENABLED()) { + DISABLE_ISRS(); + YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); + ENABLE_ISRS(); + } + else + YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); + } +#endif + +void HAL_init_board() { + #if ENABLED(USE_ESP32_TASK_WDT) + esp_task_wdt_init(10, true); + #endif #if ENABLED(ESP3D_WIFISUPPORT) esp3dlib.init(); #elif ENABLED(WIFISUPPORT) @@ -127,7 +147,11 @@ void HAL_init_board() { // Initialize the i2s peripheral only if the I2S stepper stream is enabled. // The following initialization is performed after Serial1 and Serial2 are defined as // their native pins might conflict with the i2s stream even when they are remapped. - TERN_(I2S_STEPPER_STREAM, i2s_init()); + #if ENABLED(USE_ESP32_EXIO) + YSerial2.begin(460800 * 3, SERIAL_8N1, 16, 17); + #elif ENABLED(I2S_STEPPER_STREAM) + i2s_init(); + #endif } void HAL_idletask() { diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 0f92052030..bc0ce4e037 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -142,6 +142,10 @@ void HAL_idletask(); inline void HAL_init() {} void HAL_init_board(); +#if ENABLED(USE_ESP32_EXIO) + void Write_EXIO(uint8_t IO, uint8_t v); +#endif + // // Delay in cycles (used by DELAY_NS / DELAY_US) // diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 8743ac5be2..868ab1b671 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -53,11 +53,9 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #if !PIN_EXISTS(SD_SS) - #error "SD_SS_PIN not defined!" + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif - - OUT_WRITE(SD_SS_PIN, HIGH); } void spiInit(uint8_t spiRate) { diff --git a/Marlin/src/HAL/ESP32/esp32.csv b/Marlin/src/HAL/ESP32/esp32.csv new file mode 100644 index 0000000000..8f6e101f02 --- /dev/null +++ b/Marlin/src/HAL/ESP32/esp32.csv @@ -0,0 +1,6 @@ +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x5000, +otadata, data, ota, 0xe000, 0x2000, +app0, app, ota_0, 0x10000, 0x180000, +app1, app, ota_1, 0x190000, 0x180000, +spiffs, data, spiffs, 0x310000, 0xF0000, diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index 8db89dca12..c8e3f7e343 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -40,13 +40,19 @@ // Set pin as input with pullup mode #define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT) -// Read a pin wrapper -#define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO)) +#if ENABLED(USE_ESP32_EXIO) + // Read a pin wrapper + #define READ(IO) digitalRead(IO) + // Write to a pin wrapper + #define WRITE(IO, v) (IO >= 100 ? Write_EXIO(IO, v) : digitalWrite(IO, v)) +#else + // Read a pin wrapper + #define READ(IO) (IS_I2S_EXPANDER_PIN(IO) ? i2s_state(I2S_EXPANDER_PIN_INDEX(IO)) : digitalRead(IO)) + // Write to a pin wrapper + #define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v)) +#endif -// Write to a pin wrapper -#define WRITE(IO, v) (IS_I2S_EXPANDER_PIN(IO) ? i2s_write(I2S_EXPANDER_PIN_INDEX(IO), v) : digitalWrite(IO, v)) - -// Set pin as input wrapper +// Set pin as input wrapper (0x80 | (v << 5) | (IO - 100)) #define SET_INPUT(IO) _SET_INPUT(IO) // Set pin as input with pullup wrapper diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index c28c008793..557ea319e6 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -23,6 +23,8 @@ #include "../../inc/MarlinConfigPre.h" +#if DISABLED(USE_ESP32_EXIO) + #include "i2s.h" #include "../shared/Marduino.h" @@ -340,4 +342,5 @@ void i2s_push_sample() { dma.current[dma.rw_pos++] = i2s_port_data; } +#endif // !USE_ESP32_EXIO #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/watchdog.h b/Marlin/src/HAL/ESP32/watchdog.h index b6c169e347..43db813076 100644 --- a/Marlin/src/HAL/ESP32/watchdog.h +++ b/Marlin/src/HAL/ESP32/watchdog.h @@ -25,7 +25,7 @@ extern "C" { #endif - esp_err_t esp_task_wdt_reset(); + esp_err_t esp_task_wdt_reset(); #ifdef __cplusplus } diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 85a5238b54..8ee4761647 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -47,7 +47,9 @@ static SPISettings spiConfig; #include "../shared/Delay.h" void spiBegin(void) { - OUT_WRITE(SD_SS_PIN, HIGH); + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif OUT_WRITE(SD_SCK_PIN, HIGH); SET_INPUT(SD_MISO_PIN); OUT_WRITE(SD_MOSI_PIN, HIGH); diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index ff84e91f79..415c692229 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -36,10 +36,9 @@ static SPISettings spiConfig; // Initialize SPI bus void spiBegin() { - #if !PIN_EXISTS(SD_SS) - #error "SD_SS_PIN not defined!" + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif - OUT_WRITE(SD_SS_PIN, HIGH); SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index e63ab1c0e3..d80f57b2c4 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -36,10 +36,9 @@ static SPISettings spiConfig; void spiBegin() { - #if !PIN_EXISTS(SD_SS) - #error "SD_SS_PIN not defined!" + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif - OUT_WRITE(SD_SS_PIN, HIGH); SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 610765ad49..9dcb812faf 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -51,12 +51,9 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #ifndef SD_SS_PIN - #error "SD_SS_PIN is not defined!" + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); #endif - - OUT_WRITE(SD_SS_PIN, HIGH); - //SET_OUTPUT(SD_SCK_PIN); //SET_INPUT(SD_MISO_PIN); //SET_OUTPUT(SD_MOSI_PIN); diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 46b2e5cf0c..bc29ab5dec 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -422,6 +422,8 @@ #define BOARD_MRR_ESPE 6002 // MRR ESPE based on ESP32 (with I2S stepper stream) #define BOARD_E4D_BOX 6003 // E4d@BOX #define BOARD_FYSETC_E4 6004 // FYSETC E4 +#define BOARD_PANDA_ZHU 6005 // Panda_ZHU +#define BOARD_PANDA_M4 6006 // Panda_M4 // // SAMD51 ARM Cortex M4 diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index bd1a18734d..374b100f59 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -27,6 +27,7 @@ #include "../gcode.h" #include "../../module/planner.h" #include "../../module/printcounter.h" +#include "../../module/temperature.h" #include "../../sd/cardreader.h" #ifdef SD_FINISHED_RELEASECOMMAND diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a4d7d37aac..7989dc8213 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -597,9 +597,9 @@ #error "SPINDLE_LASER_PWM (true) is now set with SPINDLE_LASER_USE_PWM (enabled)." #endif -#if MOTHERBOARD == BOARD_DUE3DOM_MINI && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) +#if MB(DUE3DOM_MINI) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) #warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." -#elif MOTHERBOARD == BOARD_BTT_SKR_E3_TURBO && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) +#elif MB(BTT_SKR_E3_TURBO) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) #warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." #endif diff --git a/Marlin/src/pins/esp32/pins_PANDA_M4.h b/Marlin/src/pins/esp32/pins_PANDA_M4.h new file mode 100644 index 0000000000..5e2e72af05 --- /dev/null +++ b/Marlin/src/pins/esp32/pins_PANDA_M4.h @@ -0,0 +1,38 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Panda M4 pin assignments + */ + +#define BOARD_INFO_NAME "Panda_M4" + +#include "pins_PANDA_common.h" + +// +// Steppers +// +#define X_ENABLE_PIN 115 +#define Y_ENABLE_PIN 114 +#define Z_ENABLE_PIN 113 +#define E0_ENABLE_PIN 112 diff --git a/Marlin/src/pins/esp32/pins_PANDA_ZHU.h b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h new file mode 100644 index 0000000000..4750057897 --- /dev/null +++ b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h @@ -0,0 +1,61 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Panda ZHU pin assignments + */ + +#define BOARD_INFO_NAME "Panda_ZHU" + +#include "pins_PANDA_common.h" + +// +// Steppers +// +#define X_ENABLE_PIN 128 // Shared with all steppers +#define Y_ENABLE_PIN X_ENABLE_PIN +#define Z_ENABLE_PIN X_ENABLE_PIN +#define E0_ENABLE_PIN X_ENABLE_PIN + +//#define X_CS_PIN 0 +//#define Y_CS_PIN 13 +//#define Z_CS_PIN 5 // SS_PIN +//#define E0_CS_PIN 21 + +#define E1_STEP_PIN 115 +#define E1_DIR_PIN 114 +#define E1_ENABLE_PIN X_ENABLE_PIN + +#define E2_STEP_PIN 112 +#define E2_DIR_PIN 113 +#define E2_ENABLE_PIN X_ENABLE_PIN + +#define E3_STEP_PIN 110 +#define E3_DIR_PIN 111 +#define E3_ENABLE_PIN X_ENABLE_PIN + +#define E4_STEP_PIN 121 +#define E4_DIR_PIN 122 +#define E4_ENABLE_PIN X_ENABLE_PIN + +#define HEATER_1_PIN 123 diff --git a/Marlin/src/pins/esp32/pins_PANDA_common.h b/Marlin/src/pins/esp32/pins_PANDA_common.h new file mode 100644 index 0000000000..81862fbd55 --- /dev/null +++ b/Marlin/src/pins/esp32/pins_PANDA_common.h @@ -0,0 +1,98 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Panda common pin assignments + */ + +#include "env_validate.h" + +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +// +// Servos +// +#define SERVO0_PIN 0 + +// +// Limit Switches +// +#define X_STOP_PIN 4 +#define Y_STOP_PIN 35 +#define Z_STOP_PIN 21 + +// +// Steppers +// +#define X_STEP_PIN 101 +#define X_DIR_PIN 100 + +#define Y_STEP_PIN 103 +#define Y_DIR_PIN 102 + +#define Z_STEP_PIN 105 +#define Z_DIR_PIN 104 + +#define E0_STEP_PIN 107 +#define E0_DIR_PIN 106 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 39 // Analog Input +#define TEMP_BED_PIN 36 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 108 +#define HEATER_BED_PIN 109 +#define FAN_PIN 118 // FAN0 +#define FAN1_PIN 119 // FAN1 + +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN 120 // FAN2 +#endif + +// +// SD card +// +#if ENABLED(SDSUPPORT) + #define SD_MOSI_PIN 23 + #define SD_MISO_PIN 19 + #define SD_SCK_PIN 18 + #define SDSS 5 + #define SD_DETECT_PIN 2 +#endif + +#if HAS_WIRED_LCD + #define BEEPER_PIN 129 + #define BTN_ENC 12 + + #define BTN_EN1 33 + #define BTN_EN2 32 + + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 26 + #define LCD_PINS_D4 14 +#endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 367432b1a9..6ab41fff0e 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -681,6 +681,10 @@ #include "esp32/pins_E4D.h" // ESP32 env:esp32 #elif MB(FYSETC_E4) #include "esp32/pins_FYSETC_E4.h" // ESP32 env:FYSETC_E4 +#elif MB(PANDA_ZHU) + #include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA +#elif MB(PANDA_M4) + #include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA // // Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4) diff --git a/ini/esp32.ini b/ini/esp32.ini index fcfa829608..9c0c44db67 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -27,3 +27,13 @@ monitor_speed = 250000 platform = espressif32@2.1.0 extends = env:esp32 board_build.partitions = default_16MB.csv + +[env:PANDA] +platform = espressif32@2.1.0 +extends = env:esp32 +build_flags = ${env:esp32.build_flags} -DUSE_ESP32_EXIO -DUSE_ESP32_TASK_WDT +lib_deps = ${common.lib_deps} + SoftwareSerialEsp32 +board_build.partitions = Marlin/src/HAL/ESP32/esp32.csv +upload_speed = 115200 +monitor_speed = 115200 diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 00ba93aa63..e11aa03560 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -65,8 +65,7 @@ build_flags = ${common_stm32f1.build_flags} extra_scripts = ${common_stm32f1.extra_scripts} pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py -lib_deps = ${common.lib_deps} - SoftwareSerialM +lib_deps = ${common_stm32f1.lib_deps} USBComposite for STM32F1@0.91 custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use debug_tool = stlink @@ -377,7 +376,8 @@ extra_scripts = ${common.extra_scripts} buildroot/share/PlatformIO/scripts/offset_and_rename.py build_flags = ${common_stm32f1.build_flags} -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB -lib_deps = USBComposite for STM32F1@0.91 +lib_deps = ${common_stm32f1.lib_deps} + USBComposite for STM32F1@0.91 lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper [env:STM32F103RC_ZM3E2_USB_maple] From ca7ab6e13f0e8acfb19192378c8f99a58ee3413e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 6 Oct 2021 01:02:35 +0000 Subject: [PATCH 0771/2168] [cron] Bump distribution date (2021-10-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ed42761bd0..ee23017810 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-05" +//#define STRING_DISTRIBUTION_DATE "2021-10-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b35ed5b65a..023b21a1d3 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 "2021-10-05" + #define STRING_DISTRIBUTION_DATE "2021-10-06" #endif /** From e52c30d43a171fe6ce21a83589ac17d467e9a11c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 Oct 2021 21:19:28 -0500 Subject: [PATCH 0772/2168] =?UTF-8?q?=F0=9F=90=9B=20Followup=20to=20F()=20?= =?UTF-8?q?in=20config=5Fline?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to 1dafd1887e --- Marlin/src/gcode/host/M360.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 29b7ae602b..b1b558b033 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -93,7 +93,7 @@ void GcodeSuite::M360() { // #if HAS_CLASSIC_JERK if (planner.max_jerk.x == planner.max_jerk.y) - config_line(F("XY"), planner.max_jerk.x, JERK_STR); + config_line(F("XY"), planner.max_jerk.x, FPSTR(JERK_STR)); else { config_line(X_STR, planner.max_jerk.x, JERK_STR); config_line(Y_STR, planner.max_jerk.y, JERK_STR); @@ -110,15 +110,15 @@ void GcodeSuite::M360() { PGMSTR(UNRET_STR, "RetractionUndo"); PGMSTR(SPEED_STR, "Speed"); // M10 Retract with swap (long) moves - config_line(F("Length"), fwretract.settings.retract_length, RET_STR); - config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); - config_line(F("ZLift"), fwretract.settings.retract_zraise, RET_STR); - config_line(F("LongLength"), fwretract.settings.swap_retract_length, RET_STR); + config_line(F("Length"), fwretract.settings.retract_length, FPSTR(RET_STR)); + config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); + config_line(F("ZLift"), fwretract.settings.retract_zraise, FPSTR(RET_STR)); + config_line(F("LongLength"), fwretract.settings.swap_retract_length, FPSTR(RET_STR)); // M11 Recover (undo) with swap (long) moves - config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); - config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); - config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); - config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); + config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); + config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, FPSTR(UNRET_STR)); + config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, FPSTR(UNRET_STR)); + config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, FPSTR(UNRET_STR)); #endif // From 149cbe795da4828b8df4ef34f5acee7fdd0d2dbb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 4 Oct 2021 22:19:05 -0500 Subject: [PATCH 0773/2168] =?UTF-8?q?=F0=9F=8E=A8=20Tweak=20FORCE=5FINLINE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/shared/Marduino.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h index e7f085a68d..3b5a68a373 100644 --- a/Marlin/src/HAL/shared/Marduino.h +++ b/Marlin/src/HAL/shared/Marduino.h @@ -83,7 +83,7 @@ #endif #ifndef FORCE_INLINE - #define FORCE_INLINE inline __attribute__((always_inline)) + #define FORCE_INLINE __attribute__((always_inline)) inline #endif #include "progmem.h" From 9922410a73fd3285bfba0478ac16f04eeee48b8e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 5 Oct 2021 21:35:31 -0500 Subject: [PATCH 0774/2168] =?UTF-8?q?=F0=9F=94=A8=20Port=20libsdl2=5Fnet?= =?UTF-8?q?=20required=20for=20macOS=20simulator?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.cpp | 5 +++++ ini/native.ini | 11 +++++++---- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index e0d6101ae2..1bfb82622e 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -1100,6 +1100,9 @@ void GcodeSuite::process_next_command() { * G-code "macros" to be called from within other G-code handlers. */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstringop-truncation" + void GcodeSuite::process_subcommands_now(FSTR_P fgcode) { PGM_P pgcode = FTOP(fgcode); char * const saved_cmd = parser.command_ptr; // Save the parser state @@ -1117,6 +1120,8 @@ void GcodeSuite::process_subcommands_now(FSTR_P fgcode) { parser.parse(saved_cmd); // Restore the parser state } +#pragma GCC diagnostic pop + void GcodeSuite::process_subcommands_now(char * gcode) { char * const saved_cmd = parser.command_ptr; // Save the parser state for (;;) { diff --git a/ini/native.ini b/ini/native.ini index 2f38e715ed..981e93f996 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -70,13 +70,16 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} # # Simulator for macOS (MacPorts) # -# sudo port install gcc10 gdb glm libsdl2 freetype +# sudo port install gcc10 gdb glm libsdl2 libsdl2_net freetype # sudo port install ld64 @3_3 +ld64_xcode -# sudo port uninstall ld64 ld64-latest +# # cd /opt/local/bin # sudo rm -f gcc g++ cc -# sudo ln gcc-mp-10 gcc ; sudo ln g++-mp-10 g++ ; sudo ln g++ cc -# cd - +# sudo ln -s gcc-mp-10 gcc ; sudo ln -s g++-mp-10 g++ ; sudo ln -s g++ cc +# This step may be obsolete: +# sudo port uninstall ld64 ld64-latest +# +# cd - # # Use 'sudo port install mesa' to get a if no Xcode is installed. # If Xcode is installed be sure to run `xcode-select --install` first. From f79d1f114c44c9f56cf2ae65203ae88fc2e4f6de Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 7 Oct 2021 09:42:59 +1300 Subject: [PATCH 0775/2168] =?UTF-8?q?=F0=9F=8E=A8=20Define=20Octopus=20all?= =?UTF-8?q?ocated=20endstop=20pins=20(#22882)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 29 +++++++++++++++++-- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index bb77285c01..7ab8012d88 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -37,6 +37,7 @@ // // Servos +// #define SERVO0_PIN PB6 // @@ -56,12 +57,30 @@ #define E2_DIAG_PIN PG14 // E2DET #define E3_DIAG_PIN PG15 // E3DET +// // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PB7 #endif +// +// Check for additional used endstop pins +// +#if HAS_EXTRA_ENDSTOPS + #define _ENDSTOP_IS_ANY(ES) X2_USE_ENDSTOP == ES || Y2_USE_ENDSTOP == ES || Z2_USE_ENDSTOP == ES || Z3_USE_ENDSTOP == ES || Z4_USE_ENDSTOP == ES + #if _ENDSTOP_IS_ANY(_XMIN_) || _ENDSTOP_IS_ANY(_XMAX_) + #define NEEDS_X_MINMAX 1 + #endif + #if _ENDSTOP_IS_ANY(_YMIN_) || _ENDSTOP_IS_ANY(_YMAX_) + #define NEEDS_Y_MINMAX 1 + #endif + #if _ENDSTOP_IS_ANY(_ZMIN_) || _ENDSTOP_IS_ANY(_ZMAX_) + #define NEEDS_Z_MINMAX 1 + #endif + #undef _ENDSTOP_IS_ANY +#endif + // // Limit Switches // @@ -72,7 +91,7 @@ #else #define X_MIN_PIN E0_DIAG_PIN // E0DET #endif -#elif EITHER(X_DUAL_ENDSTOPS, DUAL_X_CARRIAGE) +#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // X-STOP #endif @@ -90,7 +109,7 @@ #else #define Y_MIN_PIN E1_DIAG_PIN // E1DET #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) +#elif NEEDS_Y_MINMAX #ifndef Y_MIN_PIN #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP #endif @@ -108,7 +127,7 @@ #else #define Z_MIN_PIN E2_DIAG_PIN // PWRDET #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) +#elif NEEDS_Z_MINMAX #ifndef Z_MIN_PIN #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP #endif @@ -119,6 +138,10 @@ #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP #endif +#undef NEEDS_X_MINMAX +#undef NEEDS_Y_MINMAX +#undef NEEDS_Z_MINMAX + // // Filament Runout Sensor // From 1f41437052c35a9091e057b843533d5695e8676e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 7 Oct 2021 01:03:32 +0000 Subject: [PATCH 0776/2168] [cron] Bump distribution date (2021-10-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ee23017810..e442e8906e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-06" +//#define STRING_DISTRIBUTION_DATE "2021-10-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 023b21a1d3..4a3126ba19 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 "2021-10-06" + #define STRING_DISTRIBUTION_DATE "2021-10-07" #endif /** From 1ec399c6ab2f51f7d9c491c098c001679d0ad0da Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 8 Oct 2021 01:05:32 +0000 Subject: [PATCH 0777/2168] [cron] Bump distribution date (2021-10-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e442e8906e..abc759ad07 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-07" +//#define STRING_DISTRIBUTION_DATE "2021-10-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4a3126ba19..bc719fcbcd 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 "2021-10-07" + #define STRING_DISTRIBUTION_DATE "2021-10-08" #endif /** From bd6a1a2898909fff228febcb38538e47a2416634 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 9 Oct 2021 00:59:22 +0000 Subject: [PATCH 0778/2168] [cron] Bump distribution date (2021-10-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index abc759ad07..61faf18354 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-08" +//#define STRING_DISTRIBUTION_DATE "2021-10-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bc719fcbcd..264f24e3bc 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 "2021-10-08" + #define STRING_DISTRIBUTION_DATE "2021-10-09" #endif /** From 13bb2393e13148732861c690d523f07972f4abd8 Mon Sep 17 00:00:00 2001 From: Pyro-Fox <36782094+Pyro-Fox@users.noreply.github.com> Date: Sat, 9 Oct 2021 15:09:50 -0700 Subject: [PATCH 0779/2168] =?UTF-8?q?=F0=9F=90=9B=20LCD=20string=20followu?= =?UTF-8?q?p=20(#22892)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 178d466478..79193fbef3 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -179,7 +179,7 @@ static void _lcd_level_bed_corners_get_next_position() { // Display # of good points found vs total needed if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); - lcd_put_u8str_(GET_TEXT_F(MSG_BED_TRAMMING_GOOD_POINTS)); + lcd_put_u8str(GET_TEXT_F(MSG_BED_TRAMMING_GOOD_POINTS)); IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, cy)); lcd_put_u8str(GOOD_POINTS_TO_STR(good_points)); lcd_put_wchar('/'); From 886c59dc1045787042fa3b824bdc56655d10d655 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 10 Oct 2021 01:05:24 +0200 Subject: [PATCH 0780/2168] =?UTF-8?q?=F0=9F=90=9B=20Queue=20string=20follo?= =?UTF-8?q?wup=20(#22900)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/queue.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index c5562da3aa..2e3e26d179 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -148,6 +148,12 @@ public: */ static bool enqueue_one(FSTR_P const fgcode); + /** + * Enqueue with Serial Echo + * Return true on success + */ + static bool enqueue_one(const char *cmd); + /** * Enqueue from program memory and return only when commands are actually enqueued */ @@ -253,12 +259,6 @@ private: // Process the next "immediate" command (SRAM) static bool process_injected_command(); - /** - * Enqueue with Serial Echo - * Return true on success - */ - static bool enqueue_one(const char *cmd); - static void gcode_line_error(FSTR_P const ferr, const serial_index_t serial_ind); friend class GcodeSuite; From 33809ae000da2cf1a5a2b0641b235a6bb68d245a Mon Sep 17 00:00:00 2001 From: Minims Date: Sun, 10 Oct 2021 01:10:21 +0200 Subject: [PATCH 0781/2168] =?UTF-8?q?=F0=9F=A9=B9=20Adjust=20GTR=201.0=20S?= =?UTF-8?q?T7920=20display=20delay=20(#22904)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 0715380e22..95f74efe84 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -484,8 +484,8 @@ // Alter timing for graphical display #if IS_U8GLIB_ST7920 - #define BOARD_ST7920_DELAY_1 96 - #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 90 #define BOARD_ST7920_DELAY_3 600 #endif From b3fd0a50505455bbd4d0487b202ab75797a79421 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Sat, 9 Oct 2021 19:13:19 -0400 Subject: [PATCH 0782/2168] =?UTF-8?q?=F0=9F=90=9B=20Fix=20IDEX=20Duplicati?= =?UTF-8?q?on=20Mode=20Positioning=20(#22914)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixing #22538 --- Marlin/src/module/motion.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 1f13bd22ee..f5dd5d34c9 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1194,6 +1194,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { case DXC_DUPLICATION_MODE: if (active_extruder == 0) { // Restore planner to parked head (T1) X position + float x0_pos = current_position.x; xyze_pos_t pos_now = current_position; pos_now.x = inactive_extruder_x; planner.set_position_mm(pos_now); @@ -1201,7 +1202,9 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // Keep the same X or add the duplication X offset xyze_pos_t new_pos = pos_now; if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) - new_pos.x += duplicate_extruder_x_offset; + new_pos.x = x0_pos + duplicate_extruder_x_offset; + else + new_pos.x = _MIN(X_BED_SIZE - x0_pos, X_MAX_POS); // Move duplicate extruder into the correct position if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); From 0c86cc89f0c74e58949f8c5a0351d57dffab8019 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 10 Oct 2021 01:03:22 +0000 Subject: [PATCH 0783/2168] [cron] Bump distribution date (2021-10-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 61faf18354..68ad186971 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-09" +//#define STRING_DISTRIBUTION_DATE "2021-10-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 264f24e3bc..95e291e598 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 "2021-10-09" + #define STRING_DISTRIBUTION_DATE "2021-10-10" #endif /** From 90fa48ffd565ae28e8a0bfcf2d5f8b5a2de2e558 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 11 Oct 2021 01:03:10 +0000 Subject: [PATCH 0784/2168] [cron] Bump distribution date (2021-10-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 68ad186971..43788a7179 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-10-10" +//#define STRING_DISTRIBUTION_DATE "2021-10-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 95e291e598..1e0c68a971 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 "2021-10-10" + #define STRING_DISTRIBUTION_DATE "2021-10-11" #endif /** From ad14b5052cd60b6ab79bb236529241696266bf30 Mon Sep 17 00:00:00 2001 From: Stuart Pittaway <1201909+stuartpittaway@users.noreply.github.com> Date: Mon, 11 Oct 2021 23:42:29 +0100 Subject: [PATCH 0785/2168] =?UTF-8?q?=E2=9C=A8=20M261=20S=20I2C=20output?= =?UTF-8?q?=20format=20(#22890)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/feature/twibus.cpp | 61 +++++++++++++++++++--- Marlin/src/feature/twibus.h | 10 ++-- Marlin/src/gcode/feature/i2c/M260_M261.cpp | 7 +-- Marlin/src/libs/hex_print.h | 2 +- 4 files changed, 64 insertions(+), 16 deletions(-) diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 55e4da75cf..0e23b48a40 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -28,11 +28,17 @@ #include +#include "../libs/hex_print.h" + TWIBus i2c; TWIBus::TWIBus() { #if I2C_SLAVE_ADDRESS == 0 - Wire.begin(); // No address joins the BUS as the master + Wire.begin( // No address joins the BUS as the master + #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) + pin_t(I2C_SDA_PIN), pin_t(I2C_SCL_PIN) + #endif + ); #else Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave #endif @@ -88,14 +94,53 @@ void TWIBus::echoprefix(uint8_t bytes, FSTR_P const pref, uint8_t adr) { } // static -void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr) { - echoprefix(bytes, pref, adr); - while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); +void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr, const uint8_t style/*=0*/) { + union TwoBytesToInt16 { uint8_t bytes[2]; int16_t integervalue; }; + TwoBytesToInt16 ConversionUnion; + + echoprefix(bytes, pref, adr); + + while (bytes-- && Wire.available()) { + int value = Wire.read(); + switch (style) { + + // Style 1, HEX DUMP + case 1: + SERIAL_CHAR(hex_nybble((value & 0xF0) >> 4)); + SERIAL_CHAR(hex_nybble(value & 0x0F)); + if (bytes) SERIAL_CHAR(' '); + break; + + // Style 2, signed two byte integer (int16) + case 2: + if (bytes == 1) + ConversionUnion.bytes[1] = (uint8_t)value; + else if (bytes == 0) { + ConversionUnion.bytes[0] = (uint8_t)value; + // Output value in base 10 (standard decimal) + SERIAL_ECHO(ConversionUnion.integervalue); + } + break; + + // Style 3, unsigned byte, base 10 (uint8) + case 3: + SERIAL_ECHO(value); + if (bytes) SERIAL_CHAR(' '); + break; + + // Default style (zero), raw serial output + default: + // This can cause issues with some serial consoles, Pronterface is an example where things go wrong + SERIAL_CHAR(value); + break; + } + } + SERIAL_EOL(); } -void TWIBus::echobuffer(FSTR_P const pref, uint8_t adr) { - echoprefix(buffer_s, pref, adr); +void TWIBus::echobuffer(FSTR_P const prefix, uint8_t adr) { + echoprefix(buffer_s, prefix, adr); LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } @@ -114,11 +159,11 @@ bool TWIBus::request(const uint8_t bytes) { return true; } -void TWIBus::relay(const uint8_t bytes) { +void TWIBus::relay(const uint8_t bytes, const uint8_t style/*=0*/) { debug(F("relay"), bytes); if (request(bytes)) - echodata(bytes, F("i2c-reply"), addr); + echodata(bytes, F("i2c-reply"), addr, style); } uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 2a8a7fef6a..d2c7270303 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -142,7 +142,7 @@ class TWIBus { * * @param bytes the number of bytes to request */ - static void echoprefix(uint8_t bytes, FSTR_P prefix, uint8_t adr); + static void echoprefix(uint8_t bytes, FSTR_P const prefix, uint8_t adr); /** * @brief Echo data on the bus to serial @@ -150,8 +150,9 @@ class TWIBus { * to serial in a parser-friendly format. * * @param bytes the number of bytes to request + * @param style Output format for the bytes, 0 = Raw byte [default], 1 = Hex characters, 2 = uint16_t */ - static void echodata(uint8_t bytes, FSTR_P prefix, uint8_t adr); + static void echodata(uint8_t bytes, FSTR_P const prefix, uint8_t adr, const uint8_t style=0); /** * @brief Echo data in the buffer to serial @@ -160,7 +161,7 @@ class TWIBus { * * @param bytes the number of bytes to request */ - void echobuffer(FSTR_P prefix, uint8_t adr); + void echobuffer(FSTR_P const prefix, uint8_t adr); /** * @brief Request data from the slave device and wait. @@ -192,10 +193,11 @@ class TWIBus { * @brief Request data from the slave device, echo to serial. * @details Request a number of bytes from a slave device and output * the returned data to serial in a parser-friendly format. + * @style Output format for the bytes, 0 = raw byte [default], 1 = Hex characters, 2 = uint16_t * * @param bytes the number of bytes to request */ - void relay(const uint8_t bytes); + void relay(const uint8_t bytes, const uint8_t style=0); #if I2C_SLAVE_ADDRESS > 0 diff --git a/Marlin/src/gcode/feature/i2c/M260_M261.cpp b/Marlin/src/gcode/feature/i2c/M260_M261.cpp index 438d1527f5..e978fb5048 100644 --- a/Marlin/src/gcode/feature/i2c/M260_M261.cpp +++ b/Marlin/src/gcode/feature/i2c/M260_M261.cpp @@ -60,15 +60,16 @@ void GcodeSuite::M260() { /** * M261: Request X bytes from I2C slave device * - * Usage: M261 A B + * Usage: M261 A B S